Transform describes a combination of a rotation and a translation. More...
#include <transform.h>
Public Member Functions | |
Eigen::Affine3d | affine () const |
Returns this transform as an affine transformation matrix. | |
transform_graph::Transform | inverse () const |
Returns the inverse of this transform. | |
Eigen::Matrix4d | matrix () const |
Returns this transform's homogeneous transform matrix. | |
transform_graph::Orientation | orientation () const |
Returns the orientation component of this transform. | |
geometry_msgs::Pose | pose () const |
Returns this transform as a geometry_msgs::Pose. | |
transform_graph::Position | position () const |
Returns the position component of this transform. | |
tf::Transform | tf_transform () const |
Returns this transform as a tf::Transform. | |
void | ToPose (geometry_msgs::Pose *pose) const |
Returns this transform as a geometry_msgs::Pose. | |
Transform () | |
Default, identity constructor. | |
Transform (const transform_graph::Position &position, const transform_graph::Orientation &orientation) | |
Transform (const tf::Transform &st) | |
Constructor from a tf Transform. | |
Transform (const geometry_msgs::Pose &p) | |
Constructor from a pose. | |
Transform (const geometry_msgs::Transform &p) | |
Constructor from a pose. | |
Transform (const Eigen::Affine3d &a) | |
Constructor from an Eigen Affine matrix. | |
Transform (const Eigen::Matrix4d &m) | |
Constructor from an Eigen matrix. | |
geometry_msgs::Transform | transform () const |
Returns this transform as a geometry_msgs::Pose. | |
Static Public Member Functions | |
static Transform | Identity () |
Private Attributes | |
Eigen::Affine3d | transform_ |
Transform describes a combination of a rotation and a translation.
By default it is the identity transform.
There are various methods for converting a Transform back into other common types, such as tf::Tranform, geometry_msgs::Pose, and Eigen::Affine3d.
Definition at line 20 of file transform.h.
Default, identity constructor.
Definition at line 17 of file transform.cpp.
transform_graph::Transform::Transform | ( | const transform_graph::Position & | position, |
const transform_graph::Orientation & | orientation | ||
) |
Constructor from other transform_graph types (or implicitly convertible types).
[in] | position | The position of this frame in the coordinate system of the reference frame. |
[in] | orientation | The orientation of this frame relative to the reference frame. |
Definition at line 19 of file transform.cpp.
transform_graph::Transform::Transform | ( | const tf::Transform & | st | ) |
Constructor from a tf Transform.
Definition at line 26 of file transform.cpp.
transform_graph::Transform::Transform | ( | const geometry_msgs::Pose & | p | ) |
Constructor from a pose.
transform_graph::Transform::Transform | ( | const geometry_msgs::Transform & | p | ) |
Constructor from a pose.
Definition at line 39 of file transform.cpp.
transform_graph::Transform::Transform | ( | const Eigen::Affine3d & | a | ) |
Constructor from an Eigen Affine matrix.
Definition at line 44 of file transform.cpp.
transform_graph::Transform::Transform | ( | const Eigen::Matrix4d & | m | ) |
Constructor from an Eigen matrix.
Definition at line 46 of file transform.cpp.
Eigen::Affine3d transform_graph::Transform::affine | ( | ) | const |
Returns this transform as an affine transformation matrix.
Definition at line 83 of file transform.cpp.
Transform transform_graph::Transform::Identity | ( | ) | [static] |
Definition at line 48 of file transform.cpp.
Transform transform_graph::Transform::inverse | ( | ) | const |
Returns the inverse of this transform.
Definition at line 96 of file transform.cpp.
Eigen::Matrix4d transform_graph::Transform::matrix | ( | ) | const |
Returns this transform's homogeneous transform matrix.
Definition at line 81 of file transform.cpp.
Returns the orientation component of this transform.
Definition at line 58 of file transform.cpp.
Returns this transform as a geometry_msgs::Pose.
Definition at line 69 of file transform.cpp.
Returns the position component of this transform.
Definition at line 53 of file transform.cpp.
Returns this transform as a tf::Transform.
Definition at line 63 of file transform.cpp.
void transform_graph::Transform::ToPose | ( | geometry_msgs::Pose * | pose | ) | const |
Returns this transform as a geometry_msgs::Pose.
Definition at line 85 of file transform.cpp.
geometry_msgs::Transform transform_graph::Transform::transform | ( | ) | const |
Returns this transform as a geometry_msgs::Pose.
Definition at line 75 of file transform.cpp.
Eigen::Affine3d transform_graph::Transform::transform_ [private] |
Definition at line 89 of file transform.h.