#include <wgs84_transformer.h>

Public Member Functions | |
| virtual bool | GetTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, Transform &transform) |
| Get a Transform from a non-UTM frame to UTM or vice-versa. | |
| virtual std::map< std::string, std::vector< std::string > > | Supports () const |
| Get a map of the transforms supported by this Transformer. | |
| Wgs84Transformer () | |
Protected Member Functions | |
| virtual bool | Initialize () |
Protected Attributes | |
| std::string | local_xy_frame_ |
Definition at line 50 of file wgs84_transformer.h.
| virtual bool swri_transform_util::Wgs84Transformer::GetTransform | ( | const std::string & | target_frame, |
| const std::string & | source_frame, | ||
| const ros::Time & | time, | ||
| Transform & | transform | ||
| ) | [virtual] |
Get a Transform from a non-UTM frame to UTM or vice-versa.
Gets the swri_transform_util::Transform that transforms coordinates from the source_frame into the target_frame. If the transform is not available (or not supported), 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 |
Implements swri_transform_util::Transformer.
| virtual bool swri_transform_util::Wgs84Transformer::Initialize | ( | ) | [protected, virtual] |
Reimplemented from swri_transform_util::Transformer.
| virtual std::map<std::string, std::vector<std::string> > swri_transform_util::Wgs84Transformer::Supports | ( | ) | const [virtual] |
Get a map of the transforms supported by this Transformer.
Implements swri_transform_util::Transformer.
std::string swri_transform_util::Wgs84Transformer::local_xy_frame_ [protected] |
Definition at line 87 of file wgs84_transformer.h.