|
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 | |
| virtual bool | write (std::ostream &os) const |
| write the data to a stream | |
| void | setOffset (const Isometry3 &offset_=Isometry3::Identity()) |
| const Isometry3 & | offset () const |
| rotation of the offset as 3x3 rotation matrix | |
| const Isometry3 & | inverseOffset () const |
| rotation of the inverse offset as 3x3 rotation matrix | |
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 () |
Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | |
Protected Attributes | |
| Isometry3 | _offset |
| Isometry3 | _inverseOffset |
Protected Attributes inherited from g2o::Parameter | |
| int | _id |
offset for an SE3
Definition at line 39 of file parameter_se3_offset.h.
| g2o::ParameterSE3Offset::ParameterSE3Offset | ( | ) |
Definition at line 39 of file parameter_se3_offset.cpp.
References setOffset().
|
inline |
rotation of the inverse offset as 3x3 rotation matrix
Definition at line 57 of file parameter_se3_offset.h.
Referenced by g2o::EdgeSE3PointXYZ::linearizeOplus(), g2o::ParameterCamera::setKcam(), and g2o::ParameterCamera::setOffset().
|
inline |
rotation of the offset as 3x3 rotation matrix
Definition at line 54 of file parameter_se3_offset.h.
Referenced by g2o::EdgeSE3XYZPrior::initialEstimate(), g2o::EdgeSE3Offset::initialEstimate(), g2o::EdgeSE3PointXYZ::initialEstimate(), g2o::EdgeSE3PointXYZDepth::initialEstimate(), g2o::EdgeSE3PointXYZDisparity::initialEstimate(), g2o::EdgeSE3Prior::initialEstimate(), g2o::EdgeSE3Offset::linearizeOplus(), g2o::EdgeSE3Prior::linearizeOplus(), g2o::SensorPointXYZ::sense(), g2o::SensorPointXYZDepth::sense(), g2o::SensorPointXYZDisparity::sense(), g2o::SensorSE3Prior::sense(), and g2o::CacheSE3Offset::updateImpl().
|
virtual |
read the data from a stream
Implements g2o::Parameter.
Reimplemented in g2o::ParameterCamera, and g2o::ParameterStereoCamera.
Definition at line 46 of file parameter_se3_offset.cpp.
References g2o::internal::fromVectorQT(), g2o::internal::readVector(), and setOffset().
| void g2o::ParameterSE3Offset::setOffset | ( | const Isometry3 & | offset_ = Isometry3::Identity() | ) |
update the offset to a new value. re-calculates the different representations, e.g., the rotation matrix
Definition at line 41 of file parameter_se3_offset.cpp.
References _inverseOffset, and _offset.
Referenced by main(), ParameterSE3Offset(), read(), and g2o::ParameterCamera::setOffset().
|
virtual |
write the data to a stream
Implements g2o::Parameter.
Reimplemented in g2o::ParameterCamera, and g2o::ParameterStereoCamera.
Definition at line 56 of file parameter_se3_offset.cpp.
References _offset, g2o::internal::toVectorQT(), and g2o::internal::writeVector().
|
protected |
Definition at line 61 of file parameter_se3_offset.h.
Referenced by setOffset().
|
protected |
Definition at line 60 of file parameter_se3_offset.h.
Referenced by setOffset(), g2o::ParameterCamera::write(), and write().
| g2o::ParameterSE3Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
Definition at line 41 of file parameter_se3_offset.h.