Public Member Functions | Private Attributes
transform_graph::Orientation Class Reference

Orientation provides conversions from common orientation types. More...

#include <orientation.h>

List of all members.

Public Member Functions

Eigen::Matrix3d matrix () const
 The rotation matrix represented by this orientation.
 Orientation ()
 Default constructor, identity rotation.
 Orientation (double w, double x, double y, double z)
 Quaternion constructor.
 Orientation (const Eigen::Matrix3d &m)
 Eigen rotation matrix constructor.
 Orientation (const Eigen::Quaterniond &q)
 Eigen::Quaterniond constructor.
 Orientation (const geometry_msgs::Quaternion &q)
 geometry_msgs quaternion constructor.
 Orientation (const tf::Quaternion &q)
 tf quaternion constructor.
 Orientation (const tf::Matrix3x3 &m)
 tf rotation matrix constructor.
Eigen::Quaterniond quaternion () const
 The quaternion representation of this orientation.
geometry_msgs::Quaternion quaternion_msg () const
 Returns the orientation as a geometry_msgs::Quaternion.
tf::Matrix3x3 tf_matrix () const
 Returns the orientation as a tf::Matrix3x3.
tf::Quaternion tf_quaternion () const
 Returns the orientation as a tf::Quaternion.

Private Attributes

Eigen::Matrix3d matrix_

Detailed Description

Orientation provides conversions from common orientation types.

By default, it is the identity orientation. This class provides a number of methods to convert back to common types.

Definition at line 14 of file orientation.h.


Constructor & Destructor Documentation

Default constructor, identity rotation.

Definition at line 10 of file orientation.cpp.

transform_graph::Orientation::Orientation ( double  w,
double  x,
double  y,
double  z 
)

Quaternion constructor.

Definition at line 15 of file orientation.cpp.

transform_graph::Orientation::Orientation ( const Eigen::Matrix3d &  m)

Eigen rotation matrix constructor.

Definition at line 20 of file orientation.cpp.

transform_graph::Orientation::Orientation ( const Eigen::Quaterniond &  q)

Eigen::Quaterniond constructor.

Definition at line 22 of file orientation.cpp.

transform_graph::Orientation::Orientation ( const geometry_msgs::Quaternion &  q)

geometry_msgs quaternion constructor.

Definition at line 26 of file orientation.cpp.

tf quaternion constructor.

Definition at line 31 of file orientation.cpp.

tf rotation matrix constructor.

Definition at line 36 of file orientation.cpp.


Member Function Documentation

Eigen::Matrix3d transform_graph::Orientation::matrix ( ) const

The rotation matrix represented by this orientation.

Returns:
The rotation matrix.

Definition at line 47 of file orientation.cpp.

Eigen::Quaterniond transform_graph::Orientation::quaternion ( ) const

The quaternion representation of this orientation.

Returns:
The quaternion.

Definition at line 49 of file orientation.cpp.

geometry_msgs::Quaternion transform_graph::Orientation::quaternion_msg ( ) const

Returns the orientation as a geometry_msgs::Quaternion.

Returns:
The orientation as a geometry_msgs::Quaternion.

Definition at line 53 of file orientation.cpp.

Returns the orientation as a tf::Matrix3x3.

Returns:
The orientation as a tf::Matrix3x3.

Definition at line 69 of file orientation.cpp.

Returns the orientation as a tf::Quaternion.

Returns:
The orientation as a tf::Quaternion.

Definition at line 63 of file orientation.cpp.


Member Data Documentation

Eigen::Matrix3d transform_graph::Orientation::matrix_ [private]

Definition at line 52 of file orientation.h.


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


transform_graph
Author(s):
autogenerated on Sat Jun 8 2019 19:23:43