g2o
|
A general case Vertex for optimization. More...
#include <optimizable_graph.h>
Public Member Functions | |
Vertex () | |
virtual Vertex * | clone () const |
returns a deep copy of the current vertex More... | |
virtual | ~Vertex () |
void | setToOrigin () |
sets the node to the origin (used in the multilevel stuff) More... | |
virtual const double & | hessian (int i, int j) const =0 |
get the element from the hessian matrix More... | |
virtual double & | hessian (int i, int j)=0 |
virtual double | hessianDeterminant () const =0 |
virtual double * | hessianData ()=0 |
virtual void | mapHessianMemory (double *d)=0 |
virtual int | copyB (double *b_) const =0 |
virtual const double & | b (int i) const =0 |
get the b vector element More... | |
virtual double & | b (int i)=0 |
virtual double * | bData ()=0 |
return a pointer to the b vector associated with this vertex More... | |
virtual void | clearQuadraticForm ()=0 |
virtual double | solveDirect (double lambda=0)=0 |
bool | setEstimateData (const double *estimate) |
bool | setEstimateData (const std::vector< double > &estimate) |
virtual bool | getEstimateData (double *estimate) const |
virtual bool | getEstimateData (std::vector< double > &estimate) const |
virtual int | estimateDimension () const |
bool | setMinimalEstimateData (const double *estimate) |
bool | setMinimalEstimateData (const std::vector< double > &estimate) |
virtual bool | getMinimalEstimateData (double *estimate) const |
virtual bool | getMinimalEstimateData (std::vector< double > &estimate) const |
virtual int | minimalEstimateDimension () const |
virtual void | push ()=0 |
backup the position of the vertex to a stack More... | |
virtual void | pop ()=0 |
restore the position of the vertex by retrieving the position from the stack More... | |
virtual void | discardTop ()=0 |
pop the last element from the stack, without restoring the current estimate More... | |
virtual int | stackSize () const =0 |
return the stack size More... | |
void | oplus (const double *v) |
int | hessianIndex () const |
temporary index of this node in the parameter vector obtained from linearization More... | |
int | G2O_ATTRIBUTE_DEPRECATED (tempIndex() const) |
void | setHessianIndex (int ti) |
set the temporary index of the vertex in the parameter blocks More... | |
void | G2O_ATTRIBUTE_DEPRECATED (setTempIndex(int ti)) |
bool | fixed () const |
true => this node is fixed during the optimization More... | |
void | setFixed (bool fixed) |
true => this node should be considered fixed during the optimization More... | |
bool | marginalized () const |
true => this node is marginalized out during the optimization More... | |
void | setMarginalized (bool marginalized) |
true => this node should be marginalized out during the optimization More... | |
int | dimension () const |
dimension of the estimated state belonging to this node More... | |
virtual void | setId (int id) |
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id More... | |
void | setColInHessian (int c) |
set the row of this vertex in the Hessian More... | |
int | colInHessian () const |
get the row of this vertex in the Hessian More... | |
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 More... | |
virtual bool | write (std::ostream &os) const =0 |
write the vertex to a stream More... | |
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 More... | |
int | id () const |
returns the id More... | |
const EdgeSet & | edges () const |
returns the set of hyper-edges that are leaving/entering in this vertex More... | |
EdgeSet & | edges () |
returns the set of hyper-edges that are leaving/entering in this vertex More... | |
virtual HyperGraphElementType | elementType () 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) |
Protected Member Functions | |
virtual void | oplusImpl (const double *v)=0 |
virtual void | setToOriginImpl ()=0 |
sets the node to the origin (used in the multilevel stuff) More... | |
virtual bool | setEstimateDataImpl (const double *) |
virtual bool | setMinimalEstimateDataImpl (const double *) |
Protected Attributes | |
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 |
Friends | |
struct | OptimizableGraph |
A general case Vertex for optimization.
Definition at line 107 of file optimizable_graph.h.
g2o::OptimizableGraph::Vertex::Vertex | ( | ) |
Definition at line 53 of file optimizable_graph.cpp.
|
virtual |
Reimplemented from g2o::HyperGraph::Vertex.
Definition at line 74 of file optimizable_graph.cpp.
References _cacheContainer, and _userData.
|
pure virtual |
get the b vector element
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
|
pure virtual |
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
|
pure virtual |
return a pointer to the b vector associated with this vertex
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
Referenced by g2o::StructureOnlySolver< PointDoF >::calc().
CacheContainer * g2o::OptimizableGraph::Vertex::cacheContainer | ( | ) |
Definition at line 60 of file optimizable_graph.cpp.
References _cacheContainer.
Referenced by g2o::VertexPointXYWriteGnuplotAction::operator()(), g2o::VertexSE2WriteGnuplotAction::operator()(), g2o::deprecated::VertexSE3WriteGnuplotAction::operator()(), g2o::VertexSE3WriteGnuplotAction::operator()(), g2o::OptimizableGraph::Edge::resolveCache(), and g2o::VertexPointXYZ::write().
|
pure virtual |
set the b vector part of this vertex to zero
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
Referenced by g2o::BlockSolver< Traits >::buildSystem(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizerIncremental::updateInitialization(), and g2o::SparseOptimizerOnline::updateInitialization().
|
virtual |
returns a deep copy of the current vertex
Definition at line 80 of file optimizable_graph.cpp.
Referenced by g2o::OptimizableGraph::addGraph(), and main().
|
inline |
get the row of this vertex in the Hessian
Definition at line 291 of file optimizable_graph.h.
Referenced by g2o::BlockSolver< Traits >::buildSystem(), g2o::SparseOptimizerIncremental::optimize(), and g2o::SparseOptimizerOnline::optimize().
|
pure virtual |
copies the b vector in the array b_
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
Referenced by g2o::BlockSolver< Traits >::buildSystem(), g2o::SparseOptimizerIncremental::optimize(), and g2o::SparseOptimizerOnline::optimize().
|
inline |
dimension of the estimated state belonging to this node
Definition at line 283 of file optimizable_graph.h.
Referenced by g2o::BlockSolver< Traits >::buildStructure(), g2o::BlockSolver< Traits >::buildSystem(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::OptimizationAlgorithmLevenberg::computeLambdaInit(), g2o::computeSimpleStars(), g2o::OptimizableGraph::dimensions(), g2o::edgeAllVertsSameDim(), g2o::SparseOptimizer::findGauge(), g2o::SparseOptimizer::gaugeFreedom(), main(), g2o::OptimizableGraph::maxDimension(), g2o::SparseOptimizer::optimize(), MainWindow::prepare(), g2o::G2oSlamInterface::printVertex(), g2o::saveGnuplot(), g2o::SparseOptimizerIncremental::updateInitialization(), g2o::JacobianWorkspace::updateSize(), and g2o::BlockSolver< Traits >::updateStructure().
|
pure virtual |
pop the last element from the stack, without restoring the current estimate
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), and g2o::OptimizableGraph::discardTop().
|
virtual |
returns the dimension of the extended representation used by get/setEstimate(double*) -1 if it is not supported
Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::deprecated::VertexSE3, g2o::VertexSE2, g2o::VertexLine2D, g2o::deprecated::VertexPointXYZ, g2o::VertexPlane, g2o::VertexSegment2D, g2o::VertexPointXYZ, g2o::VertexLine3D, and g2o::VertexPointXY.
Definition at line 97 of file optimizable_graph.cpp.
Referenced by g2o::SparseOptimizer::initializeOptimization().
|
inline |
true => this node is fixed during the optimization
Definition at line 273 of file optimizable_graph.h.
Referenced by g2o::SparseOptimizer::buildIndexMapping(), g2o::BlockSolver< Traits >::buildSystem(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizer::computeInitialGuess(), g2o::SparseOptimizer::gaugeFreedom(), g2o::Edge_V_V_GICP::linearizeOplus(), main(), g2o::EstimatePropagator::PropagateAction::operator()(), g2o::OptimizableGraph::saveVertex(), g2o::SolverSLAM2DLinear::solveOrientation(), g2o::SparseOptimizerIncremental::updateInitialization(), and g2o::SparseOptimizer::updateInitialization().
|
inline |
Definition at line 267 of file optimizable_graph.h.
|
inline |
Definition at line 270 of file optimizable_graph.h.
|
virtual |
writes the estimater to an array of double
Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::deprecated::VertexSE3, g2o::VertexSE2, g2o::VertexLine2D, g2o::deprecated::VertexPointXYZ, g2o::VertexPlane, g2o::VertexSegment2D, g2o::VertexPointXYZ, g2o::VertexLine3D, and g2o::VertexPointXY.
Definition at line 92 of file optimizable_graph.cpp.
Referenced by g2o::SparseOptimizer::initializeOptimization().
|
inlinevirtual |
writes the estimater to an array of double
Definition at line 183 of file optimizable_graph.h.
|
virtual |
writes the estimate to an array of double
Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::deprecated::VertexSE3, g2o::VertexLine2D, g2o::deprecated::VertexPointXYZ, g2o::VertexSE2, g2o::VertexSegment2D, g2o::VertexPointXYZ, and g2o::VertexPointXY.
Definition at line 109 of file optimizable_graph.cpp.
Referenced by testMarginals().
|
inlinevirtual |
writes the estimate to an array of double
Definition at line 227 of file optimizable_graph.h.
|
inline |
Definition at line 293 of file optimizable_graph.h.
Referenced by g2o::activeVertexChi(), MainWindow::fixGraph(), g2o::OptimizableGraph::Edge::graph(), and g2o::VertexLine2D::write().
|
inline |
Definition at line 294 of file optimizable_graph.h.
|
pure virtual |
get the element from the hessian matrix
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
Referenced by g2o::OptimizationAlgorithmLevenberg::computeLambdaInit(), and g2o::computeSimpleStars().
|
pure virtual |
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
|
pure virtual |
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
Referenced by g2o::SparseOptimizerIncremental::updateInitialization().
|
pure virtual |
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
|
inline |
temporary index of this node in the parameter vector obtained from linearization
Definition at line 266 of file optimizable_graph.h.
Referenced by g2o::EdgeLabeler::augmentSparsePattern(), g2o::BlockSolver< Traits >::buildStructure(), g2o::SparseOptimizer::computeInitialGuess(), g2o::EdgeLabeler::labelEdge(), g2o::Star::labelStarEdges(), main(), g2o::SparseOptimizerIncremental::optimize(), g2o::ThetaTreeAction::perform(), g2o::SparseOptimizer::removeVertex(), g2o::SolverSLAM2DLinear::solveOrientation(), testMarginals(), g2o::SparseOptimizerIncremental::updateInitialization(), and g2o::BlockSolver< Traits >::updateStructure().
|
inline |
lock for the block of the hessian and the b vector associated with this vertex, to avoid race-conditions if multi-threaded.
Definition at line 300 of file optimizable_graph.h.
|
pure virtual |
maps the internal matrix to some external memory location
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
Referenced by g2o::BlockSolver< Traits >::buildStructure(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizerIncremental::updateInitialization(), and g2o::BlockSolver< Traits >::updateStructure().
|
inline |
true => this node is marginalized out during the optimization
Definition at line 278 of file optimizable_graph.h.
Referenced by g2o::SparseOptimizer::buildIndexMapping(), g2o::BlockSolver< Traits >::buildStructure(), g2o::BlockSolver< Traits >::buildSystem(), g2o::OptimizationAlgorithmWithHessian::init(), g2o::StructureOnlySolver< PointDoF >::init(), main(), g2o::SparseOptimizerIncremental::updateInitialization(), g2o::SparseOptimizer::updateInitialization(), and g2o::BlockSolver< Traits >::updateStructure().
|
virtual |
returns the dimension of the extended representation used by get/setEstimate(double*) -1 if it is not supported
Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::deprecated::VertexSE3, g2o::deprecated::VertexPointXYZ, g2o::VertexLine2D, g2o::VertexSE2, g2o::VertexPointXYZ, g2o::VertexSegment2D, and g2o::VertexPointXY.
Definition at line 114 of file optimizable_graph.cpp.
Referenced by g2o::EdgeLabeler::labelEdge(), and testMarginals().
|
inline |
Update the position of the node from the parameters in v. Depends on the implementation of oplusImpl in derived classes to actually carry out the update. Will also call updateCache() to update the caches of depending on the vertex.
Definition at line 259 of file optimizable_graph.h.
Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), g2o::EdgeLabeler::labelEdge(), g2o::SparseOptimizer::optimize(), and testMarginals().
|
protectedpure virtual |
update the position of the node from the parameters in v. Implement in your class!
Implemented in g2o::VertexSCam, g2o::VertexSBAPointXYZ, VertexPointBAL, g2o::VertexSE3, g2o::VertexSE3Expmap, g2o::deprecated::VertexSE3, g2o::VertexCam, VertexCameraBAL, g2o::VertexLine2D, VertexCircle, g2o::VertexSegment2D, g2o::VertexPointXY, VertexParams, VertexBaseline, VertexPositionVelocity3D, g2o::VertexIntrinsics, VertexVelocity3D, g2o::VertexSim3Expmap, g2o::tutorial::VertexSE2, g2o::deprecated::VertexPointXYZ, g2o::VertexSE2, g2o::VertexPlane, g2o::tutorial::VertexPointXY, g2o::VertexPointXYZ, g2o::VertexLine3D, g2o::OnlineVertexSE2, g2o::OnlineVertexSE3, g2o::VertexOdomDifferentialParams, VertexPosition3D, and VertexPosition3D.
|
pure virtual |
restore the position of the vertex by retrieving the position from the stack
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), g2o::EdgeLabeler::labelEdge(), g2o::Star::labelStarEdges(), g2o::SparseOptimizer::pop(), g2o::OptimizableGraph::pop(), and testMarginals().
|
pure virtual |
backup the position of the vertex to a stack
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizer::computeInitialGuess(), g2o::EdgeLabeler::labelEdge(), g2o::Star::labelStarEdges(), g2o::SparseOptimizer::push(), g2o::OptimizableGraph::push(), and testMarginals().
|
pure virtual |
read the vertex from a stream, i.e., the internal state of the vertex
Implemented in g2o::VertexSCam, g2o::VertexSBAPointXYZ, VertexPointBAL, g2o::VertexLine2D, g2o::VertexSE3Expmap, g2o::VertexSegment2D, g2o::VertexPointXY, g2o::VertexSE2, g2o::VertexCam, VertexCameraBAL, VertexPositionVelocity3D, VertexCircle, VertexBaseline, VertexVelocity3D, g2o::VertexSE3, g2o::tutorial::VertexSE2, g2o::tutorial::VertexPointXY, g2o::deprecated::VertexSE3, VertexParams, g2o::VertexIntrinsics, g2o::VertexOdomDifferentialParams, g2o::VertexSim3Expmap, g2o::deprecated::VertexPointXYZ, g2o::VertexPlane, g2o::VertexSE3Euler, g2o::VertexPointXYZ, g2o::VertexLine3D, VertexPosition3D, and VertexPosition3D.
Referenced by g2o::OptimizableGraph::setFixed().
|
inline |
set the row of this vertex in the Hessian
Definition at line 289 of file optimizable_graph.h.
Referenced by g2o::BlockSolver< Traits >::buildStructure(), and g2o::BlockSolver< Traits >::updateStructure().
bool g2o::OptimizableGraph::Vertex::setEstimateData | ( | const double * | estimate | ) |
sets the initial estimate from an array of double Implement setEstimateDataImpl()
Definition at line 85 of file optimizable_graph.cpp.
References setEstimateDataImpl(), and updateCache().
|
inline |
sets the initial estimate from an array of double Implement setEstimateDataImpl()
Definition at line 165 of file optimizable_graph.h.
|
inlineprotectedvirtual |
writes the estimater to an array of double
Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::VertexSE2, g2o::deprecated::VertexSE3, g2o::VertexLine2D, g2o::deprecated::VertexPointXYZ, g2o::VertexPlane, g2o::VertexSegment2D, g2o::VertexPointXYZ, g2o::VertexLine3D, and g2o::VertexPointXY.
Definition at line 339 of file optimizable_graph.h.
Referenced by setEstimateData().
|
inline |
true => this node should be considered fixed during the optimization
Definition at line 275 of file optimizable_graph.h.
Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), MainWindow::fixGraph(), g2o::G2oSlamInterface::fixNode(), g2o::Star::labelStarEdges(), main(), and g2o::OptimizableGraph::setFixed().
|
inline |
set the temporary index of the vertex in the parameter blocks
Definition at line 269 of file optimizable_graph.h.
Referenced by g2o::OptimizableGraph::addGraph(), g2o::SparseOptimizer::buildIndexMapping(), g2o::SparseOptimizerIncremental::updateInitialization(), and g2o::SparseOptimizer::updateInitialization().
|
inlinevirtual |
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id
Reimplemented from g2o::HyperGraph::Vertex.
Definition at line 286 of file optimizable_graph.h.
Referenced by g2o::G2oSlamInterface::addVertex(), main(), Robot::move(), PlaneItem::PlaneItem(), g2o::Gm2dlIO::readGm2dl(), and g2o::OptimizableGraph::setFixed().
|
inline |
true => this node should be marginalized out during the optimization
Definition at line 280 of file optimizable_graph.h.
Referenced by main(), and MainWindow::prepare().
bool g2o::OptimizableGraph::Vertex::setMinimalEstimateData | ( | const double * | estimate | ) |
sets the initial estimate from an array of double. Implement setMinimalEstimateDataImpl()
Definition at line 102 of file optimizable_graph.cpp.
References setMinimalEstimateDataImpl(), and updateCache().
|
inline |
sets the initial estimate from an array of double. Implement setMinimalEstimateDataImpl()
Definition at line 209 of file optimizable_graph.h.
|
inlineprotectedvirtual |
sets the initial estimate from an array of double
Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::deprecated::VertexSE3, g2o::VertexLine2D, g2o::VertexSE2, g2o::deprecated::VertexPointXYZ, g2o::VertexSegment2D, g2o::VertexPointXYZ, and g2o::VertexPointXY.
Definition at line 345 of file optimizable_graph.h.
Referenced by setMinimalEstimateData().
|
inline |
sets the node to the origin (used in the multilevel stuff)
Definition at line 119 of file optimizable_graph.h.
Referenced by g2o::SparseOptimizer::setToOrigin().
|
protectedpure virtual |
sets the node to the origin (used in the multilevel stuff)
Implemented in g2o::VertexSBAPointXYZ, VertexPointBAL, g2o::VertexSE3Expmap, VertexCameraBAL, VertexCircle, g2o::VertexCam, VertexParams, VertexBaseline, VertexPositionVelocity3D, g2o::VertexSE3, g2o::VertexLine2D, g2o::VertexIntrinsics, VertexVelocity3D, g2o::deprecated::VertexSE3, g2o::VertexSim3Expmap, g2o::VertexSegment2D, g2o::deprecated::VertexPointXYZ, g2o::VertexPlane, g2o::tutorial::VertexSE2, g2o::VertexSE2, g2o::VertexPointXYZ, g2o::tutorial::VertexPointXY, g2o::VertexPointXY, g2o::VertexLine3D, g2o::VertexOdomDifferentialParams, VertexPosition3D, and VertexPosition3D.
|
pure virtual |
updates the current vertex with the direct solution x += H_ii
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
Referenced by g2o::computeSimpleStars().
|
pure virtual |
return the stack size
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 6, Isometry3D >, g2o::BaseVertex< 3, Eigen::Vector3d >, g2o::BaseVertex< 6, Line3D >, g2o::BaseVertex< 4, Eigen::Matrix< double, 5, 1, Eigen::ColMajor > >, g2o::BaseVertex< 4, Vector4D >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 2, Vector2D >, g2o::BaseVertex< 1, double >, g2o::BaseVertex< 3, Plane3D >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3D >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 2, Eigen::Vector2d >, g2o::BaseVertex< 2, Line2D >, g2o::BaseVertex< 9, Eigen::VectorXd >, g2o::BaseVertex< 6, SE3Quat >, and g2o::BaseVertex< 6, Vector6d >.
|
inline |
unlock the block of the hessian and the b vector associated with this vertex
Definition at line 304 of file optimizable_graph.h.
|
virtual |
Definition at line 67 of file optimizable_graph.cpp.
References _cacheContainer, g2o::CacheContainer::setUpdateNeeded(), and g2o::CacheContainer::update().
Referenced by g2o::BaseVertex< 6, Vector6d >::pop(), g2o::deprecated::VertexSE3::read(), g2o::BaseVertex< 6, Vector6d >::setEstimate(), setEstimateData(), setMinimalEstimateData(), g2o::deprecated::VertexSE3::VertexSE3(), and g2o::VertexSE3::VertexSE3().
|
pure virtual |
write the vertex to a stream
Implemented in g2o::VertexSCam, g2o::VertexSBAPointXYZ, VertexPointBAL, g2o::VertexSE3Expmap, g2o::VertexLine2D, g2o::VertexSegment2D, g2o::VertexPointXY, g2o::VertexSE2, VertexCameraBAL, g2o::VertexCam, VertexPositionVelocity3D, VertexCircle, VertexVelocity3D, VertexBaseline, g2o::VertexSE3, VertexParams, g2o::tutorial::VertexSE2, g2o::tutorial::VertexPointXY, g2o::deprecated::VertexSE3, g2o::VertexIntrinsics, g2o::VertexOdomDifferentialParams, g2o::VertexSim3Expmap, g2o::deprecated::VertexPointXYZ, g2o::VertexPlane, g2o::VertexSE3Euler, g2o::VertexPointXYZ, g2o::VertexLine3D, VertexPosition3D, and VertexPosition3D.
Referenced by g2o::OptimizableGraph::saveVertex(), and g2o::Gm2dlIO::writeGm2dl().
|
friend |
Definition at line 109 of file optimizable_graph.h.
|
protected |
Definition at line 324 of file optimizable_graph.h.
Referenced by cacheContainer(), updateCache(), and ~Vertex().
|
protected |
Definition at line 321 of file optimizable_graph.h.
|
protected |
Definition at line 320 of file optimizable_graph.h.
|
protected |
Definition at line 318 of file optimizable_graph.h.
|
protected |
Definition at line 315 of file optimizable_graph.h.
Referenced by g2o::OptimizableGraph::addVertex().
|
protected |
Definition at line 317 of file optimizable_graph.h.
|
protected |
Definition at line 319 of file optimizable_graph.h.
Referenced by g2o::VertexSim3Expmap::VertexSim3Expmap().
|
protected |
Definition at line 322 of file optimizable_graph.h.
|
protected |
Definition at line 316 of file optimizable_graph.h.
Referenced by ~Vertex().