g2o
|
offset for an SE3 More...
#include <parameter_se3_offset.h>
Public Member Functions | |
ParameterSE3Offset () | |
virtual bool | read (std::istream &is) |
read the data from a stream More... | |
virtual bool | write (std::ostream &os) const |
write the data to a stream More... | |
void | setOffset (const Isometry3D &offset_=Isometry3D::Identity()) |
const Isometry3D & | offset () const |
rotation of the offset as 3x3 rotation matrix More... | |
const Isometry3D & | inverseOffset () const |
rotation of the inverse offset as 3x3 rotation matrix More... | |
Public Member Functions inherited from g2o::Parameter | |
Parameter () | |
virtual | ~Parameter () |
int | id () const |
void | setId (int id_) |
virtual HyperGraph::HyperGraphElementType | elementType () const |
Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement | |
virtual | ~HyperGraphElement () |
HyperGraphElement * | clone () const |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | |
Protected Attributes | |
Isometry3D | _offset |
Isometry3D | _inverseOffset |
Protected Attributes inherited from g2o::Parameter | |
int | _id |
offset for an SE3
Definition at line 45 of file parameter_se3_offset.h.
g2o::ParameterSE3Offset::ParameterSE3Offset | ( | ) |
Definition at line 38 of file parameter_se3_offset.cpp.
References setOffset().
|
inline |
rotation of the inverse offset as 3x3 rotation matrix
Definition at line 64 of file parameter_se3_offset.h.
Referenced by g2o::EdgeSE3PointXYZ::linearizeOplus().
|
inline |
rotation of the offset as 3x3 rotation matrix
Definition at line 61 of file parameter_se3_offset.h.
Referenced by g2o::EdgeSE3Offset::initialEstimate(), g2o::EdgeSE3PointXYZDepth::initialEstimate(), g2o::EdgeSE3Prior::initialEstimate(), g2o::EdgeSE3PointXYZ::initialEstimate(), g2o::EdgeSE3PointXYZDisparity::initialEstimate(), g2o::EdgeSE3Prior::linearizeOplus(), g2o::EdgeSE3Offset::linearizeOplus(), g2o::SensorSE3Prior::sense(), g2o::SensorPointXYZ::sense(), g2o::SensorPointXYZDepth::sense(), g2o::SensorPointXYZDisparity::sense(), g2o::CacheSE3Offset::setOffsetParam(), g2o::CacheCamera::updateImpl(), and g2o::CacheSE3Offset::updateImpl().
|
virtual |
read the data from a stream
Implements g2o::Parameter.
Reimplemented in g2o::ParameterCamera, and g2o::ParameterStereoCamera.
Definition at line 47 of file parameter_se3_offset.cpp.
References g2o::internal::fromVectorQT(), g2o::internal::normalize(), and setOffset().
void g2o::ParameterSE3Offset::setOffset | ( | const Isometry3D & | offset_ = Isometry3D::Identity() | ) |
update the offset to a new value. re-calculates the different representations, e.g., the rotation matrix
Definition at line 42 of file parameter_se3_offset.cpp.
References _inverseOffset, and _offset.
Referenced by main(), ParameterSE3Offset(), and read().
|
virtual |
write the data to a stream
Implements g2o::Parameter.
Reimplemented in g2o::ParameterCamera, and g2o::ParameterStereoCamera.
Definition at line 58 of file parameter_se3_offset.cpp.
References _offset, and g2o::internal::toVectorQT().
|
protected |
Definition at line 68 of file parameter_se3_offset.h.
Referenced by setOffset().
|
protected |
Definition at line 67 of file parameter_se3_offset.h.
Referenced by setOffset(), and write().
g2o::ParameterSE3Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
Definition at line 48 of file parameter_se3_offset.h.