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

#include <parameter_camera.h>

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

Public Member Functions

const ParameterCameracamParams () const
 parameters of the camera
 
const Affine3w2i () const
 return the world to image transform
 
- Public Member Functions inherited from g2o::CacheSE3Offset
 CacheSE3Offset ()
 
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
 
- Public Attributes inherited from g2o::CacheSE3Offset
 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Protected Member Functions

virtual void updateImpl ()
 redefine this to do the update
 
virtual bool resolveDependencies ()
 
- Protected Member Functions inherited from g2o::Cache
CacheinstallDependency (const std::string &type_, const std::vector< int > &parameterIndices)
 

Protected Attributes

Affine3 _w2i
 world to image transform
 
ParameterCameraparams
 
- Protected Attributes inherited from g2o::CacheSE3Offset
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

Definition at line 58 of file parameter_camera.h.

Member Function Documentation

◆ camParams()

const ParameterCamera * g2o::CacheCamera::camParams ( ) const
inline

parameters of the camera

Definition at line 62 of file parameter_camera.h.

62{ return params; }
ParameterCamera * params

◆ resolveDependencies()

bool g2o::CacheCamera::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::CacheSE3Offset.

Definition at line 85 of file parameter_camera.cpp.

85 {
86 if (!CacheSE3Offset::resolveDependencies()) return false;
87 params = dynamic_cast<ParameterCamera*>(_parameters[0]);
88 return params != 0;
89}
virtual bool resolveDependencies()
ParameterVector _parameters
Definition cache.h:103

References g2o::Cache::_parameters, params, and g2o::CacheSE3Offset::resolveDependencies().

◆ updateImpl()

void g2o::CacheCamera::updateImpl ( )
protectedvirtual

redefine this to do the update

Reimplemented from g2o::CacheSE3Offset.

Definition at line 91 of file parameter_camera.cpp.

91 {
93 _w2i.matrix().topLeftCorner<3, 4>() =
94 params->Kcam() * w2n().matrix().topLeftCorner<3, 4>();
95}
Affine3 _w2i
world to image transform
const Isometry3 & w2n() const
virtual void updateImpl()
redefine this to do the update
const Matrix3 & Kcam() const

References _w2i, g2o::ParameterCamera::Kcam(), params, g2o::CacheSE3Offset::updateImpl(), and g2o::CacheSE3Offset::w2n().

◆ w2i()

const Affine3 & g2o::CacheCamera::w2i ( ) const
inline

Member Data Documentation

◆ _w2i

Affine3 g2o::CacheCamera::_w2i
protected

world to image transform

Definition at line 69 of file parameter_camera.h.

Referenced by updateImpl().

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

g2o::CacheCamera::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 60 of file parameter_camera.h.

◆ params

ParameterCamera* g2o::CacheCamera::params
protected

Definition at line 70 of file parameter_camera.h.

Referenced by resolveDependencies(), and updateImpl().


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