g2o
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
g2o::OptimizableGraph::Vertex Class Referenceabstract

A general case Vertex for optimization. More...

#include <optimizable_graph.h>

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

Public Member Functions

 Vertex ()
 
virtual ~Vertex ()
 
void setToOrigin ()
 sets the node to the origin (used in the multilevel stuff)
 
virtual const double & hessian (int i, int j) const =0
 get the element from the hessian matrix
 
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
 
virtual double & b (int i)=0
 
virtual double * bData ()=0
 return a pointer to the b vector associated with this vertex
 
virtual void clearQuadraticForm ()=0
 
virtual double solveDirect (double lambda=0)=0
 
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
 
virtual void push ()=0
 backup the position of the vertex to a stack
 
virtual void pop ()=0
 
virtual void discardTop ()=0
 
virtual int stackSize () const =0
 return the stack size
 
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)
 

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)
 
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
 

Detailed Description

A general case Vertex for optimization.

Definition at line 107 of file optimizable_graph.h.

Constructor & Destructor Documentation

◆ Vertex()

g2o::OptimizableGraph::Vertex::Vertex ( )

◆ ~Vertex()

g2o::OptimizableGraph::Vertex::~Vertex ( )
virtual

Reimplemented from g2o::HyperGraph::Vertex.

Definition at line 78 of file optimizable_graph.cpp.

78 {
79 delete _cacheContainer;
80 delete _userData;
81}

Member Function Documentation

◆ b() [1/2]

virtual const double & g2o::OptimizableGraph::Vertex::b ( int  i) const
pure virtual

◆ b() [2/2]

virtual double & g2o::OptimizableGraph::Vertex::b ( int  i)
pure virtual

◆ bData()

virtual double * g2o::OptimizableGraph::Vertex::bData ( )
pure virtual

◆ cacheContainer()

CacheContainer * g2o::OptimizableGraph::Vertex::cacheContainer ( )

Definition at line 66 of file optimizable_graph.cpp.

66 {
67 if (!_cacheContainer) _cacheContainer = new CacheContainer(this);
68 return _cacheContainer;
69}

Referenced by g2o::OptimizableGraph::Edge::resolveCache().

◆ clearQuadraticForm()

virtual void g2o::OptimizableGraph::Vertex::clearQuadraticForm ( )
pure virtual

◆ colInHessian()

int g2o::OptimizableGraph::Vertex::colInHessian ( ) const
inline

get the row of this vertex in the Hessian

Definition at line 357 of file optimizable_graph.h.

357{ return _colInHessian; }

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

◆ copyB()

virtual int g2o::OptimizableGraph::Vertex::copyB ( double *  b_) const
pure virtual

◆ dimension()

int g2o::OptimizableGraph::Vertex::dimension ( ) const
inline

◆ discardTop()

virtual void g2o::OptimizableGraph::Vertex::discardTop ( )
pure virtual

◆ estimateDimension()

int g2o::OptimizableGraph::Vertex::estimateDimension ( ) const
virtual

returns the dimension of the extended representation used by get/setEstimate(double*) -1 if it is not supported

Reimplemented in g2o::VertexCam, g2o::VertexPointXY, g2o::VertexSE2, g2o::VertexLine2D, g2o::VertexSegment2D, g2o::VertexPointXYZ, g2o::VertexSE3, g2o::VertexLine3D, and g2o::VertexPlane.

Definition at line 91 of file optimizable_graph.cpp.

91{ return -1; }

Referenced by g2o::SparseOptimizer::initializeOptimization().

◆ fixed()

bool g2o::OptimizableGraph::Vertex::fixed ( ) const
inline

◆ G2O_ATTRIBUTE_DEPRECATED() [1/2]

void g2o::OptimizableGraph::Vertex::G2O_ATTRIBUTE_DEPRECATED ( setTempIndex(int ti)  )
inline

Definition at line 335 of file optimizable_graph.h.

335{ setHessianIndex(ti); }
void setHessianIndex(int ti)
set the temporary index of the vertex in the parameter blocks

◆ G2O_ATTRIBUTE_DEPRECATED() [2/2]

int g2o::OptimizableGraph::Vertex::G2O_ATTRIBUTE_DEPRECATED ( tempIndex() const  )
inline

Definition at line 332 of file optimizable_graph.h.

332{ return hessianIndex(); }

◆ getEstimateData() [1/3]

bool g2o::OptimizableGraph::Vertex::getEstimateData ( double *  estimate) const
virtual

writes the estimater to an array of double

Returns
true on success

Reimplemented in g2o::VertexCam, g2o::VertexPointXY, g2o::VertexSE2, g2o::VertexLine2D, g2o::VertexSegment2D, g2o::VertexPointXYZ, g2o::VertexSE3, g2o::VertexLine3D, and g2o::VertexPlane.

Definition at line 89 of file optimizable_graph.cpp.

89{ return false; }

Referenced by g2o::SparseOptimizer::initializeOptimization().

◆ getEstimateData() [2/3]

template<typename Derived >
bool g2o::OptimizableGraph::Vertex::getEstimateData ( Eigen::MatrixBase< Derived > &  estimate) const
inline

writes the estimater to an array of double

Returns
true on success

Definition at line 206 of file optimizable_graph.h.

206 {
207 int dim = estimateDimension();
208 // If dim is -ve, getEstimateData is not implemented and fails
209 if (dim < 0) return false;
210
211 // If the vector isn't the right size to store the estimate, try to resize
212 // it. This only works if the vector is dynamic. If it is static, fail.
213 if (estimate.size() != dim) {
214 if ((estimate.RowsAtCompileTime == Eigen::Dynamic) ||
215 (estimate.ColsAtCompileTime == Eigen::Dynamic))
216 estimate.derived().resize(dim);
217 else
218 return false;
219 }
220 return getEstimateData(estimate.derived().data());
221 };
virtual bool getEstimateData(double *estimate) const
virtual int estimateDimension() const

◆ getEstimateData() [3/3]

virtual bool g2o::OptimizableGraph::Vertex::getEstimateData ( std::vector< double > &  estimate) const
inlinevirtual

writes the estimater to an array of double

Returns
true on success

Definition at line 194 of file optimizable_graph.h.

194 {
195 int dim = estimateDimension();
196 if (dim < 0) return false;
197 estimate.resize(dim);
198 return getEstimateData(&estimate[0]);
199 };

◆ getMinimalEstimateData() [1/3]

bool g2o::OptimizableGraph::Vertex::getMinimalEstimateData ( double *  estimate) const
virtual

writes the estimate to an array of double

Returns
true on success

Reimplemented in g2o::VertexCam, g2o::VertexPointXY, g2o::VertexSE2, g2o::VertexLine2D, g2o::VertexSegment2D, g2o::VertexPointXYZ, and g2o::VertexSE3.

Definition at line 99 of file optimizable_graph.cpp.

99 {
100 return false;
101}

Referenced by testMarginals().

◆ getMinimalEstimateData() [2/3]

template<typename Derived >
bool g2o::OptimizableGraph::Vertex::getMinimalEstimateData ( Eigen::MatrixBase< Derived > &  estimate) const
inline

writes the estimate to an eigen type double

Returns
true on success

Definition at line 281 of file optimizable_graph.h.

281 {
282 int dim = minimalEstimateDimension();
283 // If dim is -ve, getMinimalEstimateData is not implemented and fails
284 if (dim < 0) return false;
285
286 // If the vector isn't the right size to store the estimate, try to resize
287 // it. This only works if the vector is dynamic. If it is static, fail.
288 if (estimate.size() != dim) {
289 if ((estimate.RowsAtCompileTime == Eigen::Dynamic) ||
290 (estimate.ColsAtCompileTime == Eigen::Dynamic))
291 estimate.derived().resize(dim);
292 else
293 return false;
294 }
295 return getMinimalEstimateData(estimate.derived().data());
296 };
virtual bool getMinimalEstimateData(double *estimate) const
virtual int minimalEstimateDimension() const

◆ getMinimalEstimateData() [3/3]

virtual bool g2o::OptimizableGraph::Vertex::getMinimalEstimateData ( std::vector< double > &  estimate) const
inlinevirtual

writes the estimate to an array of double

Returns
true on success

Definition at line 269 of file optimizable_graph.h.

269 {
270 int dim = minimalEstimateDimension();
271 if (dim < 0) return false;
272 estimate.resize(dim);
273 return getMinimalEstimateData(&estimate[0]);
274 };

◆ graph() [1/2]

OptimizableGraph * g2o::OptimizableGraph::Vertex::graph ( )
inline

Definition at line 360 of file optimizable_graph.h.

360{ return _graph; }

◆ graph() [2/2]

const OptimizableGraph * g2o::OptimizableGraph::Vertex::graph ( ) const
inline

◆ hessian() [1/2]

virtual const double & g2o::OptimizableGraph::Vertex::hessian ( int  i,
int  j 
) const
pure virtual

◆ hessian() [2/2]

virtual double & g2o::OptimizableGraph::Vertex::hessian ( int  i,
int  j 
)
pure virtual

◆ hessianData()

virtual double * g2o::OptimizableGraph::Vertex::hessianData ( )
pure virtual

◆ hessianDeterminant()

virtual double g2o::OptimizableGraph::Vertex::hessianDeterminant ( ) const
pure virtual

◆ hessianIndex()

int g2o::OptimizableGraph::Vertex::hessianIndex ( ) const
inline

◆ lockQuadraticForm()

void g2o::OptimizableGraph::Vertex::lockQuadraticForm ( )
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 366 of file optimizable_graph.h.

◆ mapHessianMemory()

virtual void g2o::OptimizableGraph::Vertex::mapHessianMemory ( double *  d)
pure virtual

◆ marginalized()

bool g2o::OptimizableGraph::Vertex::marginalized ( ) const
inline

◆ minimalEstimateDimension()

int g2o::OptimizableGraph::Vertex::minimalEstimateDimension ( ) const
virtual

returns the dimension of the extended representation used by get/setEstimate(double*) -1 if it is not supported

Reimplemented in g2o::VertexCam, g2o::VertexPointXY, g2o::VertexSE2, g2o::VertexLine2D, g2o::VertexSegment2D, g2o::VertexPointXYZ, and g2o::VertexSE3.

Definition at line 103 of file optimizable_graph.cpp.

103{ return -1; }

Referenced by g2o::EdgeLabeler::labelEdge(), and testMarginals().

◆ oplus()

void g2o::OptimizableGraph::Vertex::oplus ( const double *  v)
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 324 of file optimizable_graph.h.

324 {
325 oplusImpl(v);
326 updateCache();
327 }
virtual void oplusImpl(const double *v)=0

Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), g2o::EdgeLabeler::labelEdge(), testMarginals(), and g2o::SparseOptimizer::update().

◆ oplusImpl()

virtual void g2o::OptimizableGraph::Vertex::oplusImpl ( const double *  v)
protectedpure virtual

◆ pop()

virtual void g2o::OptimizableGraph::Vertex::pop ( )
pure virtual

◆ push()

virtual void g2o::OptimizableGraph::Vertex::push ( )
pure virtual

◆ read()

virtual bool g2o::OptimizableGraph::Vertex::read ( std::istream &  is)
pure virtual

◆ setColInHessian()

void g2o::OptimizableGraph::Vertex::setColInHessian ( int  c)
inline

set the row of this vertex in the Hessian

Definition at line 355 of file optimizable_graph.h.

355{ _colInHessian = c; }

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

◆ setEstimateData() [1/3]

bool g2o::OptimizableGraph::Vertex::setEstimateData ( const double *  estimate)

sets the initial estimate from an array of double Implement setEstimateDataImpl()

Returns
true on success

Definition at line 83 of file optimizable_graph.cpp.

83 {
84 bool ret = setEstimateDataImpl(v);
86 return ret;
87}
virtual bool setEstimateDataImpl(const double *)

◆ setEstimateData() [2/3]

template<typename Derived >
bool g2o::OptimizableGraph::Vertex::setEstimateData ( const Eigen::MatrixBase< Derived > &  estimate)
inline

sets the initial estimate from an array of double Implement setEstimateDataImpl()

Returns
true on success

Definition at line 178 of file optimizable_graph.h.

178 {
179 int dim = estimateDimension();
180 if ((dim == -1) || (estimate.size() != dim)) return false;
181 return setEstimateData(estimate.derived().data());
182 };
bool setEstimateData(const double *estimate)

◆ setEstimateData() [3/3]

bool g2o::OptimizableGraph::Vertex::setEstimateData ( const std::vector< double > &  estimate)
inline

sets the initial estimate from an array of double Implement setEstimateDataImpl()

Returns
true on success

Definition at line 166 of file optimizable_graph.h.

166 {
167 int dim = estimateDimension();
168 if ((dim == -1) || (estimate.size() != std::size_t(dim))) return false;
169 return setEstimateData(&estimate[0]);
170 };

◆ setEstimateDataImpl()

virtual bool g2o::OptimizableGraph::Vertex::setEstimateDataImpl ( const double *  )
inlineprotectedvirtual

writes the estimater to an array of double

Returns
true on success

Reimplemented in g2o::VertexCam, g2o::VertexPointXY, g2o::VertexSE2, g2o::VertexLine2D, g2o::VertexSegment2D, g2o::VertexPointXYZ, g2o::VertexSE3, g2o::VertexLine3D, and g2o::VertexPlane.

Definition at line 407 of file optimizable_graph.h.

407{ return false; }

◆ setFixed()

void g2o::OptimizableGraph::Vertex::setFixed ( bool  fixed)
inline

true => this node should be considered fixed during the optimization

Definition at line 340 of file optimizable_graph.h.

340{ _fixed = fixed; }
bool fixed() const
true => this node is fixed during the optimization

Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), MainWindow::fixGraph(), g2o::G2oSlamInterface::fixNode(), g2o::Star::labelStarEdges(), main(), main(), main(), and g2o::OptimizableGraph::setFixed().

◆ setHessianIndex()

void g2o::OptimizableGraph::Vertex::setHessianIndex ( int  ti)
inline

set the temporary index of the vertex in the parameter blocks

Definition at line 334 of file optimizable_graph.h.

334{ _hessianIndex = ti; }

Referenced by g2o::SparseOptimizer::buildIndexMapping(), g2o::SparseOptimizer::updateInitialization(), and g2o::SparseOptimizerIncremental::updateInitialization().

◆ setId()

virtual void g2o::OptimizableGraph::Vertex::setId ( int  id)
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 352 of file optimizable_graph.h.

352{ _id = id; }
int id() const
returns the id

Referenced by g2o::G2oSlamInterface::addVertex(), LineInfo::LineInfo(), LineItem::LineItem(), LineSensor::LineSensor(), main(), main(), main(), Robot::move(), PlaneItem::PlaneItem(), PlaneSensor::PlaneSensor(), and g2o::Gm2dlIO::readGm2dl().

◆ setMarginalized()

void g2o::OptimizableGraph::Vertex::setMarginalized ( bool  marginalized)
inline

true => this node should be marginalized out during the optimization

Definition at line 345 of file optimizable_graph.h.

bool marginalized() const
true => this node is marginalized out during the optimization

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

◆ setMinimalEstimateData() [1/3]

bool g2o::OptimizableGraph::Vertex::setMinimalEstimateData ( const double *  estimate)

sets the initial estimate from an array of double. Implement setMinimalEstimateDataImpl()

Returns
true on success

Definition at line 93 of file optimizable_graph.cpp.

93 {
94 bool ret = setMinimalEstimateDataImpl(v);
96 return ret;
97}
virtual bool setMinimalEstimateDataImpl(const double *)

◆ setMinimalEstimateData() [2/3]

template<typename Derived >
bool g2o::OptimizableGraph::Vertex::setMinimalEstimateData ( const Eigen::MatrixBase< Derived > &  estimate)
inline

sets the initial estimate from an eigen type of double. Implement setMinimalEstimateDataImpl()

Returns
true on success

Definition at line 253 of file optimizable_graph.h.

253 {
254 int dim = minimalEstimateDimension();
255 if ((dim == -1) || (estimate.size() != dim)) return false;
256 return setMinimalEstimateData(estimate.derived().data());
257 };
bool setMinimalEstimateData(const double *estimate)

◆ setMinimalEstimateData() [3/3]

bool g2o::OptimizableGraph::Vertex::setMinimalEstimateData ( const std::vector< double > &  estimate)
inline

sets the initial estimate from an array of double. Implement setMinimalEstimateDataImpl()

Returns
true on success

Definition at line 241 of file optimizable_graph.h.

241 {
242 int dim = minimalEstimateDimension();
243 if ((dim == -1) || (estimate.size() != std::size_t(dim))) return false;
244 return setMinimalEstimateData(&estimate[0]);
245 };

◆ setMinimalEstimateDataImpl()

virtual bool g2o::OptimizableGraph::Vertex::setMinimalEstimateDataImpl ( const double *  )
inlineprotectedvirtual

sets the initial estimate from an array of double

Returns
true on success

Reimplemented in g2o::VertexCam, g2o::VertexPointXY, g2o::VertexSE2, g2o::VertexLine2D, g2o::VertexSegment2D, g2o::VertexPointXYZ, and g2o::VertexSE3.

Definition at line 413 of file optimizable_graph.h.

413{ return false; }

◆ setToOrigin()

void g2o::OptimizableGraph::Vertex::setToOrigin ( )
inline

sets the node to the origin (used in the multilevel stuff)

Definition at line 117 of file optimizable_graph.h.

117 {
119 updateCache();
120 }
virtual void setToOriginImpl()=0
sets the node to the origin (used in the multilevel stuff)

Referenced by FPolynomialCoefficientVertex::FPolynomialCoefficientVertex(), g2o::SparseOptimizer::setToOrigin(), and g2o::SolverSLAM2DLinear::solveOrientation().

◆ setToOriginImpl()

virtual void g2o::OptimizableGraph::Vertex::setToOriginImpl ( )
protectedpure virtual

◆ solveDirect()

virtual double g2o::OptimizableGraph::Vertex::solveDirect ( double  lambda = 0)
pure virtual

◆ stackSize()

virtual int g2o::OptimizableGraph::Vertex::stackSize ( ) const
pure virtual

◆ unlockQuadraticForm()

void g2o::OptimizableGraph::Vertex::unlockQuadraticForm ( )
inline

unlock the block of the hessian and the b vector associated with this vertex

Definition at line 371 of file optimizable_graph.h.

◆ updateCache()

void g2o::OptimizableGraph::Vertex::updateCache ( )
virtual

◆ write()

virtual bool g2o::OptimizableGraph::Vertex::write ( std::ostream &  os) const
pure virtual

Friends And Related Symbol Documentation

◆ OptimizableGraph

friend struct OptimizableGraph
friend

Definition at line 110 of file optimizable_graph.h.

Member Data Documentation

◆ _cacheContainer

CacheContainer* g2o::OptimizableGraph::Vertex::_cacheContainer
protected

Definition at line 392 of file optimizable_graph.h.

◆ _colInHessian

int g2o::OptimizableGraph::Vertex::_colInHessian
protected

Definition at line 389 of file optimizable_graph.h.

◆ _dimension

int g2o::OptimizableGraph::Vertex::_dimension
protected

◆ _fixed

bool g2o::OptimizableGraph::Vertex::_fixed
protected

Definition at line 386 of file optimizable_graph.h.

◆ _graph

OptimizableGraph* g2o::OptimizableGraph::Vertex::_graph
protected

Definition at line 383 of file optimizable_graph.h.

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

◆ _hessianIndex

int g2o::OptimizableGraph::Vertex::_hessianIndex
protected

Definition at line 385 of file optimizable_graph.h.

◆ _marginalized

bool g2o::OptimizableGraph::Vertex::_marginalized
protected

Definition at line 387 of file optimizable_graph.h.

Referenced by g2o::VertexSim3Expmap::VertexSim3Expmap().

◆ _quadraticFormMutex

OpenMPMutex g2o::OptimizableGraph::Vertex::_quadraticFormMutex
protected

Definition at line 390 of file optimizable_graph.h.

◆ _userData

Data* g2o::OptimizableGraph::Vertex::_userData
protected

Definition at line 384 of file optimizable_graph.h.


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