#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. More... | |
| const ErrorVector & | error () const |
| ErrorVector & | error () |
| virtual const double * | errorData () const |
| returns the error vector cached after calling the computeError; More... | |
| virtual double * | errorData () |
| const InformationType & | information () const |
| information matrix of the constraint More... | |
| InformationType & | information () |
| virtual const double * | informationData () const |
| returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd> More... | |
| virtual double * | informationData () |
| virtual void | initialEstimate (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *) |
| const Measurement & | measurement () const |
| accessor functions for the measurement represented by the edge More... | |
| virtual int | rank () const |
| void | setInformation (const InformationType &information) |
| virtual void | setMeasurement (const Measurement &m) |
| virtual | ~BaseEdge () |
Public Member Functions inherited from g2o::OptimizableGraph::Edge | |
| virtual bool | allVerticesFixed () const =0 |
| virtual Edge * | clone () const |
| virtual void | computeError ()=0 |
| virtual void | constructQuadraticForm ()=0 |
| virtual Vertex * | createFrom () |
| virtual Vertex * | createTo () |
| int | dimension () const |
| returns the dimensions of the error function More... | |
| Edge () | |
| virtual bool | getMeasurementData (double *m) const |
| OptimizableGraph * | graph () |
| const OptimizableGraph * | graph () const |
| virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
| long long | internalId () const |
| the internal ID of the edge More... | |
| int | level () const |
| returns the level of the edge More... | |
| virtual void | linearizeOplus (JacobianWorkspace &jacobianWorkspace)=0 |
| virtual void | mapHessianMemory (double *d, int i, int j, bool rowMajor)=0 |
| virtual int | measurementDimension () const |
| size_t | numParameters () const |
| const Parameter * | parameter (int argNo) const |
| virtual bool | read (std::istream &is)=0 |
| read the vertex from a stream, i.e., the internal state of the vertex More... | |
| void | resizeParameters (size_t newSize) |
| RobustKernel * | robustKernel () const |
| if NOT NULL, error of this edge will be robustifed with the kernel More... | |
| void | setLevel (int l) |
| sets the level of the edge More... | |
| virtual bool | setMeasurementData (const double *m) |
| virtual bool | setMeasurementFromState () |
| bool | setParameterId (int argNum, int paramId) |
| void | setRobustKernel (RobustKernel *ptr) |
| virtual bool | write (std::ostream &os) const =0 |
| write the vertex to a stream More... | |
| virtual | ~Edge () |
Public Member Functions inherited from g2o::HyperGraph::Edge | |
| Edge (int id=-1) | |
| creates and empty edge with no vertices More... | |
| virtual HyperGraphElementType | elementType () const |
| int | id () const |
| virtual void | resize (size_t size) |
| void | setId (int id) |
| void | setVertex (size_t i, Vertex *v) |
| const Vertex * | vertex (size_t i) const |
| Vertex * | vertex (size_t i) |
| const VertexContainer & | vertices () const |
| VertexContainer & | vertices () |
Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement | |
| virtual | ~HyperGraphElement () |
Static Public Attributes | |
| static const int | Dimension = D |
Protected Member Functions | |
| InformationType | robustInformation (const Eigen::Vector3d &rho) |
Protected Member Functions inherited from g2o::OptimizableGraph::Edge | |
| template<typename ParameterType > | |
| bool | installParameter (ParameterType *&p, size_t argNo, int paramId=-1) |
| template<typename CacheType > | |
| void | resolveCache (CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters) |
| virtual bool | resolveCaches () |
| bool | resolveParameters () |
Protected Attributes | |
| ErrorVector | _error |
| InformationType | _information |
| Measurement | _measurement |
Protected Attributes inherited from g2o::OptimizableGraph::Edge | |
| std::vector< int > | _cacheIds |
| int | _dimension |
| long long | _internalId |
| int | _level |
| std::vector< int > | _parameterIds |
| std::vector< Parameter ** > | _parameters |
| std::vector< std::string > | _parameterTypes |
| RobustKernel * | _robustKernel |
Protected Attributes inherited from g2o::HyperGraph::Edge | |
| int | _id |
| unique id More... | |
| VertexContainer | _vertices |
Definition at line 42 of file base_edge.h.
| typedef Matrix<double, D, 1> g2o::BaseEdge< D, E >::ErrorVector |
Definition at line 48 of file base_edge.h.
| typedef Matrix<double, D, D> g2o::BaseEdge< D, E >::InformationType |
Definition at line 49 of file base_edge.h.
| typedef E g2o::BaseEdge< D, E >::Measurement |
Definition at line 47 of file base_edge.h.
|
inline |
Definition at line 51 of file base_edge.h.
|
inlinevirtual |
Definition at line 56 of file base_edge.h.
|
inlinevirtual |
computes the chi2 based on the cached error value, only valid after computeError has been called.
Implements g2o::OptimizableGraph::Edge.
Definition at line 58 of file base_edge.h.
|
inline |
Definition at line 65 of file base_edge.h.
|
inline |
Definition at line 66 of file base_edge.h.
|
inlinevirtual |
returns the error vector cached after calling the computeError;
Implements g2o::OptimizableGraph::Edge.
Definition at line 63 of file base_edge.h.
|
inlinevirtual |
Implements g2o::OptimizableGraph::Edge.
Definition at line 64 of file base_edge.h.
|
inline |
information matrix of the constraint
Definition at line 69 of file base_edge.h.
|
inline |
Definition at line 70 of file base_edge.h.
|
inlinevirtual |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd>
Implements g2o::OptimizableGraph::Edge.
Definition at line 73 of file base_edge.h.
|
inlinevirtual |
Implements g2o::OptimizableGraph::Edge.
Definition at line 74 of file base_edge.h.
|
inlinevirtual |
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::EdgeSim3, g2o::BaseUnaryEdge< D, E, VertexXi >, g2o::BaseUnaryEdge< 2, Vector2d, VertexSE3Expmap >, and g2o::BaseUnaryEdge< 3, Vector3d, VertexSE3Expmap >.
Definition at line 82 of file base_edge.h.
|
inline |
accessor functions for the measurement represented by the edge
Definition at line 77 of file base_edge.h.
|
inlinevirtual |
Definition at line 80 of file base_edge.h.
|
inlineprotected |
calculate the robust information matrix by updating the information matrix of the error
Definition at line 96 of file base_edge.h.
|
inline |
Definition at line 71 of file base_edge.h.
|
inlinevirtual |
Definition at line 78 of file base_edge.h.
|
protected |
Definition at line 91 of file base_edge.h.
|
protected |
Definition at line 90 of file base_edge.h.
|
protected |
Definition at line 89 of file base_edge.h.
|
static |
Definition at line 46 of file base_edge.h.