g2o
|
Offset edge. More...
#include <edge_se3_offset.h>
Public Member Functions | |
EdgeSE3Offset () | |
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... | |
void | computeError () |
virtual void | setMeasurement (const SE3Quat &m) |
virtual bool | setMeasurementData (const double *d) |
virtual bool | getMeasurementData (double *d) const |
void | linearizeOplus () |
virtual int | measurementDimension () const |
virtual bool | setMeasurementFromState () |
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *) |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
Public Member Functions inherited from g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 > | |
BaseBinaryEdge () | |
virtual OptimizableGraph::Vertex * | createFrom () |
virtual OptimizableGraph::Vertex * | createTo () |
virtual OptimizableGraph::Vertex * | createVertex (int i) |
virtual void | resize (size_t size) |
virtual bool | allVerticesFixed () const |
virtual void | linearizeOplus (JacobianWorkspace &jacobianWorkspace) |
const JacobianXiOplusType & | jacobianOplusXi () const |
returns the result of the linearization in the manifold space for the node xi More... | |
const JacobianXjOplusType & | jacobianOplusXj () const |
returns the result of the linearization in the manifold space for the node xj More... | |
virtual void | constructQuadraticForm () |
virtual void | mapHessianMemory (double *d, int i, int j, bool rowMajor) |
Public Member Functions inherited from g2o::BaseEdge< D, SE3Quat > | |
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 int | rank () const |
Public Member Functions inherited from g2o::OptimizableGraph::Edge | |
Edge () | |
virtual | ~Edge () |
virtual Edge * | clone () 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()) | |
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) |
Public Member Functions inherited from g2o::HyperGraph::Edge | |
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 |
Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement | |
virtual | ~HyperGraphElement () |
HyperGraphElement * | clone () const |
Public Member Functions inherited from g2o::HyperGraph::DataContainer | |
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 Member Functions | |
virtual bool | resolveCaches () |
Protected Member Functions inherited from g2o::BaseEdge< D, SE3Quat > | |
InformationType | robustInformation (const 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) |
bool | resolveParameters () |
Additional Inherited Members | |
Public Types inherited from g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 > | |
typedef VertexSE3 | VertexXiType |
typedef VertexSE3 | VertexXjType |
typedef BaseEdge< D, SE3Quat >::Measurement | Measurement |
typedef Eigen::Matrix< double, D, Di, D==1?Eigen::RowMajor:Eigen::ColMajor >::AlignedMapType | JacobianXiOplusType |
typedef Eigen::Matrix< double, D, Dj, D==1?Eigen::RowMajor:Eigen::ColMajor >::AlignedMapType | JacobianXjOplusType |
typedef BaseEdge< D, SE3Quat >::ErrorVector | ErrorVector |
typedef BaseEdge< D, SE3Quat >::InformationType | InformationType |
typedef Eigen::Map< Eigen::Matrix< double, Di, Dj, Di==1?Eigen::RowMajor:Eigen::ColMajor >, Eigen::Matrix< double, Di, Dj, Di==1?Eigen::RowMajor:Eigen::ColMajor >::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > | HessianBlockType |
typedef Eigen::Map< Eigen::Matrix< double, Dj, Di, Dj==1?Eigen::RowMajor:Eigen::ColMajor >, Eigen::Matrix< double, Dj, Di, Dj==1?Eigen::RowMajor:Eigen::ColMajor >::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > | HessianBlockTransposedType |
Public Types inherited from g2o::BaseEdge< D, SE3Quat > | |
typedef SE3Quat | Measurement |
typedef Eigen::Matrix< double, D, 1, Eigen::ColMajor > | ErrorVector |
typedef Eigen::Matrix< double, D, D, Eigen::ColMajor > | InformationType |
Static Public Attributes inherited from g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 > | |
static const int | Di |
static const int | Dj |
static const int | Dimension |
Static Public Attributes inherited from g2o::BaseEdge< D, SE3Quat > | |
static const int | Dimension |
Offset edge.
Definition at line 44 of file edge_se3_offset.h.
g2o::deprecated::EdgeSE3Offset::EdgeSE3Offset | ( | ) |
Definition at line 38 of file edge_se3_offset.cpp.
References _cacheFrom, _cacheTo, _offsetFrom, _offsetTo, g2o::BaseEdge< D, SE3Quat >::information(), g2o::OptimizableGraph::Edge::installParameter(), and g2o::OptimizableGraph::Edge::resizeParameters().
|
virtual |
Implements g2o::OptimizableGraph::Edge.
Definition at line 99 of file edge_se3_offset.cpp.
References _cacheFrom, _cacheTo, g2o::BaseEdge< D, SE3Quat >::_error, _inverseMeasurement, g2o::deprecated::CacheSE3Offset::n2w(), g2o::SE3Quat::rotation(), g2o::SE3Quat::translation(), and g2o::deprecated::CacheSE3Offset::w2n().
|
inlinevirtual |
writes the measurement to an array of double
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 68 of file edge_se3_offset.h.
|
virtual |
set the estimate of the to vertex, based on the estimate of the from vertices in the edge.
Reimplemented from g2o::BaseEdge< D, SE3Quat >.
Definition at line 143 of file edge_se3_offset.cpp.
References _cacheFrom, _cacheTo, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), g2o::SE3Quat::inverse(), g2o::BaseEdge< D, SE3Quat >::measurement(), g2o::deprecated::ParameterSE3Offset::offset(), g2o::deprecated::CacheSE3Offset::offsetParam(), and g2o::BaseVertex< D, T >::setEstimate().
|
inlinevirtual |
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 80 of file edge_se3_offset.h.
|
virtual |
Linearizes the oplus operator in the vertex, and stores the result in temporary variables _jacobianOplusXi and _jacobianOplusXj
Reimplemented from g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >.
Definition at line 115 of file edge_se3_offset.cpp.
References _cacheFrom, _cacheTo, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >::_jacobianOplusXi, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >::_jacobianOplusXj, g2o::BaseEdge< D, SE3Quat >::_measurement, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), g2o::deprecated::ParameterSE3Offset::offset(), g2o::deprecated::CacheSE3Offset::offsetParam(), g2o::SE3Quat::rotation(), and g2o::SE3Quat::translation().
|
inlinevirtual |
returns the dimension of the measurement in the extended representation which is used by get/setMeasurement;
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 76 of file edge_se3_offset.h.
|
virtual |
read the vertex from a stream, i.e., the internal state of the vertex
Implements g2o::OptimizableGraph::Edge.
Definition at line 60 of file edge_se3_offset.cpp.
References g2o::BaseEdge< D, SE3Quat >::information(), setMeasurement(), and g2o::OptimizableGraph::Edge::setParameterId().
|
protectedvirtual |
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 49 of file edge_se3_offset.cpp.
References _cacheFrom, _cacheTo, _offsetFrom, _offsetTo, g2o::HyperGraph::Edge::_vertices, and g2o::OptimizableGraph::Edge::resolveCache().
|
inlinevirtual |
Reimplemented from g2o::BaseEdge< D, SE3Quat >.
Definition at line 56 of file edge_se3_offset.h.
References g2o::SE3Quat::inverse().
Referenced by read(), and setMeasurementFromState().
|
inlinevirtual |
sets the measurement from an array of double
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 61 of file edge_se3_offset.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 109 of file edge_se3_offset.cpp.
References _cacheFrom, _cacheTo, g2o::deprecated::CacheSE3Offset::n2w(), setMeasurement(), and g2o::deprecated::CacheSE3Offset::w2n().
|
virtual |
write the vertex to a stream
Implements g2o::OptimizableGraph::Edge.
Definition at line 89 of file edge_se3_offset.cpp.
References _offsetFrom, _offsetTo, g2o::Parameter::id(), g2o::BaseEdge< D, SE3Quat >::information(), and g2o::BaseEdge< D, SE3Quat >::measurement().
|
protected |
Definition at line 91 of file edge_se3_offset.h.
Referenced by computeError(), EdgeSE3Offset(), initialEstimate(), linearizeOplus(), resolveCaches(), and setMeasurementFromState().
|
protected |
Definition at line 91 of file edge_se3_offset.h.
Referenced by computeError(), EdgeSE3Offset(), initialEstimate(), linearizeOplus(), resolveCaches(), and setMeasurementFromState().
|
protected |
Definition at line 88 of file edge_se3_offset.h.
Referenced by computeError().
|
protected |
Definition at line 90 of file edge_se3_offset.h.
Referenced by EdgeSE3Offset(), resolveCaches(), and write().
|
protected |
Definition at line 90 of file edge_se3_offset.h.
Referenced by EdgeSE3Offset(), resolveCaches(), and write().
g2o::deprecated::EdgeSE3Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
Definition at line 46 of file edge_se3_offset.h.