g2o
|
#include <base_edge.h>
Public Types | |
typedef E | Measurement |
typedef Eigen::Matrix< double, D, 1, Eigen::ColMajor > | ErrorVector |
typedef Eigen::Matrix< double, D, D, Eigen::ColMajor > | InformationType |
Public Member Functions | |
BaseEdge () | |
virtual | ~BaseEdge () |
virtual double | chi2 () const |
computes the chi2 based on the cached error value, only valid after computeError has been called. More... | |
virtual const double * | errorData () const |
returns the error vector cached after calling the computeError; More... | |
virtual double * | errorData () |
const ErrorVector & | error () const |
ErrorVector & | error () |
EIGEN_STRONG_INLINE const InformationType & | information () const |
information matrix of the constraint More... | |
EIGEN_STRONG_INLINE InformationType & | information () |
EIGEN_STRONG_INLINE void | setInformation (const InformationType &information) |
virtual const double * | informationData () const |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXD> More... | |
virtual double * | informationData () |
EIGEN_STRONG_INLINE const Measurement & | measurement () const |
accessor functions for the measurement represented by the edge More... | |
virtual void | setMeasurement (const Measurement &m) |
virtual int | rank () const |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *) |
Public Member Functions inherited from g2o::OptimizableGraph::Edge | |
Edge () | |
virtual | ~Edge () |
virtual Edge * | clone () const |
virtual bool | allVerticesFixed () const =0 |
virtual void | computeError ()=0 |
virtual bool | setMeasurementData (const double *m) |
virtual bool | getMeasurementData (double *m) const |
virtual int | measurementDimension () const |
virtual bool | setMeasurementFromState () |
RobustKernel * | robustKernel () const |
if NOT NULL, error of this edge will be robustifed with the kernel More... | |
void | setRobustKernel (RobustKernel *ptr) |
virtual void | constructQuadraticForm ()=0 |
virtual void | mapHessianMemory (double *d, int i, int j, bool rowMajor)=0 |
virtual void | linearizeOplus (JacobianWorkspace &jacobianWorkspace)=0 |
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
int | level () const |
returns the level of the edge More... | |
void | setLevel (int l) |
sets the level of the edge More... | |
int | dimension () const |
returns the dimensions of the error function More... | |
G2O_ATTRIBUTE_DEPRECATED (virtual Vertex *createFrom()) | |
G2O_ATTRIBUTE_DEPRECATED (virtual Vertex *createTo()) | |
virtual Vertex * | createVertex (int) |
virtual bool | read (std::istream &is)=0 |
read the vertex from a stream, i.e., the internal state of the vertex More... | |
virtual bool | write (std::ostream &os) const =0 |
write the vertex to a stream More... | |
long long | internalId () const |
the internal ID of the edge More... | |
OptimizableGraph * | graph () |
const OptimizableGraph * | graph () const |
bool | setParameterId (int argNum, int paramId) |
const Parameter * | parameter (int argNo) const |
size_t | numParameters () const |
void | resizeParameters (size_t newSize) |
Public Member Functions inherited from g2o::HyperGraph::Edge | |
Edge (int id=InvalidId) | |
creates and empty edge with no vertices More... | |
virtual void | resize (size_t size) |
const VertexContainer & | vertices () const |
VertexContainer & | vertices () |
const Vertex * | vertex (size_t i) const |
Vertex * | vertex (size_t i) |
void | setVertex (size_t i, Vertex *v) |
int | id () const |
void | setId (int id) |
virtual HyperGraphElementType | elementType () const |
int | numUndefinedVertices () const |
Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement | |
virtual | ~HyperGraphElement () |
HyperGraphElement * | clone () const |
Public Member Functions inherited from g2o::HyperGraph::DataContainer | |
DataContainer () | |
virtual | ~DataContainer () |
const Data * | userData () const |
the user data associated with this vertex More... | |
Data * | userData () |
void | setUserData (Data *obs) |
void | addUserData (Data *obs) |
Static Public Attributes | |
static const int | Dimension = D |
Protected Member Functions | |
InformationType | robustInformation (const Vector3D &rho) |
Protected Member Functions inherited from g2o::OptimizableGraph::Edge | |
template<typename ParameterType > | |
bool | installParameter (ParameterType *&p, size_t argNo, int paramId=-1) |
template<typename CacheType > | |
void | resolveCache (CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters) |
bool | resolveParameters () |
virtual bool | resolveCaches () |
Protected Attributes | |
Measurement | _measurement |
InformationType | _information |
ErrorVector | _error |
Protected Attributes inherited from g2o::OptimizableGraph::Edge | |
int | _dimension |
int | _level |
RobustKernel * | _robustKernel |
long long | _internalId |
std::vector< int > | _cacheIds |
std::vector< std::string > | _parameterTypes |
std::vector< Parameter ** > | _parameters |
std::vector< int > | _parameterIds |
Protected Attributes inherited from g2o::HyperGraph::Edge | |
VertexContainer | _vertices |
int | _id |
unique id More... | |
Protected Attributes inherited from g2o::HyperGraph::DataContainer | |
Data * | _userData |
Definition at line 40 of file base_edge.h.
typedef Eigen::Matrix<double, D, 1, Eigen::ColMajor> g2o::BaseEdge< D, E >::ErrorVector |
Definition at line 46 of file base_edge.h.
typedef Eigen::Matrix<double, D, D, Eigen::ColMajor> g2o::BaseEdge< D, E >::InformationType |
Definition at line 47 of file base_edge.h.
typedef E g2o::BaseEdge< D, E >::Measurement |
Definition at line 45 of file base_edge.h.
|
inline |
Definition at line 49 of file base_edge.h.
|
inlinevirtual |
Definition at line 54 of file base_edge.h.
|
inlinevirtual |
computes the chi2 based on the cached error value, only valid after computeError has been called.
Implements g2o::OptimizableGraph::Edge.
Reimplemented in g2o::OnlineEdgeSE2, and g2o::OnlineEdgeSE3.
Definition at line 56 of file base_edge.h.
Referenced by main().
|
inline |
Definition at line 63 of file base_edge.h.
|
inline |
Definition at line 64 of file base_edge.h.
|
inlinevirtual |
returns the error vector cached after calling the computeError;
Implements g2o::OptimizableGraph::Edge.
Definition at line 61 of file base_edge.h.
|
inlinevirtual |
|
inline |
information matrix of the constraint
Definition at line 67 of file base_edge.h.
Referenced by g2o::addOdometryCalibLinksDifferential(), g2o::BaseEdge< D, Eigen::Vector2d >::chi2(), g2o::BaseEdge<-1, E >::chi2(), main(), g2o::UnarySensor< Robot3D, EdgeSE3Prior >::mkEdge(), g2o::BinarySensor< Robot2D, EdgeSE2PointXY, WorldObjectPointXY >::mkEdge(), g2o::Gm2dlIO::readGm2dl(), g2o::BaseEdge< D, Eigen::Vector2d >::setInformation(), g2o::BaseEdge<-1, E >::setInformation(), g2o::SolverSLAM2DLinear::solveOrientation(), and g2o::Gm2dlIO::writeGm2dl().
|
inline |
Definition at line 68 of file base_edge.h.
|
inlinevirtual |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXD>
Implements g2o::OptimizableGraph::Edge.
Definition at line 71 of file base_edge.h.
|
inlinevirtual |
|
inlinevirtual |
set the estimate of the to vertex, based on the estimate of the from vertices in the edge.
Implements g2o::OptimizableGraph::Edge.
Reimplemented in g2o::EdgeSBAScale, g2o::EdgeSBACam, TargetOdometry3DEdge, g2o::EdgeSim3, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Line2D, g2o::EdgeSE2, g2o::EdgeSE2Segment2D, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::deprecated::EdgeSE3Offset, g2o::EdgeSE3PointXYZDisparity, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2Offset, g2o::EdgeSE2PointXYOffset, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE3Prior, g2o::deprecated::EdgeSE3Prior, g2o::BaseUnaryEdge< D, E, VertexXi >, g2o::BaseUnaryEdge< 6, Isometry3D, VertexSE3 >, g2o::BaseUnaryEdge< 3, Eigen::Vector3d, VertexPosition3D >, g2o::BaseUnaryEdge< 1, Eigen::Vector2d, VertexCircle >, g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >, g2o::BaseUnaryEdge< 2, Vector2D, VertexSE2 >, g2o::BaseUnaryEdge< 3, Eigen::Vector3d, VertexPositionVelocity3D >, g2o::BaseUnaryEdge< 1, Eigen::Vector2d, VertexParams >, g2o::BaseUnaryEdge< 6, SE3Quat, VertexSE3 >, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2PointXY, g2o::EdgeSE2Prior, g2o::EdgeSE2SensorCalib, g2o::OnlineEdgeSE2, g2o::OnlineEdgeSE3, g2o::EdgeSE3Offset, g2o::EdgeSE2PointXYCalib, g2o::EdgeSE3, g2o::EdgeSE2LotsOfXY, g2o::EdgeSE3LotsOfXYZ, and g2o::EdgeSE2TwoPointsXY.
Definition at line 80 of file base_edge.h.
|
inline |
accessor functions for the measurement represented by the edge
Definition at line 75 of file base_edge.h.
Referenced by g2o::SensorOdometry2D::addNoise(), g2o::SensorPointXYBearing::addNoise(), g2o::SensorOdometry3D::addNoise(), g2o::SensorPointXY::addNoise(), g2o::SensorPose2D::addNoise(), g2o::SensorPose3DOffset::addNoise(), g2o::SensorSegment2DPointLine::addNoise(), g2o::SensorPose3D::addNoise(), g2o::SensorPointXYOffset::addNoise(), g2o::SensorSegment2D::addNoise(), g2o::SensorSegment2DLine::addNoise(), g2o::SensorPointXYZDepth::addNoise(), g2o::SensorSE3Prior::addNoise(), g2o::SensorPointXYZ::addNoise(), g2o::SensorPointXYZDisparity::addNoise(), g2o::Edge_V_V_GICP::Edge_V_V_GICP(), main(), Robot::move(), g2o::EdgeSE2PointXYBearingWriteGnuplotAction::operator()(), g2o::EdgeSE2PointXYWriteGnuplotAction::operator()(), g2o::EdgeSE2WriteGnuplotAction::operator()(), g2o::ThetaTreeAction::perform(), g2o::SolverSLAM2DLinear::solveOrientation(), g2o::EdgeSE3PlaneSensorCalib::write(), and g2o::Gm2dlIO::writeGm2dl().
|
inlinevirtual |
Definition at line 78 of file base_edge.h.
|
inlineprotected |
calculate the robust information matrix by updating the information matrix of the error
Definition at line 94 of file base_edge.h.
|
inline |
Definition at line 69 of file base_edge.h.
Referenced by g2o::G2oSlamInterface::addEdge(), g2o::SensorOdometry2D::addNoise(), g2o::SensorPointXYBearing::addNoise(), g2o::SensorOdometry3D::addNoise(), g2o::SensorPointXY::addNoise(), g2o::SensorPose2D::addNoise(), g2o::SensorPose3DOffset::addNoise(), g2o::SensorSegment2DLine::addNoise(), g2o::SensorSegment2DPointLine::addNoise(), g2o::SensorPose3D::addNoise(), g2o::SensorPointXYOffset::addNoise(), g2o::SensorSegment2D::addNoise(), g2o::SensorSE3Prior::addNoise(), g2o::SensorPointXYZDepth::addNoise(), g2o::SensorPointXYZ::addNoise(), g2o::SensorPointXYZDisparity::addNoise(), main(), Robot::move(), and PlaneSensor::sense().
|
inlinevirtual |
Reimplemented in g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::deprecated::EdgeSE3, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeSE2Prior, g2o::EdgeSE3PointXYZDisparity, g2o::EdgeSE3PlaneSensorCalib, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2PointXYOffset, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE2SensorCalib, g2o::EdgeSE2, g2o::EdgeSE2Offset, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE3Prior, g2o::EdgeSE3Line3D, g2o::deprecated::EdgeSE3Prior, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgeLine2D, g2o::EdgePointXYZ, and g2o::EdgeSE3.
Definition at line 76 of file base_edge.h.
Referenced by g2o::SensorPointXYBearing::addNoise(), g2o::SensorPointXY::addNoise(), g2o::SensorSegment2D::addNoise(), g2o::SensorSegment2DLine::addNoise(), g2o::SensorSegment2DPointLine::addNoise(), g2o::addOdometryCalibLinksDifferential(), and main().
|
protected |
Definition at line 89 of file base_edge.h.
Referenced by g2o::BaseEdge< D, Eigen::Vector2d >::chi2(), g2o::BaseEdge<-1, E >::chi2(), g2o::BaseEdge< D, Eigen::Vector2d >::error(), g2o::BaseEdge<-1, E >::error(), g2o::BaseEdge< D, Eigen::Vector2d >::errorData(), and g2o::BaseEdge<-1, E >::errorData().
|
protected |
Definition at line 88 of file base_edge.h.
Referenced by g2o::BaseEdge< D, Eigen::Vector2d >::information(), g2o::BaseEdge<-1, E >::information(), g2o::BaseEdge< D, Eigen::Vector2d >::informationData(), g2o::BaseEdge<-1, E >::informationData(), g2o::BaseEdge< D, Eigen::Vector2d >::robustInformation(), g2o::BaseEdge<-1, E >::robustInformation(), g2o::BaseEdge< D, Eigen::Vector2d >::setInformation(), and g2o::BaseEdge<-1, E >::setInformation().
|
protected |
Definition at line 87 of file base_edge.h.
Referenced by g2o::BaseEdge< D, Eigen::Vector2d >::measurement(), g2o::BaseEdge<-1, E >::measurement(), g2o::BaseEdge< D, Eigen::Vector2d >::setMeasurement(), and g2o::BaseEdge<-1, E >::setMeasurement().
|
static |
Definition at line 44 of file base_edge.h.