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

Wrapper around tf::TransformListener to support non-TF transforms. More...

#include <transform_manager.h>

List of all members.

Public Member Functions

bool GetTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, Transform &transform) const
 Get the Transform between two frames at a specified time.
bool GetTransform (const std::string &target_frame, const std::string &source_frame, Transform &transform) const
 Get the most recent Transform between two frames.
bool GetTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, tf::StampedTransform &transform) const
 Get the tf::Transform between two frames at a specified time.
bool GetTransform (const std::string &target_frame, const std::string &source_frame, tf::StampedTransform &transform) const
 Get the most recent tf::Transform between two frames.
void Initialize (boost::shared_ptr< tf::TransformListener > tf=boost::make_shared< tf::TransformListener >())
 Initialize the TransformManager with a tf::TransformListener.
bool SupportsTransform (const std::string &target_frame, const std::string &source_frame) const
 Check whether the TransformManager supports transforms from source_frame to target_frame.
 TransformManager ()
 ~TransformManager ()

Private Attributes

boost::shared_ptr
< LocalXyWgs84Util
local_xy_util_
boost::shared_ptr
< tf::TransformListener
tf_listener_
SourceTargetMap transformers_

Detailed Description

Wrapper around tf::TransformListener to support non-TF transforms.

TransformManager wraps tf::TransformListener and provides a similar interface to get Transforms between TF frames, UTM, and WGS84.

TransformManager uses PluginLib to load all of the swri_transform_util::Transformer plugins it can find. To extend the functionality of TranformManager, create a new swri_transform_util::Transformer plugin that implements the desired transform.

Definition at line 62 of file transform_manager.h.


Constructor & Destructor Documentation


Member Function Documentation

bool swri_transform_util::TransformManager::GetTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
Transform transform 
) const

Get the Transform between two frames at a specified time.

This function gets the transform from source_frame to target_frame at the specified time and returns it as a swri_transform_util::Transform.

The frame IDs for target_frame and source_frame can be either a frame id in the current TF tree or one of the special frames /UTM or /WGS84.

Parameters:
[in]target_frameThe TF (or special) frame id of the target
[in]source_frameThe TF (or special) frame id of the source
[in]timeThe requested time to request the transform. ros::Time(0) means the most recent time for which a valid transform is available.
[out]transformThe transform requested. If the function returns false, transform is not mutated.
Returns:
True if the transform is supported and available at the requested time. False otherwise.
bool swri_transform_util::TransformManager::GetTransform ( const std::string &  target_frame,
const std::string &  source_frame,
Transform transform 
) const

Get the most recent Transform between two frames.

This function gets the most recent transform from source_frame to target_frame and returns it as a swri_transform_util::Transform.

The frame IDs for target_frame and source_frame can be either a frame id in the current TF tree or one of the special frames /UTM or /WGS84.

Parameters:
[in]target_frameThe TF (or special) frame id of the target
[in]source_frameThe TF (or special) frame id of the source
[out]transformThe transform requested. If the function returns false, transform is not mutated
Returns:
True if the transform is supported and available. False otherwise.
bool swri_transform_util::TransformManager::GetTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
tf::StampedTransform transform 
) const

Get the tf::Transform between two frames at a specified time.

This function is a thin wrapper around the tf::TransformListener. Only TF frames are supported.

Parameters:
[in]target_frameThe TF frame id of the target
[in]source_frameThe TF frame id of the source
[in]timeThe requested time to request the transform. ros::Time(0) means the most recent time for which a valid transform is available.
[out]transformThe transform requested. If the function returns false, transform is not mutated.
Returns:
True if the transform is available at the requested time. False otherwise.
bool swri_transform_util::TransformManager::GetTransform ( const std::string &  target_frame,
const std::string &  source_frame,
tf::StampedTransform transform 
) const

Get the most recent tf::Transform between two frames.

This function is a thin wrapper around the tf::TransformListener. Only TF frames are supported.

Parameters:
[in]target_frameThe TF frame id of the target
[in]source_frameThe TF frame id of the source
[out]transformThe transform requested. If the function returns false, transform is not mutated.
Returns:
True if the transform is available. False otherwise.
void swri_transform_util::TransformManager::Initialize ( boost::shared_ptr< tf::TransformListener tf = boost::make_shared< tf::TransformListener >())

Initialize the TransformManager with a tf::TransformListener.

The TransformManager must be initialized before it can be used.

Parameters:
tfA shared pointer to a tf::TransformListener that the Transformer wraps.
bool swri_transform_util::TransformManager::SupportsTransform ( const std::string &  target_frame,
const std::string &  source_frame 
) const

Check whether the TransformManager supports transforms from source_frame to target_frame.

Supporting a transform does not imply that the TransformManager supports the inverse.

Parameters:
[in]target_frameThe TF (or special) frame id of the target
[in]source_frameThe TF (or special) frame id of the source
Returns:
True if the transform is supported. False if the transform is unsupported.

Member Data Documentation

Definition at line 182 of file transform_manager.h.

Definition at line 180 of file transform_manager.h.

Definition at line 184 of file transform_manager.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