Class TfToUtmTransform

Inheritance Relationships

Base Types

Class Documentation

class TfToUtmTransform : public swri_transform_util::TransformImpl, public swri_transform_util::StampedTransformStampInterface

Class to implement transformation from TF to UTM

This class should not be used directly. It is used internally by swri_transform_util::Transform

Public Functions

TfToUtmTransform(const geometry_msgs::msg::TransformStamped &transform, std::shared_ptr<UtmUtil> utm_util, std::shared_ptr<LocalXyWgs84Util> local_xy_util, int32_t utm_zone, char utm_band)
virtual void Transform(const tf2::Vector3 &v_in, tf2::Vector3 &v_out) const

Apply this transform to a 3D vector

Parameters:
  • v_in[in] Input vector

  • v_out[out] Transformed vector

virtual tf2::Quaternion GetOrientation() const

Get the orientation of this transform

Get the orientation of this transform by getting the vector between the origin point and a point offset 1 on the x axis.

Returns:

The orientation component of the transform

virtual TransformImplPtr Inverse() const

Protected Attributes

std::shared_ptr<UtmUtil> utm_util_
std::shared_ptr<LocalXyWgs84Util> local_xy_util_
int32_t utm_zone_
char utm_band_