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

Instantiation of Transformer to handle transforms to/from UTM. More...

#include <utm_transformer.h>

Inheritance diagram for swri_transform_util::UtmTransformer:
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)
 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.
 UtmTransformer ()

Protected Member Functions

virtual bool Initialize ()

Protected Attributes

std::string local_xy_frame_
char utm_band_
boost::shared_ptr< UtmUtilutm_util_
int32_t utm_zone_

Detailed Description

Instantiation of Transformer to handle transforms to/from UTM.

Definition at line 51 of file utm_transformer.h.


Constructor & Destructor Documentation


Member Function Documentation

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_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.

Implements swri_transform_util::Transformer.

virtual bool swri_transform_util::UtmTransformer::Initialize ( ) [protected, virtual]

Reimplemented from swri_transform_util::Transformer.

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.


Member Data Documentation

Definition at line 93 of file utm_transformer.h.

Definition at line 92 of file utm_transformer.h.

Definition at line 89 of file utm_transformer.h.

Definition at line 91 of file utm_transformer.h.


The documentation for this class was generated from the following file:


swri_transform_util
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 20:35:01