g2o
Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
g2o::OptimizableGraph::Edge Class Referenceabstract

#include <optimizable_graph.h>

Inheritance diagram for g2o::OptimizableGraph::Edge:
Inheritance graph
[legend]
Collaboration diagram for g2o::OptimizableGraph::Edge:
Collaboration graph
[legend]

Public Member Functions

 Edge ()
 
virtual ~Edge ()
 
virtual Edgeclone () 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 ()
 
RobustKernelrobustKernel () const
 if NOT NULL, error of this edge will be robustifed with the kernel More...
 
void setRobustKernel (RobustKernel *ptr)
 
virtual const double * errorData () const =0
 returns the error vector cached after calling the computeError; More...
 
virtual double * errorData ()=0
 
virtual const double * informationData () const =0
 returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXD> More...
 
virtual double * informationData ()=0
 
virtual double chi2 () const =0
 computes the chi2 based on the cached error value, only valid after computeError has been called. More...
 
virtual void constructQuadraticForm ()=0
 
virtual void mapHessianMemory (double *d, int i, int j, bool rowMajor)=0
 
virtual void linearizeOplus (JacobianWorkspace &jacobianWorkspace)=0
 
virtual void initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)=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 VertexcreateVertex (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...
 
OptimizableGraphgraph ()
 
const OptimizableGraphgraph () const
 
bool setParameterId (int argNum, int paramId)
 
const Parameterparameter (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 VertexContainervertices () const
 
VertexContainervertices ()
 
const Vertexvertex (size_t i) const
 
Vertexvertex (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 ()
 
HyperGraphElementclone () const
 
- Public Member Functions inherited from g2o::HyperGraph::DataContainer
 DataContainer ()
 
virtual ~DataContainer ()
 
const DatauserData () const
 the user data associated with this vertex More...
 
DatauserData ()
 
void setUserData (Data *obs)
 
void addUserData (Data *obs)
 

Protected Member Functions

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 &parameters)
 
bool resolveParameters ()
 
virtual bool resolveCaches ()
 

Protected Attributes

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
 

Friends

struct OptimizableGraph
 

Detailed Description

Definition at line 349 of file optimizable_graph.h.

Constructor & Destructor Documentation

g2o::OptimizableGraph::Edge::Edge ( )

Definition at line 120 of file optimizable_graph.cpp.

120  :
122  _dimension(-1), _level(0), _robustKernel(0)
123  {
124  }
class G2O_CORE_API Edge
Definition: hyper_graph.h:79
g2o::OptimizableGraph::Edge::~Edge ( )
virtual

Reimplemented from g2o::HyperGraph::Edge.

Definition at line 126 of file optimizable_graph.cpp.

References _robustKernel.

127  {
128  delete _robustKernel;
129  }

Member Function Documentation

virtual bool g2o::OptimizableGraph::Edge::allVerticesFixed ( ) const
pure virtual

Implemented in g2o::BaseMultiEdge<-1, E >, g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 6, Isometry3D >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 4, Vector4D >, g2o::BaseMultiEdge< 2, Vector2D >, g2o::BaseMultiEdge< 3, Plane3D >, g2o::BaseMultiEdge<-1, VectorXD >, g2o::BaseMultiEdge< 3, VelocityMeasurement >, g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 1, double, VertexLine2D, VertexPointXY >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 6, Eigen::Vector3d, VertexPositionVelocity3D, VertexPositionVelocity3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexCameraBAL, VertexPointBAL >, g2o::BaseBinaryEdge< 2, Vector2D, VertexPointXY, VertexPointXY >, g2o::BaseBinaryEdge< 4, Vector4D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Line2D, VertexLine2D, VertexLine2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, Isometry3D, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 3, Eigen::Vector3d, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 4, Vector4D, VertexPlane, VertexPlane >, g2o::BaseBinaryEdge< 2, Line2D, VertexSE2, VertexLine2D >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 7, Vector7d, VertexSE3, VertexLine3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, Vector3D, VertexPointXYZ, VertexPointXYZ >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexBaseline >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexOdomDifferentialParams >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, Vector6d, VertexLine3D, VertexLine3D >, 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 >, and g2o::BaseUnaryEdge< 6, SE3Quat, VertexSE3 >.

Referenced by g2o::SparseOptimizer::initializeOptimization(), and g2o::SparseOptimizer::updateInitialization().

virtual double g2o::OptimizableGraph::Edge::chi2 ( ) const
pure virtual
OptimizableGraph::Edge * g2o::OptimizableGraph::Edge::clone ( ) const
virtual

Definition at line 212 of file optimizable_graph.cpp.

Referenced by g2o::OptimizableGraph::addGraph().

213  {
214  // TODO
215  return 0;
216  }
virtual void g2o::OptimizableGraph::Edge::computeError ( )
pure virtual

Implemented in g2o::Edge_XYZ_VSC, g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::EdgeProjectP2MC_Intrinsics, EdgeObservationBAL, g2o::EdgeProjectP2SC, g2o::EdgeProjectXYZ2UVU, g2o::Edge_V_V_GICP, GPSObservationEdgePositionVelocity3D, g2o::EdgeProjectP2MC, g2o::EdgeProjectPSI2UV, g2o::EdgeProjectXYZ2UV, TargetOdometry3DEdge, g2o::EdgeSim3ProjectXYZ, g2o::EdgeSE3Expmap, EdgePointOnCircle, EdgePointOnCurve, g2o::EdgeSim3, GPSObservationPosition3DEdge, EdgeCalib, g2o::EdgeSE2XYPrior, g2o::EdgeSE2PureCalib, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Segment2DPointLine, g2o::EdgeSE3PointXYZDisparity, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2PointXYOffset, g2o::EdgeSE3Line3D, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE2Offset, g2o::EdgeSE2Segment2DLine, g2o::EdgeSE3Offset, g2o::EdgeSE3PointXYZ, g2o::tutorial::EdgeSE2PointXY, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE2Segment2D, g2o::EdgeSE3Prior, g2o::deprecated::EdgeSE3Prior, g2o::tutorial::EdgeSE2, g2o::EdgeSE3Calib, g2o::EdgeSE2, g2o::EdgeSE2PointXYCalib, g2o::EdgeSE3PlaneSensorCalib, g2o::EdgeSE2OdomDifferentialCalib, g2o::EdgeSE2SensorCalib, g2o::EdgeSE2Prior, g2o::EdgeLine2DPointXY, g2o::EdgeSE2Line2D, g2o::EdgeSE2PointXY, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeLine2D, g2o::EdgePointXYZ, g2o::EdgeSE2LotsOfXY, g2o::EdgeSE3LotsOfXYZ, g2o::EdgeSE3, and g2o::EdgeSE2TwoPointsXY.

Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizer::computeActiveErrors(), gnudump_edges(), gnudump_features(), g2o::EdgeLabeler::labelEdge(), main(), InvChi2CostFunction::operator()(), g2o::SparseOptimizerOnline::optimize(), and g2o::SparseOptimizerIncremental::updateInitialization().

virtual void g2o::OptimizableGraph::Edge::constructQuadraticForm ( )
pure virtual

Linearizes the constraint in the edge. Makes side effect on the vertices of the graph by changing the parameter vector b and the hessian blocks ii and jj. The off diagoinal block is accesed via _hessian.

Implemented in g2o::BaseMultiEdge<-1, E >, g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 1, double, VertexLine2D, VertexPointXY >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 6, Eigen::Vector3d, VertexPositionVelocity3D, VertexPositionVelocity3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexCameraBAL, VertexPointBAL >, g2o::BaseBinaryEdge< 2, Vector2D, VertexPointXY, VertexPointXY >, g2o::BaseBinaryEdge< 4, Vector4D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Line2D, VertexLine2D, VertexLine2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, Isometry3D, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 3, Eigen::Vector3d, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 4, Vector4D, VertexPlane, VertexPlane >, g2o::BaseBinaryEdge< 2, Line2D, VertexSE2, VertexLine2D >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 7, Vector7d, VertexSE3, VertexLine3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, Vector3D, VertexPointXYZ, VertexPointXYZ >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexBaseline >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexOdomDifferentialParams >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, Vector6d, VertexLine3D, VertexLine3D >, g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 6, Isometry3D >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 4, Vector4D >, g2o::BaseMultiEdge< 2, Vector2D >, g2o::BaseMultiEdge< 3, Plane3D >, g2o::BaseMultiEdge<-1, VectorXD >, g2o::BaseMultiEdge< 3, VelocityMeasurement >, 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 >, and g2o::BaseUnaryEdge< 6, SE3Quat, VertexSE3 >.

Referenced by g2o::BlockSolver< Traits >::buildSystem(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizerOnline::optimize(), and g2o::SparseOptimizerIncremental::updateInitialization().

virtual Vertex* g2o::OptimizableGraph::Edge::createVertex ( int  )
inlinevirtual

Reimplemented in g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 1, double, VertexLine2D, VertexPointXY >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 6, Eigen::Vector3d, VertexPositionVelocity3D, VertexPositionVelocity3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexCameraBAL, VertexPointBAL >, g2o::BaseBinaryEdge< 2, Vector2D, VertexPointXY, VertexPointXY >, g2o::BaseBinaryEdge< 4, Vector4D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Line2D, VertexLine2D, VertexLine2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, Isometry3D, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 3, Eigen::Vector3d, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 4, Vector4D, VertexPlane, VertexPlane >, g2o::BaseBinaryEdge< 2, Line2D, VertexSE2, VertexLine2D >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 7, Vector7d, VertexSE3, VertexLine3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, Vector3D, VertexPointXYZ, VertexPointXYZ >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexBaseline >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexOdomDifferentialParams >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, Vector6d, VertexLine3D, VertexLine3D >, 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 >, and g2o::BaseUnaryEdge< 6, SE3Quat, VertexSE3 >.

Definition at line 444 of file optimizable_graph.h.

Referenced by g2o::OptimizableGraph::setFixed().

444 {return 0;}
int g2o::OptimizableGraph::Edge::dimension ( ) const
inline
virtual const double* g2o::OptimizableGraph::Edge::errorData ( ) const
pure virtual
virtual double* g2o::OptimizableGraph::Edge::errorData ( )
pure virtual
g2o::OptimizableGraph::Edge::G2O_ATTRIBUTE_DEPRECATED ( virtual Vertex createFrom())
inline

Definition at line 442 of file optimizable_graph.h.

442 {return 0;}
g2o::OptimizableGraph::Edge::G2O_ATTRIBUTE_DEPRECATED ( virtual Vertex createTo())
inline

Definition at line 443 of file optimizable_graph.h.

443 {return 0;}
bool g2o::OptimizableGraph::Edge::getMeasurementData ( double *  m) const
virtual
OptimizableGraph * g2o::OptimizableGraph::Edge::graph ( )

Definition at line 131 of file optimizable_graph.cpp.

References g2o::HyperGraph::Edge::_vertices, and g2o::OptimizableGraph::Vertex::graph().

Referenced by resolveParameters().

131  {
132  if (! _vertices.size())
133  return 0;
135  if (!v)
136  return 0;
137  return v->graph();
138  }
class G2O_CORE_API Vertex
VertexContainer _vertices
Definition: hyper_graph.h:202
const OptimizableGraph * g2o::OptimizableGraph::Edge::graph ( ) const

Definition at line 140 of file optimizable_graph.cpp.

References g2o::HyperGraph::Edge::_vertices, and g2o::OptimizableGraph::Vertex::graph().

140  {
141  if (! _vertices.size())
142  return 0;
144  if (!v)
145  return 0;
146  return v->graph();
147  }
class G2O_CORE_API Vertex
VertexContainer _vertices
Definition: hyper_graph.h:202
virtual const double* g2o::OptimizableGraph::Edge::informationData ( ) const
pure virtual
virtual double* g2o::OptimizableGraph::Edge::informationData ( )
pure virtual
virtual void g2o::OptimizableGraph::Edge::initialEstimate ( const OptimizableGraph::VertexSet from,
OptimizableGraph::Vertex to 
)
pure virtual

set the estimate of the to vertex, based on the estimate of the from vertices in the edge.

Implemented in g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::BaseEdge<-1, E >, 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::BaseEdge< D, E >, g2o::deprecated::EdgeSE3Prior, g2o::BaseEdge< D, Vector2D >, g2o::BaseEdge< D, Eigen::Vector3d >, g2o::BaseEdge< D, Vector3D >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Isometry3D >, g2o::BaseEdge< D, Vector4D >, g2o::BaseEdge< D, Plane3D >, g2o::BaseEdge< D, Vector6d >, g2o::BaseEdge< D, Line2D >, g2o::BaseEdge< D, Vector7d >, g2o::BaseEdge< D, OdomAndLaserMotion >, g2o::BaseEdge< D, VectorXD >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, VelocityMeasurement >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, g2o::BaseEdge< D, Eigen::Vector2d >, 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.

Referenced by g2o::SparseOptimizer::computeInitialGuess(), g2o::EstimatePropagator::PropagateAction::operator()(), and g2o::OptimizableGraph::setFixed().

virtual double g2o::OptimizableGraph::Edge::initialEstimatePossible ( const OptimizableGraph::VertexSet from,
OptimizableGraph::Vertex to 
)
inlinevirtual
template<typename ParameterType >
bool g2o::OptimizableGraph::Edge::installParameter ( ParameterType *&  p,
size_t  argNo,
int  paramId = -1 
)
inlineprotected
long long g2o::OptimizableGraph::Edge::internalId ( ) const
inline

the internal ID of the edge

Definition at line 452 of file optimizable_graph.h.

References graph.

Referenced by g2o::OptimizableGraph::EdgeIDCompare::operator()().

452 { return _internalId;}
int g2o::OptimizableGraph::Edge::level ( ) const
inline
virtual void g2o::OptimizableGraph::Edge::linearizeOplus ( JacobianWorkspace jacobianWorkspace)
pure virtual

Linearizes the constraint in the edge in the manifold space, and store the result in the given workspace

Implemented in g2o::BaseMultiEdge<-1, E >, g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 1, double, VertexLine2D, VertexPointXY >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 6, Eigen::Vector3d, VertexPositionVelocity3D, VertexPositionVelocity3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexCameraBAL, VertexPointBAL >, g2o::BaseBinaryEdge< 2, Vector2D, VertexPointXY, VertexPointXY >, g2o::BaseBinaryEdge< 4, Vector4D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Line2D, VertexLine2D, VertexLine2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, Isometry3D, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 3, Eigen::Vector3d, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 4, Vector4D, VertexPlane, VertexPlane >, g2o::BaseBinaryEdge< 2, Line2D, VertexSE2, VertexLine2D >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 7, Vector7d, VertexSE3, VertexLine3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, Vector3D, VertexPointXYZ, VertexPointXYZ >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexBaseline >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexOdomDifferentialParams >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, Vector6d, VertexLine3D, VertexLine3D >, g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 6, Isometry3D >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 4, Vector4D >, g2o::BaseMultiEdge< 2, Vector2D >, g2o::BaseMultiEdge< 3, Plane3D >, g2o::BaseMultiEdge<-1, VectorXD >, g2o::BaseMultiEdge< 3, VelocityMeasurement >, 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 >, and g2o::BaseUnaryEdge< 6, SE3Quat, VertexSE3 >.

Referenced by g2o::BlockSolver< Traits >::buildSystem(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizerOnline::optimize(), and g2o::SparseOptimizerIncremental::updateInitialization().

virtual void g2o::OptimizableGraph::Edge::mapHessianMemory ( double *  d,
int  i,
int  j,
bool  rowMajor 
)
pure virtual

maps the internal matrix to some external memory location, you need to provide the memory before calling constructQuadraticForm

Parameters
dthe memory location to which we map
iindex of the vertex i
jindex of the vertex j (j > i, upper triangular fashion)
rowMajorif true, will write in rowMajor order to the block. Since EIGEN is columnMajor by default, this results in writing the transposed

Implemented in g2o::BaseMultiEdge<-1, E >, g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 1, double, VertexLine2D, VertexPointXY >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 6, Eigen::Vector3d, VertexPositionVelocity3D, VertexPositionVelocity3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexCameraBAL, VertexPointBAL >, g2o::BaseBinaryEdge< 2, Vector2D, VertexPointXY, VertexPointXY >, g2o::BaseBinaryEdge< 4, Vector4D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Line2D, VertexLine2D, VertexLine2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, Isometry3D, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 3, Eigen::Vector3d, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 4, Vector4D, VertexPlane, VertexPlane >, g2o::BaseBinaryEdge< 2, Line2D, VertexSE2, VertexLine2D >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 7, Vector7d, VertexSE3, VertexLine3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, Vector3D, VertexPointXYZ, VertexPointXYZ >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexBaseline >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexOdomDifferentialParams >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, Vector6d, VertexLine3D, VertexLine3D >, g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 6, Isometry3D >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 4, Vector4D >, g2o::BaseMultiEdge< 2, Vector2D >, g2o::BaseMultiEdge< 3, Plane3D >, g2o::BaseMultiEdge<-1, VectorXD >, g2o::BaseMultiEdge< 3, VelocityMeasurement >, 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 >, and g2o::BaseUnaryEdge< 6, SE3Quat, VertexSE3 >.

Referenced by g2o::BlockSolver< Traits >::buildStructure(), g2o::SparseOptimizerIncremental::updateInitialization(), and g2o::BlockSolver< Traits >::updateStructure().

int g2o::OptimizableGraph::Edge::measurementDimension ( ) const
virtual
size_t g2o::OptimizableGraph::Edge::numParameters ( ) const
inline

Definition at line 459 of file optimizable_graph.h.

Referenced by g2o::EdgeCreator::createEdge().

459 {return _parameters.size();}
std::vector< Parameter ** > _parameters
const Parameter* g2o::OptimizableGraph::Edge::parameter ( int  argNo) const
inline
virtual bool g2o::OptimizableGraph::Edge::read ( std::istream &  is)
pure virtual

read the vertex from a stream, i.e., the internal state of the vertex

Implemented in g2o::Edge_XYZ_VSC, g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::EdgeProjectP2MC_Intrinsics, g2o::EdgeProjectP2SC, g2o::EdgeProjectXYZ2UVU, GPSObservationEdgePositionVelocity3D, g2o::Edge_V_V_GICP, g2o::EdgeProjectPSI2UV, g2o::EdgeProjectP2MC, EdgeObservationBAL, TargetOdometry3DEdge, g2o::EdgeProjectXYZ2UV, g2o::EdgeSim3ProjectXYZ, g2o::EdgeSE3Expmap, EdgePointOnCircle, g2o::EdgeSE2Segment2DPointLine, EdgeCalib, g2o::EdgeSE2Segment2DLine, EdgePointOnCurve, g2o::EdgeSim3, GPSObservationPosition3DEdge, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Line2D, g2o::EdgeSE2Segment2D, g2o::EdgeLine2DPointXY, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2SensorCalib, g2o::EdgeSE2Prior, g2o::EdgeSE2OdomDifferentialCalib, g2o::EdgeSE2XYPrior, g2o::EdgeSE3PlaneSensorCalib, g2o::tutorial::EdgeSE2, g2o::EdgeSE2PureCalib, g2o::EdgeSE2PointXYCalib, g2o::EdgeSE2, g2o::tutorial::EdgeSE2PointXY, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgeLine2D, g2o::EdgePointXYZ, g2o::EdgeSE3PointXYZDisparity, g2o::EdgeSE3Line3D, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2Offset, g2o::EdgeSE2PointXYOffset, g2o::EdgeSE3Offset, g2o::EdgeSE3Calib, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE3Prior, g2o::EdgeSE3Euler, g2o::deprecated::EdgeSE3Prior, g2o::EdgeSE2LotsOfXY, g2o::EdgeSE3LotsOfXYZ, g2o::EdgeSE3, and g2o::EdgeSE2TwoPointsXY.

Referenced by g2o::OptimizableGraph::setFixed().

void g2o::OptimizableGraph::Edge::resizeParameters ( size_t  newSize)
inline
template<typename CacheType >
void g2o::OptimizableGraph::Edge::resolveCache ( CacheType *&  cache,
OptimizableGraph::Vertex v,
const std::string &  _type,
const ParameterVector parameters 
)
protected
bool g2o::OptimizableGraph::Edge::resolveCaches ( )
protectedvirtual
bool g2o::OptimizableGraph::Edge::resolveParameters ( )
protected

Definition at line 159 of file optimizable_graph.cpp.

References __PRETTY_FUNCTION__, _parameterIds, _parameters, _parameterTypes, graph(), and g2o::OptimizableGraph::parameter().

Referenced by g2o::OptimizableGraph::addEdge(), and g2o::OptimizableGraph::setEdgeVertex().

159  {
160  if (!graph()) {
161  cerr << __PRETTY_FUNCTION__ << ": edge not registered with a graph" << endl;
162  return false;
163  }
164 
165  assert (_parameters.size() == _parameterIds.size());
166  //cerr << __PRETTY_FUNCTION__ << ": encountered " << _parameters.size() << " parameters" << endl;
167  for (size_t i=0; i<_parameters.size(); i++){
168  int index = _parameterIds[i];
169  *_parameters[i] = graph()->parameter(index);
170  if (typeid(**_parameters[i]).name()!=_parameterTypes[i]){
171  cerr << __PRETTY_FUNCTION__ << ": FATAL, parameter type mismatch - encountered " << typeid(**_parameters[i]).name() << "; should be " << _parameterTypes[i] << endl;
172  }
173  if (!*_parameters[i]) {
174  cerr << __PRETTY_FUNCTION__ << ": FATAL, *_parameters[i] == 0" << endl;
175  return false;
176  }
177  }
178  return true;
179  }
#define __PRETTY_FUNCTION__
Definition: macros.h:89
std::vector< std::string > _parameterTypes
std::vector< Parameter ** > _parameters
std::vector< int > _parameterIds
Parameter * parameter(int id)
RobustKernel* g2o::OptimizableGraph::Edge::robustKernel ( ) const
inline

if NOT NULL, error of this edge will be robustifed with the kernel

Definition at line 383 of file optimizable_graph.h.

Referenced by g2o::SparseOptimizer::activeRobustChi2(), gnudump_edges(), gnudump_features(), main(), InvChi2CostFunction::operator()(), and MainWindow::setRobustKernel().

383 { return _robustKernel;}
void g2o::OptimizableGraph::Edge::setLevel ( int  l)
inline

sets the level of the edge

Definition at line 437 of file optimizable_graph.h.

Referenced by g2o::assignHierarchicalEdges(), and g2o::computeSimpleStars().

bool g2o::OptimizableGraph::Edge::setMeasurementData ( const double *  m)
virtual
bool g2o::OptimizableGraph::Edge::setMeasurementFromState ( )
virtual
bool g2o::OptimizableGraph::Edge::setParameterId ( int  argNum,
int  paramId 
)
void g2o::OptimizableGraph::Edge::setRobustKernel ( RobustKernel ptr)

specify the robust kernel to be used in this edge

Definition at line 181 of file optimizable_graph.cpp.

References _robustKernel.

Referenced by main(), and MainWindow::setRobustKernel().

182  {
183  if (_robustKernel)
184  delete _robustKernel;
185  _robustKernel = ptr;
186  }
virtual bool g2o::OptimizableGraph::Edge::write ( std::ostream &  os) const
pure virtual

write the vertex to a stream

Implemented in g2o::Edge_XYZ_VSC, g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::EdgeProjectP2MC_Intrinsics, g2o::EdgeProjectP2SC, g2o::EdgeProjectXYZ2UVU, GPSObservationEdgePositionVelocity3D, g2o::Edge_V_V_GICP, EdgeObservationBAL, g2o::EdgeProjectPSI2UV, g2o::EdgeProjectP2MC, TargetOdometry3DEdge, g2o::EdgeProjectXYZ2UV, g2o::EdgeSim3ProjectXYZ, g2o::EdgeSE3Expmap, EdgePointOnCircle, g2o::EdgeSE2Segment2DPointLine, EdgeCalib, EdgePointOnCurve, g2o::EdgeSE2Segment2DLine, GPSObservationPosition3DEdge, g2o::EdgeSim3, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Line2D, g2o::EdgeSE2Segment2D, g2o::EdgeLine2DPointXY, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2SensorCalib, g2o::EdgeSE2Prior, g2o::EdgeSE2OdomDifferentialCalib, g2o::EdgeSE2XYPrior, g2o::EdgeSE3PlaneSensorCalib, g2o::tutorial::EdgeSE2, g2o::EdgeSE2PureCalib, g2o::EdgeSE2PointXYCalib, g2o::EdgeSE2, g2o::tutorial::EdgeSE2PointXY, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgeLine2D, g2o::EdgePointXYZ, g2o::EdgeSE3PointXYZDisparity, g2o::EdgeSE3Line3D, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2Offset, g2o::EdgeSE2PointXYOffset, g2o::EdgeSE3Offset, g2o::EdgeSE3Calib, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE3Prior, g2o::EdgeSE3Euler, g2o::deprecated::EdgeSE3Prior, g2o::EdgeSE2LotsOfXY, g2o::EdgeSE3LotsOfXYZ, g2o::EdgeSE3, and g2o::EdgeSE2TwoPointsXY.

Referenced by g2o::OptimizableGraph::saveEdge().

Friends And Related Function Documentation

friend struct OptimizableGraph
friend

Definition at line 351 of file optimizable_graph.h.

Member Data Documentation

std::vector<int> g2o::OptimizableGraph::Edge::_cacheIds
protected

Definition at line 470 of file optimizable_graph.h.

int g2o::OptimizableGraph::Edge::_dimension
protected
long long g2o::OptimizableGraph::Edge::_internalId
protected

Definition at line 469 of file optimizable_graph.h.

Referenced by g2o::OptimizableGraph::addEdge().

int g2o::OptimizableGraph::Edge::_level
protected

Definition at line 467 of file optimizable_graph.h.

std::vector<int> g2o::OptimizableGraph::Edge::_parameterIds
protected

Definition at line 492 of file optimizable_graph.h.

Referenced by resolveParameters(), and setParameterId().

std::vector<Parameter**> g2o::OptimizableGraph::Edge::_parameters
protected
std::vector<std::string> g2o::OptimizableGraph::Edge::_parameterTypes
protected

Definition at line 490 of file optimizable_graph.h.

Referenced by resolveParameters().

RobustKernel* g2o::OptimizableGraph::Edge::_robustKernel
protected

Definition at line 468 of file optimizable_graph.h.

Referenced by setRobustKernel(), and ~Edge().


The documentation for this class was generated from the following files: