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

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

#include <local_xy_util.h>

Public Member Functions

std::string Frame () const
 Return the TF frame ID corresponding to the local origin. More...
 
bool Initialized () const
 Return whether the object has been initialized. More...
 
 LocalXyWgs84Util (double reference_latitude, double reference_longitude, double reference_angle=0, double reference_altitude=0)
 Initializing constructor. More...
 
 LocalXyWgs84Util ()
 Zero-argument constructor. More...
 
std::string NormalizedFrame () const
 Return the TF frame ID corresponding to the local origin with a leading slash. More...
 
double ReferenceAltitude () const
 Return the altitude coordinate of the local origin. More...
 
double ReferenceAngle () const
 Return the reference angle in degrees ENU. More...
 
double ReferenceLatitude () const
 Return the latitude coordinate of the local origin. More...
 
double ReferenceLongitude () const
 Return the longitude coordinate of the local origin. More...
 
void ResetInitialization ()
 Reset to "not Initialized". More...
 
bool ToLocalXy (double latitude, double longitude, double &x, double &y) const
 Convert WGS84 latitude and longitude to LocalXY. More...
 
bool ToWgs84 (double x, double y, double &latitude, double &longitude) const
 Convert LocalXY to WGS84 latitude and longitude. More...
 

Protected Member Functions

void HandleOrigin (const topic_tools::ShapeShifter::ConstPtr origin)
 
void Initialize ()
 

Protected Attributes

double cos_angle_
 
std::string frame_
 
bool initialized_
 
ros::Subscriber origin_sub_
 
double reference_altitude_
 
double reference_angle_
 
double reference_latitude_
 
double reference_longitude_
 
double rho_lat_
 
double rho_lon_
 
double sin_angle_
 

Detailed Description

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.

Definition at line 100 of file local_xy_util.h.

Constructor & Destructor Documentation

swri_transform_util::LocalXyWgs84Util::LocalXyWgs84Util ( double  reference_latitude,
double  reference_longitude,
double  reference_angle = 0,
double  reference_altitude = 0 
)

Initializing constructor.

This constructor creates and initializes a LocalXyWgs84Util.

Parameters
[in]reference_latitudeReference latitude in degrees.
[in]reference_longitudeReference longitude in degrees.
[in]reference_angleReference angle in degrees ENU.
[in]reference_altitudeReference altitude in meters.
swri_transform_util::LocalXyWgs84Util::LocalXyWgs84Util ( )

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.

Member Function Documentation

std::string swri_transform_util::LocalXyWgs84Util::Frame ( ) const
inline

Return the TF frame ID corresponding to the local origin.

Returns
The TF frame ID corresponding to the local origin

Definition at line 175 of file local_xy_util.h.

void swri_transform_util::LocalXyWgs84Util::HandleOrigin ( const topic_tools::ShapeShifter::ConstPtr  origin)
protected
void swri_transform_util::LocalXyWgs84Util::Initialize ( )
protected
bool swri_transform_util::LocalXyWgs84Util::Initialized ( ) const
inline

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.

Definition at line 136 of file local_xy_util.h.

std::string swri_transform_util::LocalXyWgs84Util::NormalizedFrame ( ) const
inline

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

Definition at line 182 of file local_xy_util.h.

double swri_transform_util::LocalXyWgs84Util::ReferenceAltitude ( ) const

Return the altitude coordinate of the local origin.

Returns
The WGS84 altitude coordinate of the local origin in meters
double swri_transform_util::LocalXyWgs84Util::ReferenceAngle ( ) const

Return the reference angle in degrees ENU.

double swri_transform_util::LocalXyWgs84Util::ReferenceLatitude ( ) const

Return the latitude coordinate of the local origin.

Returns
The WGS84 latitude coordinate of the local origin in degrees
double swri_transform_util::LocalXyWgs84Util::ReferenceLongitude ( ) const

Return the longitude coordinate of the local origin.

Returns
The WGS84 longitude coordinate of the local origin in degrees
void swri_transform_util::LocalXyWgs84Util::ResetInitialization ( )

Reset to "not Initialized".

Useful when the local_xy_origin changes and we want this class to be updated.

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

Convert WGS84 latitude and longitude to LocalXY.

Parameters
[in]latitudeLatitude value in degrees.
[in]longitudeLongitude value in degrees.
[out]xX coordinate in meters from origin.
[out]yY coordinate in meters from origin.
Returns
True if the conversion is possible.
bool swri_transform_util::LocalXyWgs84Util::ToWgs84 ( double  x,
double  y,
double &  latitude,
double &  longitude 
) const

Convert LocalXY to WGS84 latitude and longitude.

Parameters
[in]xX coordinate in meters from origin.
[in]yY coordinate in meters from origin.
[out]latitudeLatitude value in degrees.
[out]longitudeLongitude value in degrees.
Returns
True if the conversion is possible.

Member Data Documentation

double swri_transform_util::LocalXyWgs84Util::cos_angle_
protected

Definition at line 224 of file local_xy_util.h.

std::string swri_transform_util::LocalXyWgs84Util::frame_
protected

Definition at line 227 of file local_xy_util.h.

bool swri_transform_util::LocalXyWgs84Util::initialized_
protected

Definition at line 230 of file local_xy_util.h.

ros::Subscriber swri_transform_util::LocalXyWgs84Util::origin_sub_
protected

Definition at line 229 of file local_xy_util.h.

double swri_transform_util::LocalXyWgs84Util::reference_altitude_
protected

Definition at line 220 of file local_xy_util.h.

double swri_transform_util::LocalXyWgs84Util::reference_angle_
protected

Definition at line 219 of file local_xy_util.h.

double swri_transform_util::LocalXyWgs84Util::reference_latitude_
protected

Definition at line 217 of file local_xy_util.h.

double swri_transform_util::LocalXyWgs84Util::reference_longitude_
protected

Definition at line 218 of file local_xy_util.h.

double swri_transform_util::LocalXyWgs84Util::rho_lat_
protected

Definition at line 222 of file local_xy_util.h.

double swri_transform_util::LocalXyWgs84Util::rho_lon_
protected

Definition at line 223 of file local_xy_util.h.

double swri_transform_util::LocalXyWgs84Util::sin_angle_
protected

Definition at line 225 of file local_xy_util.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