|
g2o
|
Templatized BaseVertex. More...
#include <base_vertex.h>


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 () | |
| BaseVertex & | operator= (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 |
| HessianBlockType & | A () |
| return the hessian block associated with the vertex | |
| const HessianBlockType & | A () 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 EstimateType & | estimate () 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 OptimizableGraph * | graph () const |
| OptimizableGraph * | graph () |
| 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 () |
| CacheContainer * | cacheContainer () |
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 EdgeSet & | edges () const |
| returns the set of hyper-edges that are leaving/entering in this vertex | |
| EdgeSet & | edges () |
| 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 Data * | userData () const |
| the user data associated with this vertex | |
| Data * | userData () |
| 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 *) |
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.
| using g2o::BaseVertex< D, T >::BackupStackType = std::stack<EstimateType, std::vector<EstimateType> > |
Definition at line 54 of file base_vertex.h.
| using g2o::BaseVertex< D, T >::EstimateType = T |
Definition at line 53 of file base_vertex.h.
| 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.
| BaseVertex::BaseVertex | ( | ) |
Definition at line 28 of file base_vertex.hpp.
References g2o::OptimizableGraph::Vertex::_dimension.
|
delete |
|
inline |
return the hessian block associated with the vertex
Definition at line 110 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_hessian.
|
inline |
|
inline |
return right hand side b of the constructed linear system
Definition at line 107 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_b.
|
inline |
|
inlinevirtual |
Implements g2o::OptimizableGraph::Vertex.
Definition at line 94 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_b, and G2O_VERTEX_DIM.
|
inlinevirtual |
get the b vector element
Implements g2o::OptimizableGraph::Vertex.
Definition at line 90 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_b.
|
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.
References g2o::BaseVertex< D, T >::_b.
|
inlinevirtual |
set the b vector part of this vertex to zero
Implements g2o::OptimizableGraph::Vertex.
Definition at line 48 of file base_vertex.hpp.
|
inlinevirtual |
copies the b vector in the array b_
Implements g2o::OptimizableGraph::Vertex.
Definition at line 84 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_b, and G2O_VERTEX_DIM.
|
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.
References g2o::BaseVertex< D, T >::_backup.
|
inline |
return the current estimate of the vertex
Definition at line 127 of file base_vertex.h.
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().
|
inlinevirtual |
Implements g2o::OptimizableGraph::Vertex.
Definition at line 75 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_hessian, and G2O_VERTEX_DIM.
|
inlinevirtual |
get the element from the hessian matrix
Implements g2o::OptimizableGraph::Vertex.
Definition at line 71 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_hessian, and G2O_VERTEX_DIM.
|
inlinevirtual |
Implements g2o::OptimizableGraph::Vertex.
Definition at line 80 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_hessian.
|
inlinevirtual |
Implements g2o::OptimizableGraph::Vertex.
Definition at line 79 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_hessian.
|
inlinevirtual |
maps the internal matrix to some external memory location
Implements g2o::OptimizableGraph::Vertex.
Definition at line 53 of file base_vertex.hpp.
References G2O_VERTEX_DIM.
|
delete |
|
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.
References g2o::BaseVertex< D, T >::_backup, g2o::BaseVertex< D, T >::_estimate, and g2o::OptimizableGraph::Vertex::updateCache().
|
inlinevirtual |
backup the position of the vertex to a stack
Implements g2o::OptimizableGraph::Vertex.
Definition at line 113 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_backup, and g2o::BaseVertex< D, T >::_estimate.
Referenced by g2o::findConnectedEdgesWithCostLimit().
|
inline |
set the estimate for the vertex also calls updateCache()
Definition at line 129 of file base_vertex.h.
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().
|
inlinevirtual |
updates the current vertex with the direct solution x += H_ii\b_ii
Implements g2o::OptimizableGraph::Vertex.
Definition at line 34 of file base_vertex.hpp.
References g2o_isnan, and G2O_VERTEX_DIM.
|
inlinevirtual |
return the stack size
Implements g2o::OptimizableGraph::Vertex.
Definition at line 124 of file base_vertex.h.
References g2o::BaseVertex< D, T >::_backup.
|
protected |
Definition at line 136 of file base_vertex.h.
Referenced by g2o::BaseVertex< D, T >::b(), g2o::BaseVertex< D, T >::b(), g2o::BaseVertex< D, T >::b(), g2o::BaseVertex< D, T >::b(), g2o::BaseVertex< D, T >::bData(), and g2o::BaseVertex< D, T >::copyB().
|
protected |
Definition at line 138 of file base_vertex.h.
Referenced by g2o::BaseVertex< D, T >::discardTop(), g2o::BaseVertex< D, T >::pop(), g2o::BaseVertex< D, T >::push(), and g2o::BaseVertex< D, T >::stackSize().
|
protected |
Definition at line 137 of file base_vertex.h.
Referenced by g2o::BaseVertex< D, T >::estimate(), PolynomialCoefficientVertex::oplusImpl(), PPolynomialCoefficientVertex::oplusImpl(), g2o::BaseVertex< D, T >::pop(), g2o::BaseVertex< D, T >::push(), PolynomialCoefficientVertex::read(), PPolynomialCoefficientVertex::read(), PolynomialCoefficientVertex::setDimensionImpl(), PPolynomialCoefficientVertex::setDimensionImpl(), g2o::BaseVertex< D, T >::setEstimate(), PolynomialCoefficientVertex::setToOriginImpl(), PPolynomialCoefficientVertex::setToOriginImpl(), PolynomialCoefficientVertex::write(), and PPolynomialCoefficientVertex::write().
|
protected |
Definition at line 135 of file base_vertex.h.
Referenced by g2o::BaseVertex< D, T >::A(), g2o::BaseVertex< D, T >::A(), g2o::BaseVertex< D, T >::hessian(), g2o::BaseVertex< D, T >::hessian(), g2o::BaseVertex< D, T >::hessianData(), and g2o::BaseVertex< D, T >::hessianDeterminant().
|
static |
dimension of the estimate (minimal) in the manifold space
Definition at line 56 of file base_vertex.h.