Class LocalXyWgs84Util

Class Documentation

class LocalXyWgs84Util

Utility class for converting between WGS84 lat/lon and an ortho-rectified LocalXY coordinate system.

To use this class, first construct it with a reference origin. The reference origin should be a latitude, longitude, angle, and altitude in WGS84 coordinates. Once initialized, a LocalXyWgs84Util can be used to convert WGS84 coordinates to and from an ortho-rectified frame with its origin at the reference origin. Because the earth is spherical, the error in the ortho-rectified frame will accumulate as the distance from the reference origin increases. For this reason, the reference origin should be chosen to be close to the region of interest (<10 km).

It is strongly recommended to use 0 degrees for the angle. This corresponds to the X-axis of the ortho-rectified frame pointing east.

Public Functions

LocalXyWgs84Util(double reference_latitude, double reference_longitude, double reference_angle = 0, double reference_altitude = 0, rclcpp::Node::SharedPtr node = nullptr)

Initializing constructor

This constructor creates and initializes a LocalXyWgs84Util.

Parameters:
  • reference_latitude[in] Reference latitude in degrees.

  • reference_longitude[in] Reference longitude in degrees.

  • reference_angle[in] Reference angle in degrees ENU.

  • reference_altitude[in] Reference altitude in meters.

explicit LocalXyWgs84Util(rclcpp::Node::SharedPtr node)

Zero-argument constructor.

This constructor creates an uninitialized LocalXyWgs84Util. This constructor is only used to create placeholder objects in containers that require a zero-argument constructor.

inline bool Initialized() const

Return whether the object has been initialized

The object is not usable unless it has been initialized (see the two constructors).

Returns:

True if initialized, false otherwise.

void ResetInitialization()

Reset to “not Initialized”. Useful when the local_xy_origin changes and we want this class to be updated.

double ReferenceLongitude() const

Return the longitude coordinate of the local origin

Returns:

The WGS84 longitude coordinate of the local origin in degrees

double ReferenceLatitude() const

Return the latitude coordinate of the local origin

Returns:

The WGS84 latitude coordinate of the local origin in degrees

double ReferenceAngle() const

Return the reference angle in degrees ENU.

double ReferenceAltitude() const

Return the altitude coordinate of the local origin

Returns:

The WGS84 altitude coordinate of the local origin in meters

inline std::string Frame() const

Return the TF frame ID corresponding to the local origin

Returns:

The TF frame ID corresponding to the local origin

inline std::string NormalizedFrame() const

Return the TF frame ID corresponding to the local origin with a leading slash

Returns:

The TF frame ID corresponding to the local origin with a leading slash

bool ToLocalXy(double latitude, double longitude, double &x, double &y) const

Convert WGS84 latitude and longitude to LocalXY.

Parameters:
  • latitude[in] Latitude value in degrees.

  • longitude[in] Longitude value in degrees.

  • x[out] X coordinate in meters from origin.

  • y[out] Y coordinate in meters from origin.

Returns:

True if the conversion is possible.

bool ToWgs84(double x, double y, double &latitude, double &longitude) const

Convert LocalXY to WGS84 latitude and longitude.

Parameters:
  • x[in] X coordinate in meters from origin.

  • y[in] Y coordinate in meters from origin.

  • latitude[out] Latitude value in degrees.

  • longitude[out] Longitude value in degrees.

Returns:

True if the conversion is possible.

Protected Functions

void Initialize()
void HandleOrigin(double latitude, double longitude, double altitude, double angle, const std::string &frame_id)
void HandlePoseStamped(geometry_msgs::msg::PoseStamped::UniquePtr pose)

Protected Attributes

rclcpp::Node::SharedPtr node_
double reference_latitude_
double reference_longitude_
double reference_angle_
double reference_altitude_
double rho_lat_
double rho_lon_
double cos_angle_
double sin_angle_
std::string frame_
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr pose_sub_
bool initialized_