g2o
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
g2o::CacheSE3Offset Class Reference

caching the offset related to a vertex More...

#include <parameter_se3_offset.h>

Inheritance diagram for g2o::CacheSE3Offset:
Inheritance graph
[legend]
Collaboration diagram for g2o::CacheSE3Offset:
Collaboration graph
[legend]

Public Member Functions

 CacheSE3Offset ()
 
virtual void updateImpl ()
 redefine this to do the update
 
const ParameterSE3OffsetoffsetParam () const
 
void setOffsetParam (ParameterSE3Offset *offsetParam)
 
const Isometry3w2n () const
 
const Isometry3n2w () const
 
const Isometry3w2l () const
 
- Public Member Functions inherited from g2o::Cache
 Cache (CacheContainer *container_=0, const ParameterVector &parameters_=ParameterVector())
 
CacheKey key () const
 
OptimizableGraph::Vertexvertex ()
 
OptimizableGraphgraph ()
 
CacheContainercontainer ()
 
ParameterVectorparameters ()
 
void update ()
 
virtual HyperGraph::HyperGraphElementType elementType () const
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Protected Member Functions

virtual bool resolveDependencies ()
 
- Protected Member Functions inherited from g2o::Cache
CacheinstallDependency (const std::string &type_, const std::vector< int > &parameterIndices)
 

Protected Attributes

ParameterSE3Offset_offsetParam
 the parameter connected to the cache
 
Isometry3 _w2n
 
Isometry3 _n2w
 
Isometry3 _w2l
 
- Protected Attributes inherited from g2o::Cache
bool _updateNeeded
 
ParameterVector _parameters
 
std::vector< Cache * > _parentCaches
 
CacheContainer_container
 

Detailed Description

caching the offset related to a vertex

Definition at line 67 of file parameter_se3_offset.h.

Constructor & Destructor Documentation

◆ CacheSE3Offset()

g2o::CacheSE3Offset::CacheSE3Offset ( )

Definition at line 60 of file parameter_se3_offset.cpp.

60: Cache(), _offsetParam(0) {}
ParameterSE3Offset * _offsetParam
the parameter connected to the cache
Cache(CacheContainer *container_=0, const ParameterVector &parameters_=ParameterVector())
Definition cache.cpp:44

Member Function Documentation

◆ n2w()

const Isometry3 & g2o::CacheSE3Offset::n2w ( ) const
inline

◆ offsetParam()

const ParameterSE3Offset * g2o::CacheSE3Offset::offsetParam ( ) const
inline

◆ resolveDependencies()

bool g2o::CacheSE3Offset::resolveDependencies ( )
protectedvirtual

Function to be called from a cache that has dependencies. It just invokes a sequence of installDependency(). Although the caches returned are stored in the _parentCache vector, it is better that you redefine your own cache member variables, for better readability

Reimplemented from g2o::Cache.

Reimplemented in g2o::CacheCamera.

Definition at line 62 of file parameter_se3_offset.cpp.

62 {
63 _offsetParam = dynamic_cast<ParameterSE3Offset*>(_parameters[0]);
64 return _offsetParam != 0;
65}
ParameterVector _parameters
Definition cache.h:103

References _offsetParam, and g2o::Cache::_parameters.

Referenced by g2o::CacheCamera::resolveDependencies().

◆ setOffsetParam()

void g2o::CacheSE3Offset::setOffsetParam ( ParameterSE3Offset offsetParam)

Definition at line 74 of file parameter_se3_offset.cpp.

74 {
76}
const ParameterSE3Offset * offsetParam() const

References _offsetParam, and offsetParam().

◆ updateImpl()

void g2o::CacheSE3Offset::updateImpl ( )
virtual

redefine this to do the update

Implements g2o::Cache.

Reimplemented in g2o::CacheCamera.

Definition at line 67 of file parameter_se3_offset.cpp.

67 {
68 const VertexSE3* v = static_cast<const VertexSE3*>(vertex());
69 _n2w = v->estimate() * _offsetParam->offset();
70 _w2n = _n2w.inverse();
71 _w2l = v->estimate().inverse();
72}
OptimizableGraph::Vertex * vertex()
Definition cache.cpp:57
const Isometry3 & offset() const
rotation of the offset as 3x3 rotation matrix

References _n2w, _offsetParam, _w2l, _w2n, g2o::BaseVertex< D, T >::estimate(), g2o::ParameterSE3Offset::offset(), and g2o::Cache::vertex().

Referenced by g2o::CacheCamera::updateImpl().

◆ w2l()

const Isometry3 & g2o::CacheSE3Offset::w2l ( ) const
inline

◆ w2n()

const Isometry3 & g2o::CacheSE3Offset::w2n ( ) const
inline

Member Data Documentation

◆ _n2w

Isometry3 g2o::CacheSE3Offset::_n2w
protected

Definition at line 83 of file parameter_se3_offset.h.

Referenced by updateImpl().

◆ _offsetParam

ParameterSE3Offset* g2o::CacheSE3Offset::_offsetParam
protected

the parameter connected to the cache

Definition at line 81 of file parameter_se3_offset.h.

Referenced by resolveDependencies(), setOffsetParam(), and updateImpl().

◆ _w2l

Isometry3 g2o::CacheSE3Offset::_w2l
protected

Definition at line 84 of file parameter_se3_offset.h.

Referenced by updateImpl().

◆ _w2n

Isometry3 g2o::CacheSE3Offset::_w2n
protected

Definition at line 82 of file parameter_se3_offset.h.

Referenced by updateImpl().

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

g2o::CacheSE3Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 69 of file parameter_se3_offset.h.


The documentation for this class was generated from the following files: