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

#include <parameter_se2_offset.h>

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

Public Member Functions

 ParameterSE2Offset ()
 
void setOffset (const SE2 &offset=SE2())
 
const SE2offset () const
 
const SE2inverseOffset () const
 
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
 
- 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
 
SE2 _inverseOffset
 
- Protected Attributes inherited from g2o::Parameter
int _id
 

Detailed Description

Definition at line 37 of file parameter_se2_offset.h.

Constructor & Destructor Documentation

◆ ParameterSE2Offset()

g2o::tutorial::ParameterSE2Offset::ParameterSE2Offset ( )

Definition at line 34 of file parameter_se2_offset.cpp.

34{}

Member Function Documentation

◆ inverseOffset()

const SE2 & g2o::tutorial::ParameterSE2Offset::inverseOffset ( ) const
inline

Definition at line 45 of file parameter_se2_offset.h.

◆ offset()

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

◆ read()

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

read the data from a stream

Implements g2o::Parameter.

Definition at line 41 of file parameter_se2_offset.cpp.

41 {
42 double x, y, th;
43 is >> x >> y >> th;
44 setOffset(SE2(x, y, th));
45 return true;
46}
void setOffset(const SE2 &offset=SE2())

References setOffset().

◆ setOffset()

void g2o::tutorial::ParameterSE2Offset::setOffset ( const SE2 offset = SE2())

Definition at line 36 of file parameter_se2_offset.cpp.

36 {
39}
SE2 inverse() const
Definition se2.h:76

References _inverseOffset, _offset, g2o::tutorial::SE2::inverse(), and offset().

Referenced by main(), and read().

◆ write()

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

write the data to a stream

Implements g2o::Parameter.

Definition at line 48 of file parameter_se2_offset.cpp.

48 {
49 os << _offset.translation().x() << " " << _offset.translation().y() << " "
50 << _offset.rotation().angle();
51 return os.good();
52}
const Eigen::Vector2d & translation() const
Definition se2.h:49
const Eigen::Rotation2Dd & rotation() const
Definition se2.h:53

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

Member Data Documentation

◆ _inverseOffset

SE2 g2o::tutorial::ParameterSE2Offset::_inverseOffset
protected

Definition at line 52 of file parameter_se2_offset.h.

Referenced by setOffset().

◆ _offset

SE2 g2o::tutorial::ParameterSE2Offset::_offset
protected

Definition at line 51 of file parameter_se2_offset.h.

Referenced by setOffset(), and write().

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

g2o::tutorial::ParameterSE2Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 39 of file parameter_se2_offset.h.


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