27 #ifndef G2O_DEPRECATED_VERTEX_SE3_OFFSET_PARAMETERS_H_ 28 #define G2O_DEPRECATED_VERTEX_SE3_OFFSET_PARAMETERS_H_ 37 #include <Eigen/Geometry> 40 namespace deprecated {
54 virtual bool read(std::istream& is);
55 virtual bool write(std::ostream& os)
const;
67 const Eigen::Isometry3d&
offsetMatrix()
const {
return _offsetMatrix;}
85 virtual void updateImpl();
93 const Eigen::Isometry3d&
w2nMatrix()
const {
return _w2n;}
94 const Eigen::Isometry3d&
n2wMatrix()
const {
return _n2w;}
95 const Eigen::Isometry3d&
w2lMatrix()
const {
return _w2l;}
107 virtual bool resolveDependancies();
111 #ifdef G2O_HAVE_OPENGL 114 CacheSE3OffsetDrawAction();
caching the offset related to a vertex
const SE3Quat & offset() const
return the offset as SE3Quat
const Eigen::Isometry3d & inverseOffsetMatrix() const
rotation of the inverse offset as 3x3 rotation matrix
Abstract action that operates on a graph entity.
ParameterSE3Offset * _offsetParam
the parameter connected to the cache
const Eigen::Isometry3d & n2wMatrix() const
const Eigen::Isometry3d & w2nMatrix() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Eigen::Isometry3d _inverseOffsetMatrix
#define G2O_DEPRECATED_TYPES_SLAM3D_API
Eigen::Isometry3d _w2l
world to local
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
const Eigen::Isometry3d & offsetMatrix() const
rotation of the offset as 3x3 rotation matrix
const SE3Quat & n2w() const
Eigen::Isometry3d _n2w
sensor to world
const Eigen::Isometry3d & w2lMatrix() const
Eigen::Isometry3d _offsetMatrix
const SE3Quat & w2n() const
Eigen::Isometry3d _w2n
world to sensor transform
const ParameterSE3Offset * offsetParam() const