Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
swri_transform_util::Wgs84Transformer Class Reference

#include <wgs84_transformer.h>

Inheritance diagram for swri_transform_util::Wgs84Transformer:
Inheritance graph
[legend]

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. More...
 
virtual std::map< std::string, std::vector< std::string > > Supports () const
 Get a map of the transforms supported by this Transformer. More...
 
 Wgs84Transformer ()
 
- Public Member Functions inherited from swri_transform_util::Transformer
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. More...
 
 Transformer ()
 
virtual ~Transformer ()
 

Protected Member Functions

virtual bool Initialize ()
 
- Protected Member Functions inherited from swri_transform_util::Transformer
virtual bool GetTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, tf::StampedTransform &transform) const
 

Protected Attributes

std::string local_xy_frame_
 
- Protected Attributes inherited from swri_transform_util::Transformer
bool initialized_
 
boost::shared_ptr< LocalXyWgs84Utillocal_xy_util_
 
boost::shared_ptr< tf::TransformListenertf_listener_
 

Detailed Description

Definition at line 50 of file wgs84_transformer.h.

Constructor & Destructor Documentation

swri_transform_util::Wgs84Transformer::Wgs84Transformer ( )

Member Function Documentation

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.

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::Wgs84Transformer::Initialize ( )
protectedvirtual

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.

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

std::string swri_transform_util::Wgs84Transformer::local_xy_frame_
protected

Definition at line 87 of file wgs84_transformer.h.


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


swri_transform_util
Author(s): Marc Alban
autogenerated on Tue Apr 6 2021 02:50:46