g2o
|
#include <edge_se3_lotsofxyz.h>
Public Member Functions | |
EdgeSE3LotsOfXYZ () | |
void | setDimension (int dimension_) |
void | setSize (int vertices) |
virtual void | computeError () |
virtual bool | read (std::istream &is) |
read the vertex from a stream, i.e., the internal state of the vertex More... | |
virtual bool | write (std::ostream &os) const |
write the vertex to a stream More... | |
virtual bool | setMeasurementFromState () |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *) |
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *) |
virtual void | linearizeOplus () |
![]() | |
BaseMultiEdge () | |
virtual void | linearizeOplus (JacobianWorkspace &jacobianWorkspace) |
virtual void | resize (size_t size) |
virtual bool | allVerticesFixed () const |
virtual void | constructQuadraticForm () |
virtual void | mapHessianMemory (double *d, int i, int j, bool rowMajor) |
![]() | |
BaseEdge () | |
virtual | ~BaseEdge () |
virtual double | chi2 () const |
computes the chi2 based on the cached error value, only valid after computeError has been called. More... | |
virtual const double * | errorData () const |
returns the error vector cached after calling the computeError; More... | |
virtual double * | errorData () |
const ErrorVector & | error () const |
ErrorVector & | error () |
EIGEN_STRONG_INLINE const InformationType & | information () const |
information matrix of the constraint More... | |
EIGEN_STRONG_INLINE InformationType & | information () |
EIGEN_STRONG_INLINE void | setInformation (const 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 () |
EIGEN_STRONG_INLINE const Measurement & | measurement () const |
accessor functions for the measurement represented by the edge More... | |
virtual void | setMeasurement (const Measurement &m) |
virtual int | rank () const |
![]() | |
Edge () | |
virtual | ~Edge () |
virtual Edge * | clone () const |
virtual bool | setMeasurementData (const double *m) |
virtual bool | getMeasurementData (double *m) const |
virtual int | measurementDimension () const |
RobustKernel * | robustKernel () const |
if NOT NULL, error of this edge will be robustifed with the kernel More... | |
void | setRobustKernel (RobustKernel *ptr) |
int | level () const |
returns the level of the edge More... | |
void | setLevel (int l) |
sets the level of the edge More... | |
int | dimension () const |
returns the dimensions of the error function More... | |
G2O_ATTRIBUTE_DEPRECATED (virtual Vertex *createFrom()) | |
G2O_ATTRIBUTE_DEPRECATED (virtual Vertex *createTo()) | |
virtual Vertex * | createVertex (int) |
long long | internalId () const |
the internal ID of the edge More... | |
OptimizableGraph * | graph () |
const OptimizableGraph * | graph () const |
bool | setParameterId (int argNum, int paramId) |
const Parameter * | parameter (int argNo) const |
size_t | numParameters () const |
void | resizeParameters (size_t newSize) |
![]() | |
Edge (int id=InvalidId) | |
creates and empty edge with no vertices More... | |
const VertexContainer & | vertices () const |
VertexContainer & | vertices () |
const Vertex * | vertex (size_t i) const |
Vertex * | vertex (size_t i) |
void | setVertex (size_t i, Vertex *v) |
int | id () const |
void | setId (int id) |
virtual HyperGraphElementType | elementType () const |
int | numUndefinedVertices () const |
![]() | |
virtual | ~HyperGraphElement () |
HyperGraphElement * | clone () const |
![]() | |
DataContainer () | |
virtual | ~DataContainer () |
const Data * | userData () const |
the user data associated with this vertex More... | |
Data * | userData () |
void | setUserData (Data *obs) |
void | addUserData (Data *obs) |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | |
Protected Attributes | |
unsigned int | _observedPoints |
![]() | |
std::vector< HessianHelper > | _hessian |
std::vector< JacobianType, Eigen::aligned_allocator< JacobianType > > | _jacobianOplus |
jacobians of the edge (w.r.t. oplus) More... | |
![]() | |
Measurement | _measurement |
InformationType | _information |
ErrorVector | _error |
![]() | |
int | _dimension |
int | _level |
RobustKernel * | _robustKernel |
long long | _internalId |
std::vector< int > | _cacheIds |
std::vector< std::string > | _parameterTypes |
std::vector< Parameter ** > | _parameters |
std::vector< int > | _parameterIds |
![]() | |
VertexContainer | _vertices |
int | _id |
unique id More... | |
![]() | |
Data * | _userData |
Additional Inherited Members | |
![]() | |
typedef BaseEdge< D, VectorXD >::Measurement | Measurement |
typedef MatrixXD::MapType | JacobianType |
typedef BaseEdge< D, VectorXD >::ErrorVector | ErrorVector |
typedef BaseEdge< D, VectorXD >::InformationType | InformationType |
typedef Eigen::Map< MatrixXD, MatrixXD::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > | HessianBlockType |
![]() | |
typedef VectorXD | Measurement |
typedef Eigen::Matrix< double, D, 1, Eigen::ColMajor > | ErrorVector |
typedef Eigen::Matrix< double, D, D, Eigen::ColMajor > | InformationType |
![]() | |
static const int | Dimension |
![]() | |
static const int | Dimension |
![]() | |
void | computeQuadraticForm (const InformationType &omega, const ErrorVector &weightedError) |
![]() | |
InformationType | robustInformation (const Vector3D &rho) |
![]() | |
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) |
bool | resolveParameters () |
virtual bool | resolveCaches () |
Definition at line 12 of file edge_se3_lotsofxyz.h.
g2o::EdgeSE3LotsOfXYZ::EdgeSE3LotsOfXYZ | ( | ) |
Definition at line 5 of file edge_se3_lotsofxyz.cpp.
References g2o::BaseMultiEdge<-1, VectorXD >::resize().
|
virtual |
Implements g2o::OptimizableGraph::Edge.
Definition at line 27 of file edge_se3_lotsofxyz.cpp.
References g2o::BaseEdge< D, VectorXD >::_error, g2o::BaseEdge< D, VectorXD >::_measurement, _observedPoints, g2o::HyperGraph::Edge::_vertices, and g2o::BaseVertex< D, T >::estimate().
|
virtual |
set the estimate of the to vertex, based on the estimate of the from vertices in the edge.
Reimplemented from g2o::BaseEdge< D, VectorXD >.
Definition at line 135 of file edge_se3_lotsofxyz.cpp.
References g2o::BaseEdge< D, VectorXD >::_measurement, _observedPoints, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), g2o::HyperGraph::Vertex::id(), initialEstimatePossible(), and g2o::BaseVertex< D, T >::setEstimate().
|
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 170 of file edge_se3_lotsofxyz.cpp.
References g2o::HyperGraph::Edge::_vertices.
Referenced by initialEstimate().
|
virtual |
Linearizes the oplus operator in the vertex, and stores the result in temporary variable vector _jacobianOplus
Reimplemented from g2o::BaseMultiEdge<-1, VectorXD >.
Definition at line 41 of file edge_se3_lotsofxyz.cpp.
References g2o::BaseMultiEdge<-1, VectorXD >::_jacobianOplus, g2o::HyperGraph::Edge::_vertices, and g2o::BaseVertex< D, T >::estimate().
|
virtual |
read the vertex from a stream, i.e., the internal state of the vertex
Implements g2o::OptimizableGraph::Edge.
Definition at line 85 of file edge_se3_lotsofxyz.cpp.
References g2o::BaseEdge< D, VectorXD >::_measurement, _observedPoints, g2o::BaseEdge< D, VectorXD >::information(), and setSize().
|
inline |
Definition at line 21 of file edge_se3_lotsofxyz.h.
|
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 9 of file edge_se3_lotsofxyz.cpp.
References g2o::BaseEdge< D, VectorXD >::_measurement, _observedPoints, g2o::HyperGraph::Edge::_vertices, and g2o::BaseVertex< D, T >::estimate().
|
inline |
Definition at line 28 of file edge_se3_lotsofxyz.h.
Referenced by read().
|
virtual |
write the vertex to a stream
Implements g2o::OptimizableGraph::Edge.
Definition at line 114 of file edge_se3_lotsofxyz.cpp.
References g2o::BaseEdge< D, VectorXD >::_measurement, _observedPoints, and g2o::BaseEdge< D, VectorXD >::information().
|
protected |
Definition at line 15 of file edge_se3_lotsofxyz.h.
Referenced by computeError(), initialEstimate(), read(), setMeasurementFromState(), and write().
g2o::EdgeSE3LotsOfXYZ::EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
Definition at line 18 of file edge_se3_lotsofxyz.h.