Instantiation of Transformer to handle transforms to/from UTM.
More...
#include <utm_transformer.h>
Instantiation of Transformer to handle transforms to/from UTM.
Definition at line 51 of file utm_transformer.h.
swri_transform_util::UtmTransformer::UtmTransformer |
( |
| ) |
|
virtual bool swri_transform_util::UtmTransformer::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.
- Parameters
-
[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 |
- Returns
- True if the transform was found, false if no transform between the specified frames is available for the specified time.
Implements swri_transform_util::Transformer.
virtual bool swri_transform_util::UtmTransformer::Initialize |
( |
| ) |
|
|
protectedvirtual |
virtual std::map<std::string, std::vector<std::string> > swri_transform_util::UtmTransformer::Supports |
( |
| ) |
const |
|
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.
Implements swri_transform_util::Transformer.
std::string swri_transform_util::UtmTransformer::local_xy_frame_ |
|
protected |
char swri_transform_util::UtmTransformer::utm_band_ |
|
protected |
int32_t swri_transform_util::UtmTransformer::utm_zone_ |
|
protected |
The documentation for this class was generated from the following file: