g2o
Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
g2o::deprecated::CacheSE3Offset Class Reference

caching the offset related to a vertex More...

#include <parameter_se3_offset.h>

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

Public Member Functions

 CacheSE3Offset ()
 
virtual void updateImpl ()
 redefine this to do the update More...
 
const ParameterSE3OffsetoffsetParam () const
 
void setOffsetParam (ParameterSE3Offset *offsetParam)
 
const SE3Quatw2n () const
 
const SE3Quatn2w () const
 
const Eigen::Isometry3d & w2nMatrix () const
 
const Eigen::Isometry3d & n2wMatrix () const
 
const Eigen::Isometry3d & w2lMatrix () 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 ()
 
HyperGraphElementclone () const
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Protected Member Functions

virtual bool resolveDependancies ()
 
- 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 More...
 
SE3Quat _se3_w2n
 
SE3Quat _se3_n2w
 
Eigen::Isometry3d _w2n
 world to sensor transform More...
 
Eigen::Isometry3d _w2l
 world to local More...
 
Eigen::Isometry3d _n2w
 sensor to world More...
 
- 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 81 of file parameter_se3_offset.h.

Constructor & Destructor Documentation

g2o::deprecated::CacheSE3Offset::CacheSE3Offset ( )

Definition at line 66 of file parameter_se3_offset.cpp.

66  :
67  Cache(),
68  _offsetParam(0)
69  {
70  }
Cache(CacheContainer *container_=0, const ParameterVector &parameters_=ParameterVector())
Definition: cache.cpp:46
ParameterSE3Offset * _offsetParam
the parameter connected to the cache

Member Function Documentation

const SE3Quat& g2o::deprecated::CacheSE3Offset::n2w ( ) const
inline
const Eigen::Isometry3d& g2o::deprecated::CacheSE3Offset::n2wMatrix ( ) const
inline

Definition at line 94 of file parameter_se3_offset.h.

94 { return _n2w;}
Eigen::Isometry3d _n2w
sensor to world
const ParameterSE3Offset* g2o::deprecated::CacheSE3Offset::offsetParam ( ) const
inline
bool g2o::deprecated::CacheSE3Offset::resolveDependancies ( )
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::deprecated::CacheCamera.

Definition at line 72 of file parameter_se3_offset.cpp.

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

72  {
73  _offsetParam = dynamic_cast <ParameterSE3Offset*> (_parameters[0]);
74  return _offsetParam != 0;
75  }
ParameterVector _parameters
Definition: cache.h:99
ParameterSE3Offset * _offsetParam
the parameter connected to the cache
void g2o::deprecated::CacheSE3Offset::setOffsetParam ( ParameterSE3Offset offsetParam)
void g2o::deprecated::CacheSE3Offset::updateImpl ( )
virtual

redefine this to do the update

Implements g2o::Cache.

Reimplemented in g2o::deprecated::CacheCamera.

Definition at line 77 of file parameter_se3_offset.cpp.

References _n2w, _offsetParam, _se3_n2w, _se3_w2n, _w2l, _w2n, g2o::BaseVertex< D, T >::estimate(), g2o::SE3Quat::inverse(), g2o::deprecated::ParameterSE3Offset::offset(), g2o::SE3Quat::rotation(), g2o::SE3Quat::translation(), and g2o::Cache::vertex().

77  {
78  const VertexSE3* v = static_cast<const VertexSE3*>(vertex());
79  _se3_n2w = v->estimate() * _offsetParam->offset();
80 
81  _n2w = _se3_n2w.rotation().toRotationMatrix();
82  _n2w.translation() = _se3_n2w.translation();
83 
85  _w2n = _se3_w2n.rotation().toRotationMatrix();
86  _w2n.translation() = _se3_w2n.translation();
87 
88  SE3Quat w2l = v->estimate().inverse();
89  _w2l = w2l.rotation().toRotationMatrix();
90  _w2l.translation() = w2l.translation();
91  }
const SE3Quat & offset() const
return the offset as SE3Quat
OptimizableGraph::Vertex * vertex()
Definition: cache.cpp:61
SE3Quat inverse() const
Definition: se3quat.h:120
ParameterSE3Offset * _offsetParam
the parameter connected to the cache
Eigen::Isometry3d _w2l
world to local
const Eigen::Quaterniond & rotation() const
Definition: se3quat.h:97
Eigen::Isometry3d _n2w
sensor to world
Eigen::Isometry3d _w2n
world to sensor transform
const Vector3D & translation() const
Definition: se3quat.h:93
const Eigen::Isometry3d& g2o::deprecated::CacheSE3Offset::w2lMatrix ( ) const
inline
const SE3Quat& g2o::deprecated::CacheSE3Offset::w2n ( ) const
inline
const Eigen::Isometry3d& g2o::deprecated::CacheSE3Offset::w2nMatrix ( ) const
inline

Member Data Documentation

Eigen::Isometry3d g2o::deprecated::CacheSE3Offset::_n2w
protected

sensor to world

Definition at line 104 of file parameter_se3_offset.h.

Referenced by updateImpl().

ParameterSE3Offset* g2o::deprecated::CacheSE3Offset::_offsetParam
protected

the parameter connected to the cache

Definition at line 98 of file parameter_se3_offset.h.

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

SE3Quat g2o::deprecated::CacheSE3Offset::_se3_n2w
protected

Definition at line 100 of file parameter_se3_offset.h.

Referenced by updateImpl().

SE3Quat g2o::deprecated::CacheSE3Offset::_se3_w2n
protected

Definition at line 99 of file parameter_se3_offset.h.

Referenced by updateImpl().

Eigen::Isometry3d g2o::deprecated::CacheSE3Offset::_w2l
protected

world to local

Definition at line 103 of file parameter_se3_offset.h.

Referenced by updateImpl().

Eigen::Isometry3d g2o::deprecated::CacheSE3Offset::_w2n
protected

world to sensor transform

Definition at line 102 of file parameter_se3_offset.h.

Referenced by updateImpl().

g2o::deprecated::CacheSE3Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 83 of file parameter_se3_offset.h.


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