Class Wgs84ToTfTransform

Inheritance Relationships

Base Types

Class Documentation

class Wgs84ToTfTransform : public swri_transform_util::TransformImpl, public swri_transform_util::StampedTransformStampInterface

Specialization of TransformImpl for transforming from WGS84 to TF

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

Public Functions

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

Create a Wgs84ToTfTransform from a TF transform and local_xy_util

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

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

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

Transform a WGS84 triple to a 3D vector

The vector is first converted from latitude/longitude/altitude to the local XY ortho-rectified frame using the local_xy_util. Then, the transform is applied.

Parameters:
  • v_in[in] Input vector. x is the longitude in degrees, y is the latitude in degrees, and z is the altitude in meters.

  • v_out[out] Output vector in the ‘transform’ child frame.

virtual tf2::Quaternion GetOrientation() const override

Get the orientation of the transform.

This is calculated by transforming the inverse of 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 this frame to the ENU frame.

Returns:

The orientation of the transform

virtual TransformImplPtr Inverse() const override

Protected Attributes

std::shared_ptr<LocalXyWgs84Util> local_xy_util_