Public Member Functions
g2o::EdgeSE2 Class Reference

2D edge between two Vertex2 More...

#include <edge_se2.h>

Inheritance diagram for g2o::EdgeSE2:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void computeError ()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE2 ()
virtual bool getMeasurementData (double *d) const
virtual void initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
virtual double initialEstimatePossible (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
virtual void linearizeOplus ()
virtual int measurementDimension () const
virtual bool read (std::istream &is)
 read the vertex from a stream, i.e., the internal state of the vertex
virtual void setMeasurement (const SE2 &m)
virtual bool setMeasurementData (const double *d)
virtual bool setMeasurementFromState ()
virtual bool write (std::ostream &os) const
 write the vertex to a stream

Detailed Description

2D edge between two Vertex2

Definition at line 28 of file types/slam2d/edge_se2.h.


Constructor & Destructor Documentation

Definition at line 33 of file types/slam2d/edge_se2.cpp.


Member Function Documentation

void g2o::EdgeSE2::computeError ( ) [inline, virtual]

Implements g2o::OptimizableGraph::Edge.

Definition at line 34 of file types/slam2d/edge_se2.h.

virtual bool g2o::EdgeSE2::getMeasurementData ( double *  m) const [inline, virtual]

writes the measurement to an array of double

Returns:
true on success

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 55 of file types/slam2d/edge_se2.h.

set the estimate of the to vertex, based on the estimate of the from vertices in the edge.

Reimplemented from g2o::BaseEdge< D, SE2 >.

Reimplemented in g2o::OnlineEdgeSE2.

Definition at line 63 of file types/slam2d/edge_se2.cpp.

virtual double g2o::EdgeSE2::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 74 of file types/slam2d/edge_se2.h.

void g2o::EdgeSE2::linearizeOplus ( ) [virtual]

Linearizes the oplus operator in the vertex, and stores the result in temporary variables _jacobianOplusXi and _jacobianOplusXj

Reimplemented from g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >.

Definition at line 74 of file types/slam2d/edge_se2.cpp.

virtual int g2o::EdgeSE2::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 63 of file types/slam2d/edge_se2.h.

bool g2o::EdgeSE2::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 38 of file types/slam2d/edge_se2.cpp.

virtual void g2o::EdgeSE2::setMeasurement ( const SE2 m) [inline, virtual]

Reimplemented from g2o::BaseEdge< D, SE2 >.

Definition at line 44 of file types/slam2d/edge_se2.h.

virtual bool g2o::EdgeSE2::setMeasurementData ( const double *  m) [inline, virtual]

sets the measurement from an array of double

Returns:
true on success

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 49 of file types/slam2d/edge_se2.h.

virtual bool g2o::EdgeSE2::setMeasurementFromState ( ) [inline, virtual]

sets the estimate to have a zero error, based on the current value of the state variables returns false if not supported.

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 65 of file types/slam2d/edge_se2.h.

bool g2o::EdgeSE2::write ( std::ostream &  os) const [virtual]

write the vertex to a stream

Implements g2o::OptimizableGraph::Edge.

Definition at line 53 of file types/slam2d/edge_se2.cpp.


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


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:34:30