A general case Vertex for optimization. More...
#include <optimizable_graph.h>
Public Member Functions | |
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 Vertex * | clone () const |
returns a deep copy of the current vertex | |
int | colInHessian () const |
get the row of this vertex in the Hessian | |
virtual int | copyB (double *b_) const =0 |
int | dimension () const |
dimension of the estimated state belonging to this node | |
virtual void | discardTop ()=0 |
pop the last element from the stack, without restoring the current estimate | |
virtual int | estimateDimension () const |
bool | fixed () const |
true => this node is fixed during the optimization | |
virtual bool | getEstimateData (double *estimate) const |
virtual bool | getMinimalEstimateData (double *estimate) const |
const OptimizableGraph * | graph () const |
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 * | hessianData ()=0 |
virtual double | hessianDeterminant () const =0 |
void | lockQuadraticForm () |
virtual void | mapHessianMemory (double *d)=0 |
bool | marginalized () const |
true => this node is marginalized out during the optimization | |
virtual int | minimalEstimateDimension () const |
virtual void | oplus (double *v)=0 |
update the position of the node from the parameters in v | |
virtual void | pop ()=0 |
restore the position of the vertex by retrieving the position from the stack | |
virtual void | push ()=0 |
backup the position of the vertex to a stack | |
virtual bool | read (std::istream &is)=0 |
read the vertex from a stream, i.e., the internal state of the vertex | |
void | setColInHessian (int c) |
set the row of this vertex in the Hessian | |
virtual bool | setEstimateData (const double *estimate) |
void | setFixed (bool fixed) |
true => this node should be considered fixed during the optimization | |
void | setId (int id) |
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id | |
void | setMarginalized (bool marginalized) |
true => this node should be marginalized out during the optimization | |
virtual bool | setMinimalEstimateData (const double *estimate) |
void | setTempIndex (int ti) |
set the temporary index of the vertex in the parameter blocks | |
virtual void | setToOrigin ()=0 |
sets the node to the origin (used in the multilevel stuff) | |
virtual void | setUncertainty (double *c)=0 |
sets the covariance/information of the node, used internally | |
void | setUserData (Data *obs) |
virtual double | solveDirect (double lambda=0)=0 |
virtual int | stackSize () const =0 |
return the stack size | |
int | tempIndex () const |
temporary index of this node in the parameter vector obtained from linearization | |
virtual double * | uncertaintyData ()=0 |
return the pointer to the uncertainty (marginal covariance) | |
void | unlockQuadraticForm () |
const Data * | userData () const |
the user data associated with this vertex | |
Data * | userData () |
Vertex () | |
virtual bool | write (std::ostream &os) const =0 |
write the vertex to a stream | |
virtual | ~Vertex () |
Protected Attributes | |
int | _colInHessian |
int | _dimension |
bool | _fixed |
OptimizableGraph * | _graph |
bool | _marginalized |
OpenMPMutex | _quadraticFormMutex |
int | _tempIndex |
Data * | _userData |
Friends | |
struct | OptimizableGraph |
A general case Vertex for optimization.
Definition at line 100 of file optimizable_graph.h.
Definition at line 39 of file optimizable_graph.cpp.
g2o::OptimizableGraph::Vertex::~Vertex | ( | ) | [virtual] |
Reimplemented from g2o::HyperGraph::Vertex.
Definition at line 47 of file optimizable_graph.cpp.
virtual const double& g2o::OptimizableGraph::Vertex::b | ( | int | i | ) | const [pure virtual] |
get the b vector element
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
virtual double& g2o::OptimizableGraph::Vertex::b | ( | int | i | ) | [pure virtual] |
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
virtual double* g2o::OptimizableGraph::Vertex::bData | ( | ) | [pure virtual] |
return a pointer to the b vector associated with this vertex
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
virtual void g2o::OptimizableGraph::Vertex::clearQuadraticForm | ( | ) | [pure virtual] |
set the b vector part of this vertex to zero
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
OptimizableGraph::Vertex * g2o::OptimizableGraph::Vertex::clone | ( | void | ) | const [virtual] |
returns a deep copy of the current vertex
Definition at line 52 of file optimizable_graph.cpp.
int g2o::OptimizableGraph::Vertex::colInHessian | ( | ) | const [inline] |
get the row of this vertex in the Hessian
Definition at line 228 of file optimizable_graph.h.
virtual int g2o::OptimizableGraph::Vertex::copyB | ( | double * | b_ | ) | const [pure virtual] |
copies the b vector in the array b_
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
int g2o::OptimizableGraph::Vertex::dimension | ( | ) | const [inline] |
dimension of the estimated state belonging to this node
Definition at line 220 of file optimizable_graph.h.
virtual void g2o::OptimizableGraph::Vertex::discardTop | ( | ) | [pure virtual] |
pop the last element from the stack, without restoring the current estimate
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
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::VertexSE3, g2o::VertexSE2, and g2o::VertexPointXY.
Definition at line 68 of file optimizable_graph.cpp.
bool g2o::OptimizableGraph::Vertex::fixed | ( | ) | const [inline] |
true => this node is fixed during the optimization
Definition at line 210 of file optimizable_graph.h.
bool g2o::OptimizableGraph::Vertex::getEstimateData | ( | double * | estimate | ) | const [virtual] |
writes the estimater to an array of double
Reimplemented in g2o::VertexSE3, g2o::VertexSE2, and g2o::VertexPointXY.
Definition at line 63 of file optimizable_graph.cpp.
bool g2o::OptimizableGraph::Vertex::getMinimalEstimateData | ( | double * | estimate | ) | const [virtual] |
writes the estimater to an array of double
Reimplemented in g2o::VertexSE3, g2o::VertexSE2, and g2o::VertexPointXY.
Definition at line 78 of file optimizable_graph.cpp.
const OptimizableGraph* g2o::OptimizableGraph::Vertex::graph | ( | ) | const [inline] |
Definition at line 230 of file optimizable_graph.h.
virtual const double& g2o::OptimizableGraph::Vertex::hessian | ( | int | i, |
int | j | ||
) | const [pure virtual] |
get the element from the hessian matrix
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
virtual double& g2o::OptimizableGraph::Vertex::hessian | ( | int | i, |
int | j | ||
) | [pure virtual] |
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
virtual double* g2o::OptimizableGraph::Vertex::hessianData | ( | ) | [pure virtual] |
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
virtual double g2o::OptimizableGraph::Vertex::hessianDeterminant | ( | ) | const [pure virtual] |
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
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 241 of file optimizable_graph.h.
virtual void g2o::OptimizableGraph::Vertex::mapHessianMemory | ( | double * | d | ) | [pure virtual] |
maps the internal matrix to some external memory location
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
bool g2o::OptimizableGraph::Vertex::marginalized | ( | ) | const [inline] |
true => this node is marginalized out during the optimization
Definition at line 215 of file optimizable_graph.h.
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::VertexSE3, g2o::VertexSE2, and g2o::VertexPointXY.
Definition at line 83 of file optimizable_graph.cpp.
virtual void g2o::OptimizableGraph::Vertex::oplus | ( | double * | v | ) | [pure virtual] |
update the position of the node from the parameters in v
Implemented in g2o::VertexSE3AxisAngle, g2o::VertexSE3AxisAngle, g2o::VertexSCam, g2o::VertexPointXYZ, g2o::VertexPointXYZ, g2o::VertexPointXYZ, g2o::VertexSE3, g2o::VertexCam, g2o::VertexPointXY, g2o::VertexSE3Expmap, g2o::VertexIntrinsics, g2o::VertexSim3Expmap, g2o::tutorial::VertexSE2, g2o::VertexSE2, g2o::tutorial::VertexPointXY, g2o::OnlineVertexSE3, and g2o::OnlineVertexSE2.
virtual void g2o::OptimizableGraph::Vertex::pop | ( | ) | [pure virtual] |
restore the position of the vertex by retrieving the position from the stack
Implemented in g2o::VertexSE3AxisAngle, g2o::VertexSE3AxisAngle, g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
virtual void g2o::OptimizableGraph::Vertex::push | ( | ) | [pure virtual] |
backup the position of the vertex to a stack
Implemented in g2o::VertexSE3AxisAngle, g2o::VertexSE3AxisAngle, g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
virtual bool g2o::OptimizableGraph::Vertex::read | ( | std::istream & | is | ) | [pure virtual] |
read the vertex from a stream, i.e., the internal state of the vertex
Implemented in g2o::VertexSE3AxisAngle, g2o::VertexSE3AxisAngle, g2o::VertexSCam, g2o::VertexPointXYZ, g2o::VertexPointXYZ, g2o::VertexPointXYZ, g2o::VertexPointXY, g2o::VertexSE2, g2o::VertexCam, g2o::tutorial::VertexSE2, g2o::tutorial::VertexPointXY, g2o::VertexSE3, g2o::VertexSE3Expmap, g2o::VertexIntrinsics, and g2o::VertexSim3Expmap.
void g2o::OptimizableGraph::Vertex::setColInHessian | ( | int | c | ) | [inline] |
set the row of this vertex in the Hessian
Definition at line 226 of file optimizable_graph.h.
bool g2o::OptimizableGraph::Vertex::setEstimateData | ( | const double * | estimate | ) | [virtual] |
sets the initial estimate from an array of double
Reimplemented in g2o::VertexSE2, g2o::VertexSE3, and g2o::VertexPointXY.
Definition at line 58 of file optimizable_graph.cpp.
void g2o::OptimizableGraph::Vertex::setFixed | ( | bool | fixed | ) | [inline] |
true => this node should be considered fixed during the optimization
Definition at line 212 of file optimizable_graph.h.
void g2o::OptimizableGraph::Vertex::setId | ( | int | id | ) | [inline] |
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id
Definition at line 223 of file optimizable_graph.h.
void g2o::OptimizableGraph::Vertex::setMarginalized | ( | bool | marginalized | ) | [inline] |
true => this node should be marginalized out during the optimization
Definition at line 217 of file optimizable_graph.h.
bool g2o::OptimizableGraph::Vertex::setMinimalEstimateData | ( | const double * | estimate | ) | [virtual] |
sets the initial estimate from an array of double
Reimplemented in g2o::VertexSE3, g2o::VertexSE2, and g2o::VertexPointXY.
Definition at line 73 of file optimizable_graph.cpp.
void g2o::OptimizableGraph::Vertex::setTempIndex | ( | int | ti | ) | [inline] |
set the temporary index of the vertex in the parameter blocks
Definition at line 207 of file optimizable_graph.h.
virtual void g2o::OptimizableGraph::Vertex::setToOrigin | ( | ) | [pure virtual] |
sets the node to the origin (used in the multilevel stuff)
Implemented in g2o::VertexSE3AxisAngle, g2o::VertexSE3AxisAngle, g2o::VertexPointXYZ, g2o::VertexPointXYZ, g2o::VertexPointXYZ, g2o::VertexCam, g2o::VertexSE3Expmap, g2o::VertexIntrinsics, g2o::VertexSim3Expmap, g2o::VertexSE3, g2o::tutorial::VertexSE2, g2o::VertexSE2, g2o::tutorial::VertexPointXY, and g2o::VertexPointXY.
virtual void g2o::OptimizableGraph::Vertex::setUncertainty | ( | double * | c | ) | [pure virtual] |
sets the covariance/information of the node, used internally
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
void g2o::OptimizableGraph::Vertex::setUserData | ( | Data * | obs | ) | [inline] |
Definition at line 113 of file optimizable_graph.h.
virtual double g2o::OptimizableGraph::Vertex::solveDirect | ( | double | lambda = 0 | ) | [pure virtual] |
updates the current vertex with the direct solution x += H_ii
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
virtual int g2o::OptimizableGraph::Vertex::stackSize | ( | ) | const [pure virtual] |
return the stack size
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
int g2o::OptimizableGraph::Vertex::tempIndex | ( | ) | const [inline] |
temporary index of this node in the parameter vector obtained from linearization
Definition at line 205 of file optimizable_graph.h.
virtual double* g2o::OptimizableGraph::Vertex::uncertaintyData | ( | ) | [pure virtual] |
return the pointer to the uncertainty (marginal covariance)
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 3, Vector3 >, g2o::BaseVertex< 3, SE2 >, g2o::BaseVertex< 4, Matrix< double, 5, 1 > >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, g2o::BaseVertex< 6, SBACam >, g2o::BaseVertex< 6, SE3AxisAngle >, g2o::BaseVertex< 2, Eigen::Vector2d >, and g2o::BaseVertex< 6, SE3Quat >.
void g2o::OptimizableGraph::Vertex::unlockQuadraticForm | ( | ) | [inline] |
unlock the block of the hessian and the b vector associated with this vertex
Definition at line 245 of file optimizable_graph.h.
const Data* g2o::OptimizableGraph::Vertex::userData | ( | ) | const [inline] |
the user data associated with this vertex
Definition at line 110 of file optimizable_graph.h.
Data* g2o::OptimizableGraph::Vertex::userData | ( | ) | [inline] |
Definition at line 111 of file optimizable_graph.h.
virtual bool g2o::OptimizableGraph::Vertex::write | ( | std::ostream & | os | ) | const [pure virtual] |
write the vertex to a stream
Implemented in g2o::VertexSE3AxisAngle, g2o::VertexSE3AxisAngle, g2o::VertexSCam, g2o::VertexPointXYZ, g2o::VertexPointXYZ, g2o::VertexPointXYZ, g2o::VertexPointXY, g2o::VertexSE2, g2o::VertexCam, g2o::tutorial::VertexSE2, g2o::tutorial::VertexPointXY, g2o::VertexSE3, g2o::VertexSE3Expmap, g2o::VertexIntrinsics, and g2o::VertexSim3Expmap.
friend struct OptimizableGraph [friend] |
Definition at line 102 of file optimizable_graph.h.
int g2o::OptimizableGraph::Vertex::_colInHessian [protected] |
Definition at line 259 of file optimizable_graph.h.
int g2o::OptimizableGraph::Vertex::_dimension [protected] |
Definition at line 258 of file optimizable_graph.h.
bool g2o::OptimizableGraph::Vertex::_fixed [protected] |
Definition at line 256 of file optimizable_graph.h.
OptimizableGraph* g2o::OptimizableGraph::Vertex::_graph [protected] |
Definition at line 253 of file optimizable_graph.h.
bool g2o::OptimizableGraph::Vertex::_marginalized [protected] |
Definition at line 257 of file optimizable_graph.h.
Definition at line 260 of file optimizable_graph.h.
int g2o::OptimizableGraph::Vertex::_tempIndex [protected] |
Definition at line 255 of file optimizable_graph.h.
Data* g2o::OptimizableGraph::Vertex::_userData [protected] |
Definition at line 254 of file optimizable_graph.h.