An abstraction of the tf::Transform class to support transforms in addition to the rigid transforms supported by tf. More...
#include <transform.h>
Public Member Functions | |
tf::Quaternion | GetOrientation () const |
Get the orientation (rotation component) of the transform. | |
tf::Vector3 | GetOrigin () const |
Get the origin (translation component) of the transform. | |
ros::Time | GetStamp () |
Get the time stamp of the transform. | |
tf::Transform | GetTF () const |
Return a TF transform equivalent to this transform. | |
Transform | Inverse () const |
Return the inverse transform. | |
tf::Vector3 | operator() (const tf::Vector3 &v) const |
Apply the transform to a vector and return the result. | |
tf::Vector3 | operator* (const tf::Vector3 &v) const |
Apply the transform to a vector and return the result. | |
tf::Quaternion | operator* (const tf::Quaternion &q) const |
Apply the transform to a quaternion and return the result. | |
Transform & | operator= (const tf::Transform transform) |
Assignment operator for tf::Transform. | |
Transform & | operator= (boost::shared_ptr< TransformImpl > transform) |
Assignment operator for TransformImpl. | |
Transform () | |
Generates an identity transform. | |
Transform (const tf::Transform &transform) | |
Generates a standard rigid transform from a tf::Transform. | |
Transform (const tf::StampedTransform &transform) | |
Generates a standard rigid transform from a tf::Transform. | |
Transform (boost::shared_ptr< TransformImpl > transform) | |
Defines the transform using an arbitrary transform implementation. | |
Private Attributes | |
boost::shared_ptr< TransformImpl > | transform_ |
Pointer to the implementation of the transform. |
An abstraction of the tf::Transform class to support transforms in addition to the rigid transforms supported by tf.
Additional transforms are implemented through transformer plug-ins.
It can be used in conjunction with the tf::Vector3 data type.
Definition at line 105 of file transform.h.
Generates an identity transform.
swri_transform_util::Transform::Transform | ( | const tf::Transform & | transform | ) | [explicit] |
Generates a standard rigid transform from a tf::Transform.
[in] | transform | The input transform. |
swri_transform_util::Transform::Transform | ( | const tf::StampedTransform & | transform | ) | [explicit] |
Generates a standard rigid transform from a tf::Transform.
[in] | transform | The input transform. |
swri_transform_util::Transform::Transform | ( | boost::shared_ptr< TransformImpl > | transform | ) | [explicit] |
Defines the transform using an arbitrary transform implementation.
[in] | transform | The input transform implementation. |
Get the orientation (rotation component) of the transform.
Get the origin (translation component) of the transform.
The result of this should always be equal to applying the transform to the vector (0, 0, 0).
ros::Time swri_transform_util::Transform::GetStamp | ( | ) | [inline] |
Get the time stamp of the transform.
Definition at line 214 of file transform.h.
Return a TF transform equivalent to this transform.
Return the inverse transform.
tf::Vector3 swri_transform_util::Transform::operator() | ( | const tf::Vector3 & | v | ) | const |
Apply the transform to a vector and return the result.
[in] | v | The vector. |
tf::Vector3 swri_transform_util::Transform::operator* | ( | const tf::Vector3 & | v | ) | const |
Apply the transform to a vector and return the result.
[in] | v | The vector. |
tf::Quaternion swri_transform_util::Transform::operator* | ( | const tf::Quaternion & | q | ) | const |
Apply the transform to a quaternion and return the result.
[in] | q | The quaternion. |
Transform& swri_transform_util::Transform::operator= | ( | const tf::Transform | transform | ) |
Assignment operator for tf::Transform.
Generates a standard rigid transform from a tf::Transform.
[in] | transform | The input transform. |
Transform& swri_transform_util::Transform::operator= | ( | boost::shared_ptr< TransformImpl > | transform | ) |
Assignment operator for TransformImpl.
Note: The transform implementation is only a shallow copy.
[in] | transform | The input transform. |
boost::shared_ptr<TransformImpl> swri_transform_util::Transform::transform_ [private] |
Pointer to the implementation of the transform.
Definition at line 218 of file transform.h.