g2o
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Protected Attributes | List of all members
g2o::ParameterSE2Offset Class Reference

offset for an SE2 More...

#include <parameter_se2_offset.h>

Inheritance diagram for g2o::ParameterSE2Offset:
Inheritance graph
[legend]
Collaboration diagram for g2o::ParameterSE2Offset:
Collaboration graph
[legend]

Public Member Functions

 ParameterSE2Offset ()
 
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 SE2 &offset_=SE2())
 
const SE2offset () const
 
const Isometry2offsetMatrix () const
 rotation of the offset as 2x2 rotation matrix
 
const Isometry2inverseOffsetMatrix () const
 rotation of the inverse offset as 2x2 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

SE2 _offset
 
Isometry2 _offsetMatrix
 
Isometry2 _inverseOffsetMatrix
 
- Protected Attributes inherited from g2o::Parameter
int _id
 

Detailed Description

offset for an SE2

Definition at line 41 of file parameter_se2_offset.h.

Constructor & Destructor Documentation

◆ ParameterSE2Offset()

g2o::ParameterSE2Offset::ParameterSE2Offset ( )

Definition at line 38 of file parameter_se2_offset.cpp.

38{ setOffset(); }
void setOffset(const SE2 &offset_=SE2())

References setOffset().

Member Function Documentation

◆ inverseOffsetMatrix()

const Isometry2 & g2o::ParameterSE2Offset::inverseOffsetMatrix ( ) const
inline

rotation of the inverse offset as 2x2 rotation matrix

Definition at line 61 of file parameter_se2_offset.h.

◆ offset()

const SE2 & g2o::ParameterSE2Offset::offset ( ) const
inline

◆ offsetMatrix()

const Isometry2 & g2o::ParameterSE2Offset::offsetMatrix ( ) const
inline

rotation of the offset as 2x2 rotation matrix

Definition at line 58 of file parameter_se2_offset.h.

58{ return _offsetMatrix; }

Referenced by g2o::EdgeSE2PointXYOffset::initialEstimate().

◆ read()

bool g2o::ParameterSE2Offset::read ( std::istream &  is)
virtual

read the data from a stream

Implements g2o::Parameter.

Definition at line 47 of file parameter_se2_offset.cpp.

47 {
48 Vector3 off;
49 bool state = g2o::internal::readVector(is, off);
50 setOffset(SE2(off));
51 return state;
52}
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
Definition io_helper.h:42
VectorN< 3 > Vector3
Definition eigen_types.h:51

References g2o::internal::readVector(), and setOffset().

◆ setOffset()

void g2o::ParameterSE2Offset::setOffset ( const SE2 offset_ = SE2())

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.

40 {
41 _offset = offset_;
42 _offsetMatrix = _offset.rotation().toRotationMatrix();
43 _offsetMatrix.translation() = _offset.translation();
45}
const Vector2 & translation() const
translational component
Definition se2.h:57
const Rotation2D & rotation() const
rotational component
Definition se2.h:61

References _inverseOffsetMatrix, _offset, _offsetMatrix, g2o::SE2::rotation(), and g2o::SE2::translation().

Referenced by ParameterSE2Offset(), and read().

◆ write()

bool g2o::ParameterSE2Offset::write ( std::ostream &  os) const
virtual

write the data to a stream

Implements g2o::Parameter.

Definition at line 54 of file parameter_se2_offset.cpp.

54 {
55 return internal::writeVector(os, offset().toVector());
56}
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
Definition io_helper.h:36

References offset(), and g2o::internal::writeVector().

Member Data Documentation

◆ _inverseOffsetMatrix

Isometry2 g2o::ParameterSE2Offset::_inverseOffsetMatrix
protected

Definition at line 66 of file parameter_se2_offset.h.

Referenced by setOffset().

◆ _offset

SE2 g2o::ParameterSE2Offset::_offset
protected

Definition at line 64 of file parameter_se2_offset.h.

Referenced by setOffset().

◆ _offsetMatrix

Isometry2 g2o::ParameterSE2Offset::_offsetMatrix
protected

Definition at line 65 of file parameter_se2_offset.h.

Referenced by setOffset().

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

g2o::ParameterSE2Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 43 of file parameter_se2_offset.h.


The documentation for this class was generated from the following files: