g2o
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 More...
 
virtual bool write (std::ostream &os) const
 write the data to a stream 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
 
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

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

Definition at line 34 of file parameter_se2_offset.cpp.

35  {
36  }

Member Function Documentation

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

Definition at line 46 of file parameter_se2_offset.h.

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

Definition at line 45 of file parameter_se2_offset.h.

Referenced by setOffset().

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

read the data from a stream

Implements g2o::Parameter.

Definition at line 44 of file parameter_se2_offset.cpp.

References setOffset().

45  {
46  double x, y, th;
47  is >> x >> y >> th;
48  setOffset(SE2(x, y, th));
49  return true;
50  }
void setOffset(const SE2 &offset=SE2())
void g2o::tutorial::ParameterSE2Offset::setOffset ( const SE2 offset = SE2())
bool g2o::tutorial::ParameterSE2Offset::write ( std::ostream &  os) const
virtual

write the data to a stream

Implements g2o::Parameter.

Definition at line 52 of file parameter_se2_offset.cpp.

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

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

Member Data Documentation

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

Definition at line 53 of file parameter_se2_offset.h.

Referenced by setOffset().

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

Definition at line 52 of file parameter_se2_offset.h.

Referenced by setOffset(), and write().

g2o::tutorial::ParameterSE2Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 40 of file parameter_se2_offset.h.


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