Public Member Functions | Private Attributes | List of all members
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>

Public Member Functions

tf::Quaternion GetOrientation () const
 Get the orientation (rotation component) of the transform. More...
 
tf::Vector3 GetOrigin () const
 Get the origin (translation component) of the transform. More...
 
ros::Time GetStamp ()
 Get the time stamp of the transform. More...
 
tf::Transform GetTF () const
 Return a TF transform equivalent to this transform. More...
 
Transform Inverse () const
 Return the inverse transform. More...
 
tf::Vector3 operator() (const tf::Vector3 &v) const
 Apply the transform to a vector and return the result. More...
 
tf::Vector3 operator* (const tf::Vector3 &v) const
 Apply the transform to a vector and return the result. More...
 
tf::Quaternion operator* (const tf::Quaternion &q) const
 Apply the transform to a quaternion and return the result. More...
 
Transformoperator= (const tf::Transform transform)
 Assignment operator for tf::Transform. More...
 
Transformoperator= (boost::shared_ptr< TransformImpl > transform)
 Assignment operator for TransformImpl. More...
 
 Transform ()
 Generates an identity transform. More...
 
 Transform (const tf::Transform &transform)
 Generates a standard rigid transform from a tf::Transform. More...
 
 Transform (const tf::StampedTransform &transform)
 Generates a standard rigid transform from a tf::Transform. More...
 
 Transform (boost::shared_ptr< TransformImpl > transform)
 Defines the transform using an arbitrary transform implementation. More...
 

Private Attributes

boost::shared_ptr< TransformImpltransform_
 Pointer to the implementation of the transform. More...
 

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

swri_transform_util::Transform::Transform ( )

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.
swri_transform_util::Transform::Transform ( const tf::StampedTransform transform)
explicit

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

tf::Quaternion swri_transform_util::Transform::GetOrientation ( ) const

Get the orientation (rotation component) of the transform.

Returns
The orientation (translation component) of the transform
tf::Vector3 swri_transform_util::Transform::GetOrigin ( ) const

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
ros::Time swri_transform_util::Transform::GetStamp ( )
inline

Get the time stamp of the transform.

Returns
The time stamp of the transform

Definition at line 214 of file transform.h.

tf::Transform swri_transform_util::Transform::GetTF ( ) const

Return a TF transform equivalent to this transform.

Returns
The equivalent tf::Transform
Transform swri_transform_util::Transform::Inverse ( ) const

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

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.


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


swri_transform_util
Author(s): Marc Alban
autogenerated on Tue Apr 6 2021 02:50:46