Public Member Functions | Private Attributes
swri_transform_util::Transform Class Reference

An abstraction of the tf::Transform class to support transforms in addition to the rigid transforms supported by tf. More...

#include <transform.h>

List of all members.

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.
Transformoperator= (const tf::Transform transform)
 Assignment operator for tf::Transform.
Transformoperator= (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< TransformImpltransform_
 Pointer to the implementation of the transform.

Detailed Description

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.


Constructor & Destructor Documentation

Generates an identity transform.

swri_transform_util::Transform::Transform ( const tf::Transform transform) [explicit]

Generates a standard rigid transform from a tf::Transform.

Parameters:
[in]transformThe input transform.

Generates a standard rigid transform from a tf::Transform.

Parameters:
[in]transformThe input transform.
swri_transform_util::Transform::Transform ( boost::shared_ptr< TransformImpl transform) [explicit]

Defines the transform using an arbitrary transform implementation.

Parameters:
[in]transformThe input transform implementation.

Member Function Documentation

Get the orientation (rotation component) of the transform.

Returns:
The orientation (translation 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).

Returns:
The origin (translation component) of the transform

Get the time stamp of the transform.

Returns:
The time stamp of the transform

Definition at line 214 of file transform.h.

Return a TF transform equivalent to this transform.

Returns:
The equivalent tf::Transform

Return the inverse transform.

Returns:
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.

Parameters:
[in]vThe vector.
Returns:
The transformed vector.
tf::Vector3 swri_transform_util::Transform::operator* ( const tf::Vector3 v) const

Apply the transform to a vector and return the result.

Parameters:
[in]vThe vector.
Returns:
The transformed vector.
tf::Quaternion swri_transform_util::Transform::operator* ( const tf::Quaternion q) const

Apply the transform to a quaternion and return the result.

Parameters:
[in]qThe quaternion.
Returns:
The transformed 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.

Parameters:
[in]transformThe 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.

Parameters:
[in]transformThe input transform.

Member Data Documentation

Pointer to the implementation of the transform.

Definition at line 218 of file transform.h.


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


swri_transform_util
Author(s): Marc Alban
autogenerated on Tue Oct 3 2017 03:19:48