A base class for transformers. More...
#include <transformer.h>
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, const boost::shared_ptr< LocalXyWgs84Util > xy_util=boost::shared_ptr< LocalXyWgs84Util >()) |
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 < LocalXyWgs84Util > | local_xy_util_ |
boost::shared_ptr < tf::TransformListener > | tf_listener_ |
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 53 of file transformer.h.
virtual swri_transform_util::Transformer::~Transformer | ( | ) | [virtual] |
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.
[in] | target_frame | Destination frame for transform |
[in] | source_frame | Source frame for transform |
[in] | time | Time that the transform is valid for. To get the most recent transform, use ros::Time(0) |
[out] | transform | Output container for the transform |
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] |
void swri_transform_util::Transformer::Initialize | ( | const boost::shared_ptr< tf::TransformListener > | tf, |
const boost::shared_ptr< LocalXyWgs84Util > | xy_util = boost::shared_ptr< LocalXyWgs84Util >() |
||
) |
Initialize the Transformer from a tf::TransformListener.
tf | A 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] |
Reimplemented in swri_transform_util::UtmTransformer, and swri_transform_util::Wgs84Transformer.
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.
Implemented in swri_transform_util::UtmTransformer, and swri_transform_util::Wgs84Transformer.
bool swri_transform_util::Transformer::initialized_ [protected] |
Definition at line 100 of file transformer.h.
boost::shared_ptr<LocalXyWgs84Util> swri_transform_util::Transformer::local_xy_util_ [protected] |
Definition at line 102 of file transformer.h.
boost::shared_ptr<tf::TransformListener> swri_transform_util::Transformer::tf_listener_ [protected] |
Definition at line 101 of file transformer.h.