Classes | Functions
geodesy Namespace Reference

Classes

class  UTMPoint
 
class  UTMPose
 

Functions

template<class From , class To >
void convert (const From &from, To &to)
 
template<class Same >
void convert (const Same &from, Same &to)
 
static void fromMsg (const geographic_msgs::GeoPoint &from, geographic_msgs::GeoPoint &to)
 
void fromMsg (const geographic_msgs::GeoPoint &from, UTMPoint &to, const bool &force_zone=false, const char &band='A', const uint8_t &zone=0)
 
static void fromMsg (const geographic_msgs::GeoPose &from, geographic_msgs::GeoPose &to)
 
void fromMsg (const geographic_msgs::GeoPose &from, UTMPose &to, const bool &force_zone=false, const char &band='A', const uint8_t &zone=0)
 
static bool is2D (const geographic_msgs::GeoPoint &pt)
 
static bool is2D (const geographic_msgs::GeoPose &pose)
 
static bool is2D (const UTMPoint &pt)
 
static bool is2D (const UTMPose &pose)
 
static bool isValid (const geographic_msgs::GeoPoint &pt)
 
static bool isValid (const geographic_msgs::GeoPose &pose)
 
bool isValid (const UTMPoint &pt)
 
bool isValid (const UTMPose &pose)
 
static void normalize (geographic_msgs::GeoPoint &pt)
 
static void normalize (UTMPoint &pt)
 
static std::ostream & operator<< (std::ostream &out, const UTMPoint &pt)
 
static std::ostream & operator<< (std::ostream &out, const UTMPose &pose)
 
static bool sameGridZone (const UTMPoint &pt1, const UTMPoint &pt2)
 
static bool sameGridZone (const UTMPose &pose1, const UTMPose &pose2)
 
static geometry_msgs::Point toGeometry (const UTMPoint &from)
 
static geometry_msgs::Pose toGeometry (const UTMPose &from)
 
static geographic_msgs::GeoPoint toMsg (const geographic_msgs::GeoPoint &from)
 
static geographic_msgs::GeoPose toMsg (const geographic_msgs::GeoPoint &pt, const geometry_msgs::Quaternion &q)
 
static geographic_msgs::GeoPose toMsg (const geographic_msgs::GeoPose &from)
 
static geographic_msgs::GeoPoint toMsg (const sensor_msgs::NavSatFix &fix)
 
static geographic_msgs::GeoPose toMsg (const sensor_msgs::NavSatFix &fix, const geometry_msgs::Quaternion &q)
 
geographic_msgs::GeoPoint toMsg (const UTMPoint &from)
 
geographic_msgs::GeoPose toMsg (const UTMPose &from)
 
static geographic_msgs::GeoPoint toMsg (double lat, double lon)
 
static geographic_msgs::GeoPoint toMsg (double lat, double lon, double alt)
 
static char UTMBand (double Lat, double Lon)
 

Function Documentation

◆ convert() [1/2]

template<class From , class To >
void geodesy::convert ( const From &  from,
To &  to 
)

Convert any coordinate to any other via intermediate WGS 84 representation.

Author
Tully Foote
Note
Every coordinate type must implement fromMsg() and toMsg() functions for both points and poses.

Definition at line 227 of file wgs84.h.

◆ convert() [2/2]

template<class Same >
void geodesy::convert ( const Same &  from,
Same &  to 
)

Convert any coordinate to itself.

Definition at line 233 of file wgs84.h.

◆ fromMsg() [1/4]

static void geodesy::fromMsg ( const geographic_msgs::GeoPoint &  from,
geographic_msgs::GeoPoint &  to 
)
inlinestatic

Convert one WGS 84 geodetic point to another.

Parameters
fromWGS 84 point message.
toanother point.

Definition at line 85 of file wgs84.h.

◆ fromMsg() [2/4]

void geodesy::fromMsg ( const geographic_msgs::GeoPoint &  from,
UTMPoint to,
const bool &  force_zone,
const char &  band,
const uint8_t &  zone 
)

Convert WGS 84 geodetic point to UTM point.

Equations from USGS Bulletin 1532

Parameters
fromWGS 84 point message.
toUTM point.

Definition at line 187 of file utm_conversions.cpp.

◆ fromMsg() [3/4]

static void geodesy::fromMsg ( const geographic_msgs::GeoPose &  from,
geographic_msgs::GeoPose &  to 
)
inlinestatic

Convert one WGS 84 geodetic pose to another.

Parameters
fromWGS 84 pose message.
toanother pose.

Definition at line 96 of file wgs84.h.

◆ fromMsg() [4/4]

void geodesy::fromMsg ( const geographic_msgs::GeoPose &  from,
UTMPose to,
const bool &  force_zone,
const char &  band,
const uint8_t &  zone 
)

Convert WGS 84 geodetic pose to UTM pose.

Parameters
fromWGS 84 pose message.
toUTM pose.
Todo:
define the orientation transformation properly

Definition at line 318 of file utm_conversions.cpp.

◆ is2D() [1/4]

static bool geodesy::is2D ( const geographic_msgs::GeoPoint &  pt)
inlinestatic
Returns
true if no altitude specified.

Definition at line 103 of file wgs84.h.

◆ is2D() [2/4]

static bool geodesy::is2D ( const geographic_msgs::GeoPose &  pose)
inlinestatic
Returns
true if pose has no altitude.

Definition at line 109 of file wgs84.h.

◆ is2D() [3/4]

static bool geodesy::is2D ( const UTMPoint pt)
inlinestatic
Returns
true if no altitude specified.

Definition at line 186 of file utm.h.

◆ is2D() [4/4]

static bool geodesy::is2D ( const UTMPose pose)
inlinestatic
Returns
true if no altitude specified.

Definition at line 193 of file utm.h.

◆ isValid() [1/4]

static bool geodesy::isValid ( const geographic_msgs::GeoPoint &  pt)
inlinestatic
Returns
true if point is valid.

Definition at line 115 of file wgs84.h.

◆ isValid() [2/4]

static bool geodesy::isValid ( const geographic_msgs::GeoPose &  pose)
inlinestatic
Returns
true if pose is valid.

Definition at line 127 of file wgs84.h.

◆ isValid() [3/4]

bool geodesy::isValid ( const UTMPoint pt)
Returns
true if point is valid.

Definition at line 275 of file utm_conversions.cpp.

◆ isValid() [4/4]

bool geodesy::isValid ( const UTMPose pose)
Returns
true if pose is valid.

Definition at line 326 of file utm_conversions.cpp.

◆ normalize() [1/2]

static void geodesy::normalize ( geographic_msgs::GeoPoint &  pt)
inlinestatic

Normalize a WGS 84 geodetic point.

Parameters
ptpoint to normalize.

Normalizes the longitude to [-180, 180). Clamps latitude to [-90, 90].

Definition at line 147 of file wgs84.h.

◆ normalize() [2/2]

static void geodesy::normalize ( UTMPoint pt)
inlinestatic

Normalize UTM point.

Ensures the point is within its canonical grid zone.

Definition at line 206 of file utm.h.

◆ operator<<() [1/2]

static std::ostream& geodesy::operator<< ( std::ostream &  out,
const UTMPoint pt 
)
inlinestatic

Output stream operator for UTM point.

Definition at line 214 of file utm.h.

◆ operator<<() [2/2]

static std::ostream& geodesy::operator<< ( std::ostream &  out,
const UTMPose pose 
)
inlinestatic

Output stream operator for UTM pose.

Definition at line 223 of file utm.h.

◆ sameGridZone() [1/2]

static bool geodesy::sameGridZone ( const UTMPoint pt1,
const UTMPoint pt2 
)
inlinestatic
Returns
true if two points have the same Grid Zone Designator

Definition at line 234 of file utm.h.

◆ sameGridZone() [2/2]

static bool geodesy::sameGridZone ( const UTMPose pose1,
const UTMPose pose2 
)
inlinestatic
Returns
true if two poses have the same Grid Zone Designator

Definition at line 240 of file utm.h.

◆ toGeometry() [1/2]

static geometry_msgs::Point geodesy::toGeometry ( const UTMPoint from)
inlinestatic
Returns
a geometry Point corresponding to a UTM point.

Definition at line 246 of file utm.h.

◆ toGeometry() [2/2]

static geometry_msgs::Pose geodesy::toGeometry ( const UTMPose from)
inlinestatic
Returns
a geometry Pose corresponding to a UTM pose.

Definition at line 256 of file utm.h.

◆ toMsg() [1/9]

static geographic_msgs::GeoPoint geodesy::toMsg ( const geographic_msgs::GeoPoint &  from)
inlinestatic
Returns
a WGS 84 geodetic point message from another.

Definition at line 188 of file wgs84.h.

◆ toMsg() [2/9]

static geographic_msgs::GeoPose geodesy::toMsg ( const geographic_msgs::GeoPoint &  pt,
const geometry_msgs::Quaternion &  q 
)
inlinestatic
Returns
a WGS 84 geodetic pose message from a point and a quaternion.

Definition at line 197 of file wgs84.h.

◆ toMsg() [3/9]

static geographic_msgs::GeoPose geodesy::toMsg ( const geographic_msgs::GeoPose &  from)
inlinestatic
Returns
a WGS 84 geodetic pose message from another.

Definition at line 221 of file wgs84.h.

◆ toMsg() [4/9]

static geographic_msgs::GeoPoint geodesy::toMsg ( const sensor_msgs::NavSatFix &  fix)
inlinestatic
Returns
a WGS 84 geodetic point message from a NavSatFix.

Definition at line 177 of file wgs84.h.

◆ toMsg() [5/9]

static geographic_msgs::GeoPose geodesy::toMsg ( const sensor_msgs::NavSatFix &  fix,
const geometry_msgs::Quaternion &  q 
)
inlinestatic
Returns
a WGS 84 geodetic pose message from a NavSatFix and a quaternion.

Definition at line 210 of file wgs84.h.

◆ toMsg() [6/9]

geographic_msgs::GeoPoint geodesy::toMsg ( const UTMPoint from)

Convert UTM point to WGS 84 geodetic point.

Equations from USGS Bulletin 1532

Parameters
fromUTM point.
Returns
WGS 84 point message.

Definition at line 119 of file utm_conversions.cpp.

◆ toMsg() [7/9]

geographic_msgs::GeoPose geodesy::toMsg ( const UTMPose from)

Convert UTM pose to WGS 84 geodetic pose.

Parameters
fromUTM pose.
Returns
WGS 84 pose message.

Definition at line 303 of file utm_conversions.cpp.

◆ toMsg() [8/9]

static geographic_msgs::GeoPoint geodesy::toMsg ( double  lat,
double  lon 
)
inlinestatic
Returns
a 2D WGS 84 geodetic point message.

Definition at line 155 of file wgs84.h.

◆ toMsg() [9/9]

static geographic_msgs::GeoPoint geodesy::toMsg ( double  lat,
double  lon,
double  alt 
)
inlinestatic
Returns
a 3D WGS 84 geodetic point message.

Definition at line 166 of file wgs84.h.

◆ UTMBand()

static char geodesy::UTMBand ( double  Lat,
double  Lon 
)
static

Determine the correct UTM band letter for the given latitude. (Does not currently handle polar (UPS) zones: A, B, Y, Z).

Returns
' ' if latitude is outside the UTM limits of +84 to -80

Definition at line 82 of file utm_conversions.cpp.



geodesy
Author(s): Jack O'Quin
autogenerated on Wed Mar 2 2022 00:19:31