7D edge between two Vertex7 More...
#include <types_seven_dof_expmap.h>
Public Member Functions | |
void | computeError () |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | EdgeSim3 () |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *) |
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *) |
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... | |
Public Member Functions inherited from g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap > | |
virtual bool | allVerticesFixed () const |
BaseBinaryEdge () | |
virtual void | constructQuadraticForm () |
virtual OptimizableGraph::Vertex * | createFrom () |
virtual OptimizableGraph::Vertex * | createTo () |
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 | linearizeOplus (JacobianWorkspace &jacobianWorkspace) |
virtual void | linearizeOplus () |
virtual void | mapHessianMemory (double *d, int i, int j, bool rowMajor) |
virtual void | resize (size_t size) |
Public Member Functions inherited from g2o::BaseEdge< D, Sim3 > | |
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 () |
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 Edge * | clone () const |
int | dimension () const |
returns the dimensions of the error function More... | |
Edge () | |
virtual bool | getMeasurementData (double *m) const |
OptimizableGraph * | graph () |
const OptimizableGraph * | graph () const |
long long | internalId () const |
the internal ID of the edge More... | |
int | level () const |
returns the level of the edge More... | |
virtual int | measurementDimension () const |
size_t | numParameters () const |
const Parameter * | parameter (int argNo) const |
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 | ~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 |
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 () |
Additional Inherited Members | |
Public Types inherited from g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap > | |
typedef BaseEdge< D, Sim3 >::ErrorVector | ErrorVector |
typedef Eigen::Map< Matrix< double, Dj, Di >, Matrix< double, Dj, Di >::Flags &AlignedBit?Aligned:Unaligned > | HessianBlockTransposedType |
typedef Eigen::Map< Matrix< double, Di, Dj >, Matrix< double, Di, Dj >::Flags &AlignedBit?Aligned:Unaligned > | HessianBlockType |
typedef BaseEdge< D, Sim3 >::InformationType | InformationType |
typedef Matrix< double, D, Di >::AlignedMapType | JacobianXiOplusType |
typedef Matrix< double, D, Dj >::AlignedMapType | JacobianXjOplusType |
typedef BaseEdge< D, Sim3 >::Measurement | Measurement |
typedef VertexSim3Expmap | VertexXiType |
typedef VertexSim3Expmap | VertexXjType |
Public Types inherited from g2o::BaseEdge< D, Sim3 > | |
typedef Matrix< double, D, 1 > | ErrorVector |
typedef Matrix< double, D, D > | InformationType |
typedef Sim3 | Measurement |
Static Public Attributes inherited from g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap > | |
static const int | Di |
static const int | Dimension |
static const int | Dj |
Static Public Attributes inherited from g2o::BaseEdge< D, Sim3 > | |
static const int | Dimension |
Protected Member Functions inherited from g2o::BaseEdge< D, Sim3 > | |
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 inherited from g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap > | |
HessianBlockType | _hessian |
bool | _hessianRowMajor |
HessianBlockTransposedType | _hessianTransposed |
JacobianXiOplusType | _jacobianOplusXi |
JacobianXjOplusType | _jacobianOplusXj |
Protected Attributes inherited from g2o::BaseEdge< D, Sim3 > | |
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 |
7D edge between two Vertex7
Definition at line 99 of file types_seven_dof_expmap.h.
g2o::EdgeSim3::EdgeSim3 | ( | ) |
Definition at line 38 of file types_seven_dof_expmap.cpp.
|
inlinevirtual |
Implements g2o::OptimizableGraph::Edge.
Definition at line 106 of file types_seven_dof_expmap.h.
|
inlinevirtual |
set the estimate of the to vertex, based on the estimate of the from vertices in the edge.
Reimplemented from g2o::BaseEdge< D, Sim3 >.
Definition at line 117 of file types_seven_dof_expmap.h.
|
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 116 of file types_seven_dof_expmap.h.
|
virtual |
read the vertex from a stream, i.e., the internal state of the vertex
Implements g2o::OptimizableGraph::Edge.
Definition at line 88 of file types_seven_dof_expmap.cpp.
|
virtual |
write the vertex to a stream
Implements g2o::OptimizableGraph::Edge.
Definition at line 108 of file types_seven_dof_expmap.cpp.