g2o
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Static Public Attributes | Protected Attributes | List of all members
g2o::BaseVertex< D, T > Class Template Reference

Templatized BaseVertex. More...

#include <base_vertex.h>

Inheritance diagram for g2o::BaseVertex< D, T >:
Inheritance graph
[legend]
Collaboration diagram for g2o::BaseVertex< D, T >:
Collaboration graph
[legend]

Public Types

using EstimateType = T
 
using BackupStackType = std::stack< EstimateType, std::vector< EstimateType > >
 
using HessianBlockType = Eigen::Map< Eigen::Matrix< double, D, D, Eigen::ColMajor >, Eigen::Matrix< double, D, D, Eigen::ColMajor >::Flags &Eigen::PacketAccessBit ? Eigen::Aligned :Eigen::Unaligned >
 

Public Member Functions

 BaseVertex ()
 
BaseVertexoperator= (const BaseVertex &)=delete
 
 BaseVertex (const BaseVertex &)=delete
 
virtual const double & hessian (int i, int j) const
 get the element from the hessian matrix
 
virtual double & hessian (int i, int j)
 
virtual double hessianDeterminant () const
 
virtual double * hessianData ()
 
virtual void mapHessianMemory (double *d)
 
virtual int copyB (double *b_) const
 
virtual const double & b (int i) const
 get the b vector element
 
virtual double & b (int i)
 
virtual double * bData ()
 return a pointer to the b vector associated with this vertex
 
virtual void clearQuadraticForm ()
 
virtual double solveDirect (double lambda=0)
 
Eigen::Matrix< double, D, 1, Eigen::ColMajor > & b ()
 return right hand side b of the constructed linear system
 
const Eigen::Matrix< double, D, 1, Eigen::ColMajor > & b () const
 
HessianBlockTypeA ()
 return the hessian block associated with the vertex
 
const HessianBlockTypeA () const
 
virtual void push ()
 backup the position of the vertex to a stack
 
virtual void pop ()
 
virtual void discardTop ()
 
virtual int stackSize () const
 return the stack size
 
const EstimateTypeestimate () const
 return the current estimate of the vertex
 
void setEstimate (const EstimateType &et)
 set the estimate for the vertex also calls updateCache()
 
- Public Member Functions inherited from g2o::OptimizableGraph::Vertex
 Vertex ()
 
virtual ~Vertex ()
 
void setToOrigin ()
 sets the node to the origin (used in the multilevel stuff)
 
bool setEstimateData (const double *estimate)
 
bool setEstimateData (const std::vector< double > &estimate)
 
template<typename Derived >
bool setEstimateData (const Eigen::MatrixBase< Derived > &estimate)
 
virtual bool getEstimateData (double *estimate) const
 
virtual bool getEstimateData (std::vector< double > &estimate) const
 
template<typename Derived >
bool getEstimateData (Eigen::MatrixBase< Derived > &estimate) const
 
virtual int estimateDimension () const
 
bool setMinimalEstimateData (const double *estimate)
 
bool setMinimalEstimateData (const std::vector< double > &estimate)
 
template<typename Derived >
bool setMinimalEstimateData (const Eigen::MatrixBase< Derived > &estimate)
 
virtual bool getMinimalEstimateData (double *estimate) const
 
virtual bool getMinimalEstimateData (std::vector< double > &estimate) const
 
template<typename Derived >
bool getMinimalEstimateData (Eigen::MatrixBase< Derived > &estimate) const
 
virtual int minimalEstimateDimension () const
 
void oplus (const double *v)
 
int hessianIndex () const
 
int G2O_ATTRIBUTE_DEPRECATED (tempIndex() const)
 
void setHessianIndex (int ti)
 set the temporary index of the vertex in the parameter blocks
 
void G2O_ATTRIBUTE_DEPRECATED (setTempIndex(int ti))
 
bool fixed () const
 true => this node is fixed during the optimization
 
void setFixed (bool fixed)
 true => this node should be considered fixed during the optimization
 
bool marginalized () const
 true => this node is marginalized out during the optimization
 
void setMarginalized (bool marginalized)
 true => this node should be marginalized out during the optimization
 
int dimension () const
 dimension of the estimated state belonging to this node
 
virtual void setId (int id)
 
void setColInHessian (int c)
 set the row of this vertex in the Hessian
 
int colInHessian () const
 get the row of this vertex in the Hessian
 
const OptimizableGraphgraph () const
 
OptimizableGraphgraph ()
 
void lockQuadraticForm ()
 
void unlockQuadraticForm ()
 
virtual bool read (std::istream &is)=0
 read the vertex from a stream, i.e., the internal state of the vertex
 
virtual bool write (std::ostream &os) const =0
 write the vertex to a stream
 
virtual void updateCache ()
 
CacheContainercacheContainer ()
 
- Public Member Functions inherited from g2o::HyperGraph::Vertex
 Vertex (int id=InvalidId)
 creates a vertex having an ID specified by the argument
 
int id () const
 returns the id
 
const EdgeSetedges () const
 returns the set of hyper-edges that are leaving/entering in this vertex
 
EdgeSetedges ()
 returns the set of hyper-edges that are leaving/entering in this vertex
 
virtual HyperGraphElementType elementType () const
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 
- Public Member Functions inherited from g2o::HyperGraph::DataContainer
 DataContainer ()
 
virtual ~DataContainer ()
 
const DatauserData () const
 the user data associated with this vertex
 
DatauserData ()
 
void setUserData (Data *obs)
 
void addUserData (Data *obs)
 

Static Public Attributes

static const int Dimension
 dimension of the estimate (minimal) in the manifold space
 

Protected Attributes

HessianBlockType _hessian
 
Eigen::Matrix< double, D, 1, Eigen::ColMajor > _b
 
EstimateType _estimate
 
BackupStackType _backup
 
- Protected Attributes inherited from g2o::OptimizableGraph::Vertex
OptimizableGraph_graph
 
Data_userData
 
int _hessianIndex
 
bool _fixed
 
bool _marginalized
 
int _dimension
 
int _colInHessian
 
OpenMPMutex _quadraticFormMutex
 
CacheContainer_cacheContainer
 
- Protected Attributes inherited from g2o::HyperGraph::Vertex
int _id
 
EdgeSet _edges
 
- Protected Attributes inherited from g2o::HyperGraph::DataContainer
Data_userData
 

Additional Inherited Members

- Protected Member Functions inherited from g2o::OptimizableGraph::Vertex
virtual void oplusImpl (const double *v)=0
 
virtual void setToOriginImpl ()=0
 sets the node to the origin (used in the multilevel stuff)
 
virtual bool setEstimateDataImpl (const double *)
 
virtual bool setMinimalEstimateDataImpl (const double *)
 

Detailed Description

template<int D, typename T>
class g2o::BaseVertex< D, T >

Templatized BaseVertex.

Templatized BaseVertex D : minimal dimension of the vertex, e.g., 3 for rotation in 3D. -1 means dynamically assigned at runtime. T : internal type to represent the estimate, e.g., Quaternion for rotation in 3D

Definition at line 51 of file base_vertex.h.

Member Typedef Documentation

◆ BackupStackType

template<int D, typename T >
using g2o::BaseVertex< D, T >::BackupStackType = std::stack<EstimateType, std::vector<EstimateType> >

Definition at line 54 of file base_vertex.h.

◆ EstimateType

template<int D, typename T >
using g2o::BaseVertex< D, T >::EstimateType = T

Definition at line 53 of file base_vertex.h.

◆ HessianBlockType

template<int D, typename T >
using g2o::BaseVertex< D, T >::HessianBlockType = Eigen::Map<Eigen::Matrix<double, D, D, Eigen::ColMajor>, Eigen::Matrix<double, D, D, Eigen::ColMajor>::Flags & Eigen::PacketAccessBit ? Eigen::Aligned : Eigen::Unaligned>

Definition at line 59 of file base_vertex.h.

Constructor & Destructor Documentation

◆ BaseVertex() [1/2]

template<int D, typename T >
BaseVertex::BaseVertex ( )

Definition at line 28 of file base_vertex.hpp.

29 : OptimizableGraph::Vertex(), _hessian(nullptr, D, D) {
30 _dimension = D;
31}
HessianBlockType _hessian

References g2o::OptimizableGraph::Vertex::_dimension.

◆ BaseVertex() [2/2]

template<int D, typename T >
g2o::BaseVertex< D, T >::BaseVertex ( const BaseVertex< D, T > &  )
delete

Member Function Documentation

◆ A() [1/2]

template<int D, typename T >
HessianBlockType & g2o::BaseVertex< D, T >::A ( )
inline

return the hessian block associated with the vertex

Definition at line 110 of file base_vertex.h.

110{ return _hessian; }

References g2o::BaseVertex< D, T >::_hessian.

◆ A() [2/2]

template<int D, typename T >
const HessianBlockType & g2o::BaseVertex< D, T >::A ( ) const
inline

Definition at line 111 of file base_vertex.h.

111{ return _hessian; }

References g2o::BaseVertex< D, T >::_hessian.

◆ b() [1/4]

template<int D, typename T >
Eigen::Matrix< double, D, 1, Eigen::ColMajor > & g2o::BaseVertex< D, T >::b ( )
inline

return right hand side b of the constructed linear system

Definition at line 107 of file base_vertex.h.

107{ return _b; }
Eigen::Matrix< double, D, 1, Eigen::ColMajor > _b

References g2o::BaseVertex< D, T >::_b.

◆ b() [2/4]

template<int D, typename T >
const Eigen::Matrix< double, D, 1, Eigen::ColMajor > & g2o::BaseVertex< D, T >::b ( ) const
inline

Definition at line 108 of file base_vertex.h.

108{ return _b; }

References g2o::BaseVertex< D, T >::_b.

◆ b() [3/4]

template<int D, typename T >
virtual double & g2o::BaseVertex< D, T >::b ( int  i)
inlinevirtual

Implements g2o::OptimizableGraph::Vertex.

Definition at line 94 of file base_vertex.h.

94 {
95 assert(i < G2O_VERTEX_DIM);
96 return _b(i);
97 }
#define G2O_VERTEX_DIM
Definition base_vertex.h:41

References g2o::BaseVertex< D, T >::_b, and G2O_VERTEX_DIM.

◆ b() [4/4]

template<int D, typename T >
virtual const double & g2o::BaseVertex< D, T >::b ( int  i) const
inlinevirtual

get the b vector element

Implements g2o::OptimizableGraph::Vertex.

Definition at line 90 of file base_vertex.h.

90 {
91 assert(i < D);
92 return _b(i);
93 }

References g2o::BaseVertex< D, T >::_b.

◆ bData()

template<int D, typename T >
virtual double * g2o::BaseVertex< D, T >::bData ( )
inlinevirtual

return a pointer to the b vector associated with this vertex

Implements g2o::OptimizableGraph::Vertex.

Definition at line 98 of file base_vertex.h.

98{ return _b.data(); }

References g2o::BaseVertex< D, T >::_b.

◆ clearQuadraticForm()

template<int D, typename T >
void BaseVertex::clearQuadraticForm ( )
inlinevirtual

set the b vector part of this vertex to zero

Implements g2o::OptimizableGraph::Vertex.

Definition at line 48 of file base_vertex.hpp.

48 {
49 _b.setZero();
50}

◆ copyB()

template<int D, typename T >
virtual int g2o::BaseVertex< D, T >::copyB ( double *  b_) const
inlinevirtual

copies the b vector in the array b_

Returns
the number of elements copied

Implements g2o::OptimizableGraph::Vertex.

Definition at line 84 of file base_vertex.h.

84 {
85 const int vertexDim = G2O_VERTEX_DIM;
86 memcpy(b_, _b.data(), vertexDim * sizeof(double));
87 return vertexDim;
88 }

References g2o::BaseVertex< D, T >::_b, and G2O_VERTEX_DIM.

◆ discardTop()

template<int D, typename T >
virtual void g2o::BaseVertex< D, T >::discardTop ( )
inlinevirtual

pop the last element from the stack, without restoring the current estimate

Implements g2o::OptimizableGraph::Vertex.

Definition at line 120 of file base_vertex.h.

120 {
121 assert(!_backup.empty());
122 _backup.pop();
123 }
BackupStackType _backup

References g2o::BaseVertex< D, T >::_backup.

◆ estimate()

template<int D, typename T >
const EstimateType & g2o::BaseVertex< D, T >::estimate ( ) const
inline

return the current estimate of the vertex

Definition at line 127 of file base_vertex.h.

127{ return _estimate; }
EstimateType _estimate

References g2o::BaseVertex< D, T >::_estimate.

Referenced by g2o::OnlineEdgeSE3::chi2(), g2o::EdgeSE2PureCalib::computeError(), EdgeCalib::computeError(), MultipleValueEdge::computeError(), GPSObservationPosition3DEdge::computeError(), TargetOdometry3DEdge::computeError(), GPSObservationEdgePositionVelocity3D::computeError(), g2o::tutorial::EdgeSE2::computeError(), g2o::tutorial::EdgeSE2PointXY::computeError(), g2o::Edge_V_V_GICP::computeError(), g2o::Edge_XYZ_VSC::computeError(), g2o::EdgeProjectP2MC::computeError(), g2o::EdgeProjectP2SC::computeError(), g2o::EdgeProjectPSI2UV::computeError(), g2o::EdgeStereoSE3ProjectXYZ::computeError(), g2o::EdgeStereoSE3ProjectXYZOnlyPose::computeError(), g2o::EdgeSE3ProjectXYZ::computeError(), g2o::EdgeProjectXYZ2UV::computeError(), g2o::EdgeProjectXYZ2UVU::computeError(), g2o::EdgeSE3ProjectXYZOnlyPose::computeError(), g2o::EdgeSBACam::computeError(), g2o::EdgeSBAScale::computeError(), g2o::EdgeSE3Expmap::computeError(), g2o::EdgeSE2OdomDifferentialCalib::computeError(), g2o::EdgeSE2SensorCalib::computeError(), g2o::EdgeSim3::computeError(), g2o::EdgeSim3ProjectXYZ::computeError(), g2o::EdgeInverseSim3ProjectXYZ::computeError(), g2o::EdgePointXY::computeError(), g2o::EdgeSE2::computeError(), g2o::EdgeSE2LotsOfXY::computeError(), g2o::EdgeSE2PointXY::computeError(), g2o::EdgeSE2PointXYBearing::computeError(), g2o::EdgeSE2PointXYCalib::computeError(), g2o::EdgeSE2PointXYOffset::computeError(), g2o::EdgeSE2Prior::computeError(), g2o::EdgeSE2TwoPointsXY::computeError(), g2o::EdgeSE2XYPrior::computeError(), g2o::EdgeXYPrior::computeError(), g2o::EdgeLine2D::computeError(), g2o::EdgeLine2DPointXY::computeError(), g2o::EdgeSE2Line2D::computeError(), g2o::EdgeSE2Segment2D::computeError(), g2o::EdgeSE2Segment2DLine::computeError(), g2o::EdgeSE2Segment2DPointLine::computeError(), g2o::EdgePointXYZ::computeError(), g2o::EdgeSE3::computeError(), g2o::EdgeSE3LotsOfXYZ::computeError(), g2o::EdgeSE3PointXYZ::computeError(), g2o::EdgeSE3PointXYZDepth::computeError(), g2o::EdgeSE3PointXYZDisparity::computeError(), g2o::EdgeSE3XYZPrior::computeError(), g2o::EdgeXYZPrior::computeError(), g2o::EdgePlane::computeError(), g2o::EdgeSE3Calib::computeError(), g2o::EdgeSE3Line3D::computeError(), g2o::EdgeSE3PlaneSensorCalib::computeError(), g2o::Slam2DViewer::draw(), gnudump_edges(), gnudump_features(), TargetOdometry3DEdge::initialEstimate(), g2o::EdgeSE2LotsOfXY::initialEstimate(), g2o::EdgeSE2TwoPointsXY::initialEstimate(), g2o::EdgeSE3LotsOfXYZ::initialEstimate(), g2o::EdgeSE3XYZPrior::initialEstimate(), g2o::EdgeSim3::initialEstimate(), g2o::EdgeSBACam::initialEstimate(), g2o::EdgeSE2SensorCalib::initialEstimate(), g2o::EdgeSE2::initialEstimate(), g2o::EdgeSE2Offset::initialEstimate(), g2o::EdgeSE2PointXY::initialEstimate(), g2o::EdgeSE2PointXYBearing::initialEstimate(), g2o::EdgeSE2PointXYCalib::initialEstimate(), g2o::EdgeSE2PointXYOffset::initialEstimate(), g2o::EdgeSE2Line2D::initialEstimate(), g2o::EdgeSE2Segment2D::initialEstimate(), g2o::EdgeSE3::initialEstimate(), g2o::EdgeSE3Offset::initialEstimate(), g2o::EdgeSE3PointXYZ::initialEstimate(), g2o::EdgeSE3PointXYZDepth::initialEstimate(), g2o::EdgeSE3PointXYZDisparity::initialEstimate(), g2o::EdgeSE3Prior::initialEstimate(), g2o::EdgeSBAScale::initialEstimate(), g2o::EdgeStereoSE3ProjectXYZ::isDepthPositive(), g2o::EdgeStereoSE3ProjectXYZOnlyPose::isDepthPositive(), g2o::EdgeSE3ProjectXYZ::isDepthPositive(), g2o::EdgeSE3ProjectXYZOnlyPose::isDepthPositive(), g2o::Edge_V_V_GICP::linearizeOplus(), g2o::EdgeProjectP2MC::linearizeOplus(), g2o::EdgeProjectP2SC::linearizeOplus(), g2o::EdgeProjectPSI2UV::linearizeOplus(), g2o::EdgeStereoSE3ProjectXYZ::linearizeOplus(), g2o::EdgeStereoSE3ProjectXYZOnlyPose::linearizeOplus(), g2o::EdgeSE3ProjectXYZ::linearizeOplus(), g2o::EdgeProjectXYZ2UV::linearizeOplus(), g2o::EdgeSE3ProjectXYZOnlyPose::linearizeOplus(), g2o::EdgeSE3Expmap::linearizeOplus(), g2o::EdgeSE2::linearizeOplus(), g2o::EdgeSE2LotsOfXY::linearizeOplus(), g2o::EdgeSE2PointXY::linearizeOplus(), g2o::EdgeSE2PointXYOffset::linearizeOplus(), g2o::EdgeSE3::linearizeOplus(), g2o::EdgeSE3LotsOfXYZ::linearizeOplus(), g2o::EdgeSE3Offset::linearizeOplus(), g2o::EdgeSE3PointXYZ::linearizeOplus(), g2o::EdgeSE3PointXYZDepth::linearizeOplus(), g2o::EdgeSE3PointXYZDisparity::linearizeOplus(), g2o::EdgeSE3Prior::linearizeOplus(), g2o::EdgeSE3XYZPrior::linearizeOplus(), main(), main(), main(), Robot::move(), g2o::EdgeSE2WriteGnuplotAction::operator()(), g2o::EdgeSE2PointXYWriteGnuplotAction::operator()(), g2o::EdgeSE2PointXYBearingWriteGnuplotAction::operator()(), g2o::VertexPointXYWriteGnuplotAction::operator()(), g2o::VertexSE2WriteGnuplotAction::operator()(), g2o::EdgeSE3WriteGnuplotAction::operator()(), g2o::VertexPointXYZWriteGnuplotAction::operator()(), g2o::VertexSE3WriteGnuplotAction::operator()(), g2o::Gm2dlIO::readGm2dl(), LineSensor::sense(), PlaneSensor::sense(), g2o::EdgeSBACam::setMeasurementFromState(), g2o::EdgePointXY::setMeasurementFromState(), g2o::EdgeSE2::setMeasurementFromState(), g2o::EdgeSE2LotsOfXY::setMeasurementFromState(), g2o::EdgeSE2PointXY::setMeasurementFromState(), g2o::EdgeSE2PointXYBearing::setMeasurementFromState(), g2o::EdgeSE2PointXYOffset::setMeasurementFromState(), g2o::EdgeSE2TwoPointsXY::setMeasurementFromState(), g2o::EdgeXYPrior::setMeasurementFromState(), g2o::EdgeLine2D::setMeasurementFromState(), g2o::EdgeLine2DPointXY::setMeasurementFromState(), g2o::EdgeSE2Line2D::setMeasurementFromState(), g2o::EdgeSE2Segment2D::setMeasurementFromState(), g2o::EdgeSE2Segment2DLine::setMeasurementFromState(), g2o::EdgeSE2Segment2DPointLine::setMeasurementFromState(), g2o::EdgePointXYZ::setMeasurementFromState(), g2o::EdgeSE3::setMeasurementFromState(), g2o::EdgeSE3LotsOfXYZ::setMeasurementFromState(), g2o::EdgeSE3PointXYZ::setMeasurementFromState(), g2o::EdgeSE3PointXYZDepth::setMeasurementFromState(), g2o::EdgeSE3PointXYZDisparity::setMeasurementFromState(), g2o::EdgeSE3XYZPrior::setMeasurementFromState(), g2o::EdgeXYZPrior::setMeasurementFromState(), g2o::EdgePlane::setMeasurementFromState(), ToVertexSE3(), ToVertexSim3(), updateDisplay(), g2o::tutorial::CacheSE2Offset::updateImpl(), g2o::CacheSE2Offset::updateImpl(), g2o::CacheSE3Offset::updateImpl(), and g2o::Gm2dlIO::updateLaserData().

◆ hessian() [1/2]

template<int D, typename T >
virtual double & g2o::BaseVertex< D, T >::hessian ( int  i,
int  j 
)
inlinevirtual

Implements g2o::OptimizableGraph::Vertex.

Definition at line 75 of file base_vertex.h.

75 {
76 assert(i < G2O_VERTEX_DIM && j < G2O_VERTEX_DIM);
77 return _hessian(i, j);
78 }

References g2o::BaseVertex< D, T >::_hessian, and G2O_VERTEX_DIM.

◆ hessian() [2/2]

template<int D, typename T >
virtual const double & g2o::BaseVertex< D, T >::hessian ( int  i,
int  j 
) const
inlinevirtual

get the element from the hessian matrix

Implements g2o::OptimizableGraph::Vertex.

Definition at line 71 of file base_vertex.h.

71 {
72 assert(i < G2O_VERTEX_DIM && j < G2O_VERTEX_DIM);
73 return _hessian(i, j);
74 }

References g2o::BaseVertex< D, T >::_hessian, and G2O_VERTEX_DIM.

◆ hessianData()

template<int D, typename T >
virtual double * g2o::BaseVertex< D, T >::hessianData ( )
inlinevirtual

Implements g2o::OptimizableGraph::Vertex.

Definition at line 80 of file base_vertex.h.

80{ return const_cast<double*>(_hessian.data()); }

References g2o::BaseVertex< D, T >::_hessian.

◆ hessianDeterminant()

template<int D, typename T >
virtual double g2o::BaseVertex< D, T >::hessianDeterminant ( ) const
inlinevirtual

Implements g2o::OptimizableGraph::Vertex.

Definition at line 79 of file base_vertex.h.

79{ return _hessian.determinant(); }

References g2o::BaseVertex< D, T >::_hessian.

◆ mapHessianMemory()

template<int D, typename T >
void BaseVertex::mapHessianMemory ( double *  d)
inlinevirtual

maps the internal matrix to some external memory location

Implements g2o::OptimizableGraph::Vertex.

Definition at line 53 of file base_vertex.hpp.

53 {
54 const int vertexDim = G2O_VERTEX_DIM;
55 new (&_hessian) HessianBlockType(d, vertexDim, vertexDim);
56}
Eigen::Map< Eigen::Matrix< double, D, D, Eigen::ColMajor >, Eigen::Matrix< double, D, D, Eigen::ColMajor >::Flags &Eigen::PacketAccessBit ? Eigen::Aligned :Eigen::Unaligned > HessianBlockType
Definition base_vertex.h:64

References G2O_VERTEX_DIM.

◆ operator=()

template<int D, typename T >
BaseVertex & g2o::BaseVertex< D, T >::operator= ( const BaseVertex< D, T > &  )
delete

◆ pop()

template<int D, typename T >
virtual void g2o::BaseVertex< D, T >::pop ( )
inlinevirtual

restore the position of the vertex by retrieving the position from the stack

Implements g2o::OptimizableGraph::Vertex.

Definition at line 114 of file base_vertex.h.

114 {
115 assert(!_backup.empty());
116 _estimate = _backup.top();
117 _backup.pop();
118 updateCache();
119 }

References g2o::BaseVertex< D, T >::_backup, g2o::BaseVertex< D, T >::_estimate, and g2o::OptimizableGraph::Vertex::updateCache().

◆ push()

template<int D, typename T >
virtual void g2o::BaseVertex< D, T >::push ( )
inlinevirtual

backup the position of the vertex to a stack

Implements g2o::OptimizableGraph::Vertex.

Definition at line 113 of file base_vertex.h.

113{ _backup.push(_estimate); }

References g2o::BaseVertex< D, T >::_backup, and g2o::BaseVertex< D, T >::_estimate.

Referenced by g2o::findConnectedEdgesWithCostLimit().

◆ setEstimate()

template<int D, typename T >
void g2o::BaseVertex< D, T >::setEstimate ( const EstimateType et)
inline

set the estimate for the vertex also calls updateCache()

Definition at line 129 of file base_vertex.h.

129 {
130 _estimate = et;
131 updateCache();
132 }

References g2o::BaseVertex< D, T >::_estimate, and g2o::OptimizableGraph::Vertex::updateCache().

Referenced by TargetOdometry3DEdge::initialEstimate(), g2o::EdgeSE2LotsOfXY::initialEstimate(), g2o::EdgeSE2TwoPointsXY::initialEstimate(), g2o::EdgeSE3LotsOfXYZ::initialEstimate(), g2o::EdgeSE3XYZPrior::initialEstimate(), g2o::OnlineEdgeSE2::initialEstimate(), g2o::OnlineEdgeSE3::initialEstimate(), g2o::EdgeSim3::initialEstimate(), g2o::EdgeSE2SensorCalib::initialEstimate(), g2o::EdgeSE2::initialEstimate(), g2o::EdgeSE2Offset::initialEstimate(), g2o::EdgeSE2PointXY::initialEstimate(), g2o::EdgeSE2PointXYBearing::initialEstimate(), g2o::EdgeSE2PointXYCalib::initialEstimate(), g2o::EdgeSE2PointXYOffset::initialEstimate(), g2o::EdgeSE2Prior::initialEstimate(), g2o::EdgeSE2Line2D::initialEstimate(), g2o::EdgeSE3::initialEstimate(), g2o::EdgeSE3Offset::initialEstimate(), g2o::EdgeSE3PointXYZ::initialEstimate(), g2o::EdgeSE3PointXYZDepth::initialEstimate(), g2o::EdgeSE3PointXYZDisparity::initialEstimate(), g2o::EdgeSE3Prior::initialEstimate(), LineInfo::LineInfo(), LineSensor::LineSensor(), main(), main(), main(), Robot::move(), g2o::SparseOptimizerIncremental::optimize(), g2o::SparseOptimizerOnline::optimize(), PlaneSensor::PlaneSensor(), g2o::Gm2dlIO::readGm2dl(), g2o::SolverSLAM2DLinear::solveOrientation(), ToVertexSE3(), and ToVertexSim3().

◆ solveDirect()

template<int D, typename T >
double BaseVertex::solveDirect ( double  lambda = 0)
inlinevirtual

updates the current vertex with the direct solution x += H_ii\b_ii

Returns
the determinant of the inverted hessian

Implements g2o::OptimizableGraph::Vertex.

Definition at line 34 of file base_vertex.hpp.

34 {
35 Eigen::Matrix<double, D, D, Eigen::ColMajor> tempA =
36 _hessian + Eigen::Matrix<double, D, D, Eigen::ColMajor>::Identity(
38 lambda;
39 double det = tempA.determinant();
40 if (g2o_isnan(det) || det < std::numeric_limits<double>::epsilon())
41 return det;
42 Eigen::Matrix<double, D, 1, Eigen::ColMajor> dx = tempA.llt().solve(_b);
43 oplus(&dx[0]);
44 return det;
45}
#define g2o_isnan(x)
Definition macros.h:100

References g2o_isnan, and G2O_VERTEX_DIM.

◆ stackSize()

template<int D, typename T >
virtual int g2o::BaseVertex< D, T >::stackSize ( ) const
inlinevirtual

return the stack size

Implements g2o::OptimizableGraph::Vertex.

Definition at line 124 of file base_vertex.h.

124{ return _backup.size(); }

References g2o::BaseVertex< D, T >::_backup.

Member Data Documentation

◆ _b

template<int D, typename T >
Eigen::Matrix<double, D, 1, Eigen::ColMajor> g2o::BaseVertex< D, T >::_b
protected

◆ _backup

template<int D, typename T >
BackupStackType g2o::BaseVertex< D, T >::_backup
protected

◆ _estimate

template<int D, typename T >
EstimateType g2o::BaseVertex< D, T >::_estimate
protected

◆ _hessian

template<int D, typename T >
HessianBlockType g2o::BaseVertex< D, T >::_hessian
protected

◆ Dimension

template<int D, typename T >
const int g2o::BaseVertex< D, T >::Dimension
static
Initial value:
=
D

dimension of the estimate (minimal) in the manifold space

Definition at line 56 of file base_vertex.h.


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