|
g2o
|
#include <parameter_camera.h>


Public Member Functions | |
| const ParameterCamera * | camParams () const |
| parameters of the camera | |
| const Affine3 & | w2i () const |
| return the world to image transform | |
Public Member Functions inherited from g2o::CacheSE3Offset | |
| CacheSE3Offset () | |
| const ParameterSE3Offset * | offsetParam () const |
| void | setOffsetParam (ParameterSE3Offset *offsetParam) |
| const Isometry3 & | w2n () const |
| const Isometry3 & | n2w () const |
| const Isometry3 & | w2l () const |
Public Member Functions inherited from g2o::Cache | |
| Cache (CacheContainer *container_=0, const ParameterVector ¶meters_=ParameterVector()) | |
| CacheKey | key () const |
| OptimizableGraph::Vertex * | vertex () |
| OptimizableGraph * | graph () |
| CacheContainer * | container () |
| ParameterVector & | parameters () |
| 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 | |
| Cache * | installDependency (const std::string &type_, const std::vector< int > ¶meterIndices) |
Protected Attributes | |
| Affine3 | _w2i |
| world to image transform | |
| ParameterCamera * | params |
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 |
Definition at line 58 of file parameter_camera.h.
|
inline |
|
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.
References g2o::Cache::_parameters, params, and g2o::CacheSE3Offset::resolveDependencies().
|
protectedvirtual |
redefine this to do the update
Reimplemented from g2o::CacheSE3Offset.
Definition at line 91 of file parameter_camera.cpp.
References _w2i, g2o::ParameterCamera::Kcam(), params, g2o::CacheSE3Offset::updateImpl(), and g2o::CacheSE3Offset::w2n().
|
inline |
return the world to image transform
Definition at line 64 of file parameter_camera.h.
Referenced by g2o::EdgeSE3PointXYZDepth::computeError(), g2o::EdgeSE3PointXYZDisparity::computeError(), g2o::EdgeSE3PointXYZDepth::linearizeOplus(), g2o::EdgeSE3PointXYZDisparity::linearizeOplus(), g2o::EdgeSE3PointXYZDepth::setMeasurementFromState(), and g2o::EdgeSE3PointXYZDisparity::setMeasurementFromState().
|
protected |
world to image transform
Definition at line 69 of file parameter_camera.h.
Referenced by updateImpl().
| g2o::CacheCamera::EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
Definition at line 60 of file parameter_camera.h.
|
protected |
Definition at line 70 of file parameter_camera.h.
Referenced by resolveDependencies(), and updateImpl().