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

offset for an SE3 More...

#include <parameter_se3_offset.h>

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

Public Member Functions

 ParameterSE3Offset ()
 
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 Isometry3 &offset_=Isometry3::Identity())
 
const Isometry3offset () const
 rotation of the offset as 3x3 rotation matrix
 
const Isometry3inverseOffset () const
 rotation of the inverse offset as 3x3 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

Isometry3 _offset
 
Isometry3 _inverseOffset
 
- Protected Attributes inherited from g2o::Parameter
int _id
 

Detailed Description

offset for an SE3

Definition at line 39 of file parameter_se3_offset.h.

Constructor & Destructor Documentation

◆ ParameterSE3Offset()

g2o::ParameterSE3Offset::ParameterSE3Offset ( )

Definition at line 39 of file parameter_se3_offset.cpp.

39{ setOffset(); }
void setOffset(const Isometry3 &offset_=Isometry3::Identity())

References setOffset().

Member Function Documentation

◆ inverseOffset()

const Isometry3 & g2o::ParameterSE3Offset::inverseOffset ( ) const
inline

rotation of the inverse offset as 3x3 rotation matrix

Definition at line 57 of file parameter_se3_offset.h.

57{ return _inverseOffset; }

Referenced by g2o::EdgeSE3PointXYZ::linearizeOplus(), g2o::ParameterCamera::setKcam(), and g2o::ParameterCamera::setOffset().

◆ offset()

const Isometry3 & g2o::ParameterSE3Offset::offset ( ) const
inline

◆ read()

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

read the data from a stream

Implements g2o::Parameter.

Reimplemented in g2o::ParameterCamera, and g2o::ParameterStereoCamera.

Definition at line 46 of file parameter_se3_offset.cpp.

46 {
47 Vector7 off;
48 bool state = internal::readVector(is, off);
49 // normalize the quaternion to recover numerical precision lost by storing as
50 // human readable text
51 Vector4::MapType(off.data() + 3).normalize();
53 return state;
54}
Isometry3 fromVectorQT(const Vector7 &v)
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
Definition io_helper.h:42
VectorN< 7 > Vector7
Definition eigen_types.h:54

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

◆ setOffset()

void g2o::ParameterSE3Offset::setOffset ( const Isometry3 offset_ = Isometry3::Identity())

update the offset to a new value. re-calculates the different representations, e.g., the rotation matrix

Definition at line 41 of file parameter_se3_offset.cpp.

41 {
42 _offset = offset_;
43 _inverseOffset = _offset.inverse();
44}

References _inverseOffset, and _offset.

Referenced by main(), ParameterSE3Offset(), read(), and g2o::ParameterCamera::setOffset().

◆ write()

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

write the data to a stream

Implements g2o::Parameter.

Reimplemented in g2o::ParameterCamera, and g2o::ParameterStereoCamera.

Definition at line 56 of file parameter_se3_offset.cpp.

56 {
58}
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
Definition io_helper.h:36
Vector7 toVectorQT(const Isometry3 &t)

References _offset, g2o::internal::toVectorQT(), and g2o::internal::writeVector().

Member Data Documentation

◆ _inverseOffset

Isometry3 g2o::ParameterSE3Offset::_inverseOffset
protected

Definition at line 61 of file parameter_se3_offset.h.

Referenced by setOffset().

◆ _offset

Isometry3 g2o::ParameterSE3Offset::_offset
protected

Definition at line 60 of file parameter_se3_offset.h.

Referenced by setOffset(), g2o::ParameterCamera::write(), and write().

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

g2o::ParameterSE3Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 41 of file parameter_se3_offset.h.


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