Class TfToWgs84Transform

Inheritance Relationships

Base Types

Class Documentation

class TfToWgs84Transform : public swri_transform_util::TransformImpl, public swri_transform_util::StampedTransformStampInterface

Specialization of TransformImpl for transforming from TF to WGS84

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

Public Functions

TfToWgs84Transform(const geometry_msgs::msg::TransformStamped &transform, std::shared_ptr<LocalXyWgs84Util> local_xy_util)

Create a TfToWgs84Transform from a TF transform and local_xy_util

Parameters:
  • transform[in] The TF transform to use as the source frame. This transform should be the transform from the source frame to the local XY origin frame

  • local_xy_util – A local XY Utility object to transform from the local XY origin frame to WGS84 coordinates

virtual void Transform(const tf2::Vector3 &v_in, tf2::Vector3 &v_out) const override

Transform a 3D vector to latitude/longitude

The vector is first transformed with the transform into the local XY ortho-rectified frame. Then, the local_xy_util is used to convert to latitude/longitude.

Parameters:
  • v_in[in] Input vector in the ‘transform’ parent frame.

  • v_out[out] Output vector. x is the longitude in degrees, y is the latitude in degrees, and z is the altitude in meters.

virtual tf2::Quaternion GetOrientation() const override

Get the orientation of the transform.

This is calculated by transforming the reference angle of the local_xy_util using the transform. The result is the composition of those two rotations, which is the complete rotation from ENU frame to this frame.

Returns:

The orientation of the transform

virtual TransformImplPtr Inverse() const override

Protected Attributes

std::shared_ptr<LocalXyWgs84Util> local_xy_util_