#include <base_edge.h>
Public Types | |
typedef Matrix< double, D, 1 > | ErrorVector |
typedef Matrix< double, D, D > | InformationType |
typedef E | Measurement |
Public Member Functions | |
BaseEdge () | |
virtual double | chi2 () const |
computes the chi2 based on the cached error value, only valid after computeError has been called. | |
const ErrorVector & | error () const |
ErrorVector & | error () |
virtual const double * | errorData () const |
returns the error vector cached after calling the computeError; | |
virtual double * | errorData () |
const InformationType & | information () const |
information matrix of the constraint | |
InformationType & | information () |
virtual const double * | informationData () const |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd> | |
virtual double * | informationData () |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
const Measurement & | inverseMeasurement () const |
Measurement & | inverseMeasurement () |
const Measurement & | measurement () const |
accessor functions for the measurement represented by the edge | |
Measurement & | measurement () |
virtual int | rank () const |
virtual void | robustifyError () |
void | setInformation (const InformationType &information) |
virtual void | setInverseMeasurement (const Measurement &im) |
virtual void | setMeasurement (const Measurement &m) |
virtual | ~BaseEdge () |
Static Public Attributes | |
static const int | Dimension = D |
Protected Attributes | |
ErrorVector | _error |
InformationType | _information |
Measurement | _inverseMeasurement |
Measurement | _measurement |
Definition at line 30 of file base_edge.h.
typedef Matrix<double, D, 1> g2o::BaseEdge< D, E >::ErrorVector |
Reimplemented in g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 2, Vector2d >, g2o::BaseMultiEdge< 2, Eigen::Vector2d >, g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseUnaryEdge< D, E, VertexXi >, and g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >.
Definition at line 36 of file base_edge.h.
typedef Matrix<double, D, D> g2o::BaseEdge< D, E >::InformationType |
Reimplemented in g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 2, Vector2d >, g2o::BaseMultiEdge< 2, Eigen::Vector2d >, g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseUnaryEdge< D, E, VertexXi >, and g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >.
Definition at line 37 of file base_edge.h.
typedef E g2o::BaseEdge< D, E >::Measurement |
Reimplemented in g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 2, Vector2d >, g2o::BaseMultiEdge< 2, Eigen::Vector2d >, g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseUnaryEdge< D, E, VertexXi >, and g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >.
Definition at line 35 of file base_edge.h.
g2o::BaseEdge< D, E >::BaseEdge | ( | ) | [inline] |
Definition at line 39 of file base_edge.h.
virtual g2o::BaseEdge< D, E >::~BaseEdge | ( | ) | [inline, virtual] |
Definition at line 44 of file base_edge.h.
virtual double g2o::BaseEdge< D, E >::chi2 | ( | ) | const [inline, virtual] |
computes the chi2 based on the cached error value, only valid after computeError has been called.
Implements g2o::OptimizableGraph::Edge.
Definition at line 46 of file base_edge.h.
const ErrorVector& g2o::BaseEdge< D, E >::error | ( | ) | const [inline] |
Definition at line 60 of file base_edge.h.
ErrorVector& g2o::BaseEdge< D, E >::error | ( | ) | [inline] |
Definition at line 61 of file base_edge.h.
virtual const double* g2o::BaseEdge< D, E >::errorData | ( | ) | const [inline, virtual] |
returns the error vector cached after calling the computeError;
Implements g2o::OptimizableGraph::Edge.
Definition at line 58 of file base_edge.h.
virtual double* g2o::BaseEdge< D, E >::errorData | ( | ) | [inline, virtual] |
Implements g2o::OptimizableGraph::Edge.
Definition at line 59 of file base_edge.h.
const InformationType& g2o::BaseEdge< D, E >::information | ( | ) | const [inline] |
information matrix of the constraint
Definition at line 64 of file base_edge.h.
InformationType& g2o::BaseEdge< D, E >::information | ( | ) | [inline] |
Definition at line 65 of file base_edge.h.
virtual const double* g2o::BaseEdge< D, E >::informationData | ( | ) | const [inline, virtual] |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd>
Implements g2o::OptimizableGraph::Edge.
Definition at line 68 of file base_edge.h.
virtual double* g2o::BaseEdge< D, E >::informationData | ( | ) | [inline, virtual] |
Implements g2o::OptimizableGraph::Edge.
Definition at line 69 of file base_edge.h.
virtual void g2o::BaseEdge< D, E >::initialEstimate | ( | const OptimizableGraph::VertexSet & | from, |
OptimizableGraph::Vertex * | to | ||
) | [inline, virtual] |
set the estimate of the to vertex, based on the estimate of the from vertices in the edge.
Implements g2o::OptimizableGraph::Edge.
Reimplemented in g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::EdgeSim3, g2o::EdgeSE3, g2o::EdgeSE2, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2PointXY, g2o::EdgeSE2Prior, g2o::BaseUnaryEdge< D, E, VertexXi >, g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >, g2o::OnlineEdgeSE3, g2o::OnlineEdgeSE2, and g2o::EdgeSE2PointXYCalib.
Definition at line 86 of file base_edge.h.
const Measurement& g2o::BaseEdge< D, E >::inverseMeasurement | ( | ) | const [inline] |
accessor functions for the inverse measurement, you may use this to cache the inverse measurement in case you need it to compute, for example, the error vector.
Definition at line 82 of file base_edge.h.
Measurement& g2o::BaseEdge< D, E >::inverseMeasurement | ( | ) | [inline] |
Definition at line 83 of file base_edge.h.
const Measurement& g2o::BaseEdge< D, E >::measurement | ( | ) | const [inline] |
accessor functions for the measurement represented by the edge
Definition at line 72 of file base_edge.h.
Measurement& g2o::BaseEdge< D, E >::measurement | ( | ) | [inline] |
Definition at line 73 of file base_edge.h.
virtual int g2o::BaseEdge< D, E >::rank | ( | ) | const [inline, virtual] |
Definition at line 76 of file base_edge.h.
virtual void g2o::BaseEdge< D, E >::robustifyError | ( | ) | [inline, virtual] |
robustify the error of the edge using an robust kernel/M-estimator this is only called if robustKernel==true
Implements g2o::OptimizableGraph::Edge.
Definition at line 51 of file base_edge.h.
void g2o::BaseEdge< D, E >::setInformation | ( | const InformationType & | information | ) | [inline] |
Definition at line 66 of file base_edge.h.
virtual void g2o::BaseEdge< D, E >::setInverseMeasurement | ( | const Measurement & | im | ) | [inline, virtual] |
Definition at line 84 of file base_edge.h.
virtual void g2o::BaseEdge< D, E >::setMeasurement | ( | const Measurement & | m | ) | [inline, virtual] |
Reimplemented in g2o::EdgeSE3, and g2o::EdgeSE2.
Definition at line 74 of file base_edge.h.
ErrorVector g2o::BaseEdge< D, E >::_error [protected] |
Definition at line 97 of file base_edge.h.
InformationType g2o::BaseEdge< D, E >::_information [protected] |
Definition at line 96 of file base_edge.h.
Measurement g2o::BaseEdge< D, E >::_inverseMeasurement [protected] |
Definition at line 95 of file base_edge.h.
Measurement g2o::BaseEdge< D, E >::_measurement [protected] |
Definition at line 94 of file base_edge.h.
const int g2o::BaseEdge< D, E >::Dimension = D [static] |
Reimplemented in g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 2, Vector2d >, g2o::BaseMultiEdge< 2, Eigen::Vector2d >, g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseUnaryEdge< D, E, VertexXi >, and g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >.
Definition at line 34 of file base_edge.h.