g2o
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 More...
 
virtual bool write (std::ostream &os) const
 write the data to a stream More...
 
void setOffset (const SE2 &offset_=SE2())
 
const SE2offset () const
 
const Isometry2DoffsetMatrix () const
 rotation of the offset as 2x2 rotation matrix More...
 
const Isometry2DinverseOffsetMatrix () 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 ()
 
HyperGraphElementclone () const
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Protected Attributes

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

Detailed Description

offset for an SE2

Definition at line 46 of file parameter_se2_offset.h.

Constructor & Destructor Documentation

g2o::ParameterSE2Offset::ParameterSE2Offset ( )

Definition at line 36 of file parameter_se2_offset.cpp.

References setOffset().

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

Member Function Documentation

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

rotation of the inverse offset as 2x2 rotation matrix

Definition at line 67 of file parameter_se2_offset.h.

67 { return _inverseOffsetMatrix;}
const SE2& g2o::ParameterSE2Offset::offset ( ) const
inline
const Isometry2D& g2o::ParameterSE2Offset::offsetMatrix ( ) const
inline

rotation of the offset as 2x2 rotation matrix

Definition at line 64 of file parameter_se2_offset.h.

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

64 { return _offsetMatrix;}
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.

References setOffset().

47  {
48  Vector3D off;
49  for (int i=0; i<3; i++) {
50  is >> off[i];
51  std::cerr << off[i] << " " ;
52  }
53  std::cerr << std::endl;
54  setOffset(SE2(off));
55  return is.good() || is.eof();
56  }
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
void setOffset(const SE2 &offset_=SE2())
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.

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

Referenced by ParameterSE2Offset(), and read().

40  {
41  _offset = offset_;
42  _offsetMatrix= _offset.rotation().toRotationMatrix();
43  _offsetMatrix.translation() = _offset.translation();
45  }
const Eigen::Rotation2Dd & rotation() const
rotational component
Definition: se2.h:58
const Vector2D & translation() const
translational component
Definition: se2.h:54
bool g2o::ParameterSE2Offset::write ( std::ostream &  os) const
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().

58  {
59  Vector3D off = _offset.toVector();
60  for (int i=0; i<3; i++)
61  os << off[i] << " ";
62  return os.good();
63  }
Vector3D toVector() const
convert to a 3D vector (x, y, theta)
Definition: se2.h:108
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46

Member Data Documentation

Isometry2D g2o::ParameterSE2Offset::_inverseOffsetMatrix
protected

Definition at line 72 of file parameter_se2_offset.h.

Referenced by setOffset().

SE2 g2o::ParameterSE2Offset::_offset
protected

Definition at line 70 of file parameter_se2_offset.h.

Referenced by setOffset(), and write().

Isometry2D g2o::ParameterSE2Offset::_offsetMatrix
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.


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