Public Member Functions | Public Attributes | List of all members
swri_transform_util::TransformImpl Class Referenceabstract

Base class for Transform implementations. More...

#include <transform.h>

Inheritance diagram for swri_transform_util::TransformImpl:
Inheritance graph
[legend]

Public Member Functions

virtual tf::Quaternion GetOrientation () const
 Get the orientation of this transform. More...
 
virtual boost::shared_ptr< TransformImplInverse () const =0
 
virtual void Transform (const tf::Vector3 &v_in, tf::Vector3 &v_out) const =0
 Apply this transform to a 3D vector. More...
 
 TransformImpl ()
 
virtual ~TransformImpl ()
 

Public Attributes

ros::Time stamp_
 Time stamp for this transform. More...
 

Detailed Description

Base class for Transform implementations.

swri_transform_util::Transform uses a "pointer to implementation" design pattern. Extend this class to create new implementations of Transform. TransformImpl and its descendants should not be used bare, only as part of a swri_transform_util::Transform.

Definition at line 49 of file transform.h.

Constructor & Destructor Documentation

swri_transform_util::TransformImpl::TransformImpl ( )
inline

Definition at line 52 of file transform.h.

virtual swri_transform_util::TransformImpl::~TransformImpl ( )
inlinevirtual

Definition at line 53 of file transform.h.

Member Function Documentation

virtual tf::Quaternion swri_transform_util::TransformImpl::GetOrientation ( ) const
inlinevirtual

Get the orientation of this transform.

Get the orientation of this transform by getting the vector between the origin point and a point offset 1 on the x axis.

Returns
The orientation component of the transform

Reimplemented in swri_transform_util::TfTransform, swri_transform_util::Wgs84ToTfTransform, swri_transform_util::TfToUtmTransform, swri_transform_util::TfToWgs84Transform, and swri_transform_util::UtmToTfTransform.

Definition at line 71 of file transform.h.

virtual boost::shared_ptr<TransformImpl> swri_transform_util::TransformImpl::Inverse ( ) const
pure virtual
virtual void swri_transform_util::TransformImpl::Transform ( const tf::Vector3 v_in,
tf::Vector3 v_out 
) const
pure virtual

Member Data Documentation

ros::Time swri_transform_util::TransformImpl::stamp_

Time stamp for this transform.

Definition at line 93 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