Public Member Functions | Protected Attributes | List of all members
octomath::Pose6D Class Reference

This class represents a tree-dimensional pose of an object. More...

#include <Pose6D.h>

Public Member Functions

double distance (const Pose6D &other) const
 Translational distance. More...
 
Pose6D inv () const
 Inversion. More...
 
Pose6Dinv_IP ()
 Inversion. More...
 
bool operator!= (const Pose6D &other) const
 
Pose6D operator* (const Pose6D &p) const
 Concatenation. More...
 
const Pose6Doperator*= (const Pose6D &p)
 In place concatenation. More...
 
Pose6Doperator= (const Pose6D &other)
 
bool operator== (const Pose6D &other) const
 
double pitch () const
 
 Pose6D ()
 
 Pose6D (const Pose6D &other)
 
 Pose6D (const Vector3 &trans, const Quaternion &rot)
 Constructor. More...
 
 Pose6D (float x, float y, float z, double roll, double pitch, double yaw)
 Constructor. More...
 
std::istream & read (std::istream &s)
 Input operator. More...
 
std::istream & readBinary (std::istream &s)
 Binary input operator. More...
 
double roll () const
 
Quaternionrot ()
 Rotational component. More...
 
const Quaternionrot () const
 Rotational component. More...
 
Vector3trans ()
 Translational component. More...
 
const Vector3trans () const
 Translational component. More...
 
Vector3 transform (const Vector3 &v) const
 Transformation of a vector. More...
 
double transLength () const
 Translational length. More...
 
std::ostream & write (std::ostream &s) const
 Output operator. More...
 
std::ostream & writeBinary (std::ostream &s) const
 Binary output operator. More...
 
float & x ()
 
const float & x () const
 
float & y ()
 
const float & y () const
 
double yaw () const
 
float & z ()
 
const float & z () const
 
 ~Pose6D ()
 

Protected Attributes

Quaternion rotation
 
Vector3 translation
 

Detailed Description

This class represents a tree-dimensional pose of an object.

The tree-dimensional pose is represented by a three-dimensional translation vector representing the position of the object and a Quaternion representing the attitude of the object

Definition at line 49 of file Pose6D.h.

Constructor & Destructor Documentation

◆ Pose6D() [1/4]

octomath::Pose6D::Pose6D ( )

Definition at line 39 of file Pose6D.cpp.

◆ ~Pose6D()

octomath::Pose6D::~Pose6D ( )

Definition at line 55 of file Pose6D.cpp.

◆ Pose6D() [2/4]

octomath::Pose6D::Pose6D ( const Vector3 trans,
const Quaternion rot 
)

Constructor.

Constructs a pose from given translation and rotation.

Definition at line 43 of file Pose6D.cpp.

◆ Pose6D() [3/4]

octomath::Pose6D::Pose6D ( float  x,
float  y,
float  z,
double  roll,
double  pitch,
double  yaw 
)

Constructor.

Constructs a pose from a translation represented by its x, y, z-values and a rotation represented by its Tait-Bryan angles roll, pitch, and yaw

Definition at line 50 of file Pose6D.cpp.

◆ Pose6D() [4/4]

octomath::Pose6D::Pose6D ( const Pose6D other)

Definition at line 58 of file Pose6D.cpp.

Member Function Documentation

◆ distance()

double octomath::Pose6D::distance ( const Pose6D other) const

Translational distance.

Returns
the translational (euclidian) distance to p

Definition at line 103 of file Pose6D.cpp.

◆ inv()

Pose6D octomath::Pose6D::inv ( ) const

Inversion.

Inverts the coordinate transformation represented by this pose

Returns
a copy of this pose inverted

Definition at line 70 of file Pose6D.cpp.

◆ inv_IP()

Pose6D & octomath::Pose6D::inv_IP ( )

Inversion.

Inverts the coordinate transformation represented by this pose

Returns
a reference to this pose

Definition at line 78 of file Pose6D.cpp.

◆ operator!=()

bool octomath::Pose6D::operator!= ( const Pose6D other) const

Definition at line 120 of file Pose6D.cpp.

◆ operator*()

Pose6D octomath::Pose6D::operator* ( const Pose6D p) const

Concatenation.

Concatenates the coordinate transformations represented by this and p.

Returns
this * p (applies first this, then p)

Definition at line 91 of file Pose6D.cpp.

◆ operator*=()

const Pose6D & octomath::Pose6D::operator*= ( const Pose6D p)

In place concatenation.

Concatenates p to this Pose6D.

Returns
this which results from first moving by this and afterwards by p

Definition at line 97 of file Pose6D.cpp.

◆ operator=()

Pose6D & octomath::Pose6D::operator= ( const Pose6D other)

Definition at line 63 of file Pose6D.cpp.

◆ operator==()

bool octomath::Pose6D::operator== ( const Pose6D other) const

Definition at line 115 of file Pose6D.cpp.

◆ pitch()

double octomath::Pose6D::pitch ( ) const
inline

Definition at line 110 of file Pose6D.h.

◆ read()

std::istream & octomath::Pose6D::read ( std::istream &  s)

Input operator.

Parsing from stream which was written by write().

Definition at line 124 of file Pose6D.cpp.

◆ readBinary()

std::istream & octomath::Pose6D::readBinary ( std::istream &  s)

Binary input operator.

Parsing from binary stream which was written by writeBinary().

Definition at line 139 of file Pose6D.cpp.

◆ roll()

double octomath::Pose6D::roll ( ) const
inline

Definition at line 109 of file Pose6D.h.

◆ rot() [1/2]

Quaternion& octomath::Pose6D::rot ( )
inline

Rotational component.

Returns
the rotational component of this pose

Definition at line 88 of file Pose6D.h.

◆ rot() [2/2]

const Quaternion& octomath::Pose6D::rot ( ) const
inline

Rotational component.

Returns
the rotational component of this pose

Definition at line 99 of file Pose6D.h.

◆ trans() [1/2]

Vector3& octomath::Pose6D::trans ( )
inline

Translational component.

Returns
the translational component of this pose

Definition at line 82 of file Pose6D.h.

◆ trans() [2/2]

const Vector3& octomath::Pose6D::trans ( ) const
inline

Translational component.

Returns
the translational component of this pose

Definition at line 94 of file Pose6D.h.

◆ transform()

Vector3 octomath::Pose6D::transform ( const Vector3 v) const

Transformation of a vector.

Transforms the vector v by the transformation which is specified by this.

Returns
the vector which is translated by the translation of this and afterwards rotated by the rotation of this.

Definition at line 85 of file Pose6D.cpp.

◆ transLength()

double octomath::Pose6D::transLength ( ) const

Translational length.

Returns
the translational (euclidian) length of the translation vector of this Pose6D

Definition at line 110 of file Pose6D.cpp.

◆ write()

std::ostream & octomath::Pose6D::write ( std::ostream &  s) const

Output operator.

Output to stream in a format which can be parsed using read().

Definition at line 131 of file Pose6D.cpp.

◆ writeBinary()

std::ostream & octomath::Pose6D::writeBinary ( std::ostream &  s) const

Binary output operator.

Output to stream in a binary format which can be parsed using readBinary().

Definition at line 146 of file Pose6D.cpp.

◆ x() [1/2]

float& octomath::Pose6D::x ( )
inline

Definition at line 102 of file Pose6D.h.

◆ x() [2/2]

const float& octomath::Pose6D::x ( ) const
inline

Definition at line 105 of file Pose6D.h.

◆ y() [1/2]

float& octomath::Pose6D::y ( )
inline

Definition at line 103 of file Pose6D.h.

◆ y() [2/2]

const float& octomath::Pose6D::y ( ) const
inline

Definition at line 106 of file Pose6D.h.

◆ yaw()

double octomath::Pose6D::yaw ( ) const
inline

Definition at line 111 of file Pose6D.h.

◆ z() [1/2]

float& octomath::Pose6D::z ( )
inline

Definition at line 104 of file Pose6D.h.

◆ z() [2/2]

const float& octomath::Pose6D::z ( ) const
inline

Definition at line 107 of file Pose6D.h.

Member Data Documentation

◆ rotation

Quaternion octomath::Pose6D::rotation
protected

Definition at line 198 of file Pose6D.h.

◆ translation

Vector3 octomath::Pose6D::translation
protected

Definition at line 197 of file Pose6D.h.


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


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Thu Mar 21 2024 02:40:30