Public Member Functions | Protected Member Functions | Protected Attributes
swri_transform_util::Transformer Class Reference

A base class for transformers. More...

#include <transformer.h>

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

List of all members.

Public Member Functions

virtual bool GetTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, Transform &transform)=0
 Get a swri_transform_util::Transform.
void Initialize (const boost::shared_ptr< tf::TransformListener > tf)
 Initialize the Transformer from a tf::TransformListener.
virtual std::map< std::string,
std::vector< std::string > > 
Supports () const =0
 Get a map of the transforms supported by this Transformer.
 Transformer ()
virtual ~Transformer ()

Protected Member Functions

virtual bool GetTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, tf::StampedTransform &transform) const
virtual bool Initialize ()

Protected Attributes

bool initialized_
boost::shared_ptr
< tf::TransformListener
tf_listener_

Detailed Description

A base class for transformers.

Instantiations of this class implement an interface to get transforms from certain types of frames (e.g. TF, WGS84) to other types of frames.

Definition at line 52 of file transformer.h.


Constructor & Destructor Documentation


Member Function Documentation

virtual bool swri_transform_util::Transformer::GetTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
Transform transform 
) [pure virtual]

Get a swri_transform_util::Transform.

Gets the swri_transform_util::Transform that transforms coordinates from the source_frame into the target_frame. If the transform is not available, return false.

Parameters:
[in]target_frameDestination frame for transform
[in]source_frameSource frame for transform
[in]timeTime that the transform is valid for. To get the most recent transform, use ros::Time(0)
[out]transformOutput container for the transform
Returns:
True if the transform was found, false if no transform between the specified frames is available for the specified time.

Implemented in swri_transform_util::UtmTransformer, and swri_transform_util::Wgs84Transformer.

virtual bool swri_transform_util::Transformer::GetTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
tf::StampedTransform transform 
) const [protected, virtual]

Initialize the Transformer from a tf::TransformListener.

Parameters:
tfA shared pointer to a tf::TransformListener that the Transformer wraps. It is recommended that every Transformer in a node use the same tf::TransformListener to reduce redundant computation.
virtual bool swri_transform_util::Transformer::Initialize ( ) [protected, virtual]
virtual std::map<std::string, std::vector<std::string> > swri_transform_util::Transformer::Supports ( ) const [pure virtual]

Get a map of the transforms supported by this Transformer.

Returns:
A map from source frame IDs to list of destination frame IDs. A source->destination entry does not imply that the inverse transform is supported as well.

Implemented in swri_transform_util::UtmTransformer, and swri_transform_util::Wgs84Transformer.


Member Data Documentation

Definition at line 98 of file transformer.h.

Definition at line 99 of file transformer.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