Prior for a two D pose. More...
#include <edge_se2_prior.h>
Public Member Functions | |
void | computeError () |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | EdgeSE2Prior () |
virtual bool | getMeasurementData (double *d) const |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *) |
int | measurementDimension () const |
virtual bool | read (std::istream &is) |
read the vertex from a stream, i.e., the internal state of the vertex | |
virtual bool | setMeasurementData (const double *d) |
virtual bool | write (std::ostream &os) const |
write the vertex to a stream |
Prior for a two D pose.
Definition at line 28 of file edge_se2_prior.h.
Definition at line 21 of file edge_se2_prior.cpp.
void g2o::EdgeSE2Prior::computeError | ( | ) | [inline, virtual] |
Implements g2o::OptimizableGraph::Edge.
Definition at line 34 of file edge_se2_prior.h.
virtual bool g2o::EdgeSE2Prior::getMeasurementData | ( | double * | m | ) | const [inline, virtual] |
writes the measurement to an array of double
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 47 of file edge_se2_prior.h.
void g2o::EdgeSE2Prior::initialEstimate | ( | const OptimizableGraph::VertexSet & | from, |
OptimizableGraph::Vertex * | to | ||
) | [virtual] |
set the estimate of the to vertex, based on the estimate of the from vertices in the edge.
Reimplemented from g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >.
Definition at line 25 of file edge_se2_prior.cpp.
virtual double g2o::EdgeSE2Prior::initialEstimatePossible | ( | const OptimizableGraph::VertexSet & | from, |
OptimizableGraph::Vertex * | to | ||
) | [inline, virtual] |
override in your class if it's possible to initialize the vertices in certain combinations. The return value may correspond to the cost for initiliaizng the vertex but should be positive if the initialization is possible and negative if not possible.
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 60 of file edge_se2_prior.h.
int g2o::EdgeSE2Prior::measurementDimension | ( | ) | const [inline, virtual] |
returns the dimension of the measurement in the extended representation which is used by get/setMeasurement;
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 55 of file edge_se2_prior.h.
bool g2o::EdgeSE2Prior::read | ( | std::istream & | is | ) | [virtual] |
read the vertex from a stream, i.e., the internal state of the vertex
Implements g2o::OptimizableGraph::Edge.
Definition at line 32 of file edge_se2_prior.cpp.
virtual bool g2o::EdgeSE2Prior::setMeasurementData | ( | const double * | m | ) | [inline, virtual] |
sets the measurement from an array of double
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 41 of file edge_se2_prior.h.
bool g2o::EdgeSE2Prior::write | ( | std::ostream & | os | ) | const [virtual] |
write the vertex to a stream
Implements g2o::OptimizableGraph::Edge.
Definition at line 47 of file edge_se2_prior.cpp.