g2o
|
#include <parameter_se2_offset.h>
Public Member Functions | |
ParameterSE2Offset () | |
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 SE2 &offset_=SE2()) |
const SE2 & | offset () const |
const Isometry2D & | offsetMatrix () const |
rotation of the offset as 2x2 rotation matrix More... | |
const Isometry2D & | inverseOffsetMatrix () const |
rotation of the inverse offset as 2x2 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 | |
SE2 | _offset |
Isometry2D | _offsetMatrix |
Isometry2D | _inverseOffsetMatrix |
Protected Attributes inherited from g2o::Parameter | |
int | _id |
offset for an SE2
Definition at line 46 of file parameter_se2_offset.h.
g2o::ParameterSE2Offset::ParameterSE2Offset | ( | ) |
Definition at line 36 of file parameter_se2_offset.cpp.
References setOffset().
|
inline |
rotation of the inverse offset as 2x2 rotation matrix
Definition at line 67 of file parameter_se2_offset.h.
|
inline |
Definition at line 61 of file parameter_se2_offset.h.
Referenced by g2o::EdgeSE2Offset::initialEstimate(), g2o::SensorPointXYOffset::sense(), and g2o::CacheSE2Offset::updateImpl().
|
inline |
rotation of the offset as 2x2 rotation matrix
Definition at line 64 of file parameter_se2_offset.h.
Referenced by g2o::EdgeSE2PointXYOffset::initialEstimate().
|
virtual |
read the data from a stream
Implements g2o::Parameter.
Definition at line 47 of file parameter_se2_offset.cpp.
References setOffset().
update the offset to a new value. re-calculates the different representations, e.g., the rotation matrix
Definition at line 40 of file parameter_se2_offset.cpp.
References _inverseOffsetMatrix, _offset, _offsetMatrix, g2o::SE2::rotation(), and g2o::SE2::translation().
Referenced by ParameterSE2Offset(), and read().
|
virtual |
write the data to a stream
Implements g2o::Parameter.
Definition at line 58 of file parameter_se2_offset.cpp.
References _offset, and g2o::SE2::toVector().
|
protected |
Definition at line 72 of file parameter_se2_offset.h.
Referenced by setOffset().
|
protected |
Definition at line 70 of file parameter_se2_offset.h.
Referenced by setOffset(), and write().
|
protected |
Definition at line 71 of file parameter_se2_offset.h.
Referenced by setOffset().
g2o::ParameterSE2Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
Definition at line 49 of file parameter_se2_offset.h.