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)
static void fromMsg (const geographic_msgs::GeoPose &from, geographic_msgs::GeoPose &to)
void fromMsg (const geographic_msgs::GeoPoint &from, UTMPoint &to)
void fromMsg (const geographic_msgs::GeoPose &from, UTMPose &to)
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 (double lat, double lon)
static geographic_msgs::GeoPoint toMsg (double lat, double lon, double alt)
geographic_msgs::GeoPoint toMsg (const UTMPoint &from)
geographic_msgs::GeoPose toMsg (const UTMPose &from)
static geographic_msgs::GeoPoint toMsg (const sensor_msgs::NavSatFix &fix)
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 sensor_msgs::NavSatFix &fix, const geometry_msgs::Quaternion &q)
static geographic_msgs::GeoPose toMsg (const geographic_msgs::GeoPose &from)
static char UTMBand (double Lat, double Lon)

Function Documentation

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 75 of file wgs84.h.

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

Convert any coordinate to itself.

Definition at line 82 of file wgs84.h.

static void geodesy::fromMsg ( const geographic_msgs::GeoPoint from,
geographic_msgs::GeoPoint to 
) [inline, static]

Convert one WGS 84 geodetic point to another.

Parameters:
fromWGS 84 point message.
toanother point.

Definition at line 93 of file wgs84.h.

static void geodesy::fromMsg ( const geographic_msgs::GeoPose from,
geographic_msgs::GeoPose to 
) [inline, static]

Convert one WGS 84 geodetic pose to another.

Parameters:
fromWGS 84 pose message.
toanother pose.

Definition at line 104 of file wgs84.h.

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

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.

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

Convert WGS 84 geodetic pose to UTM pose.

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

Definition at line 295 of file utm_conversions.cpp.

static bool geodesy::is2D ( const geographic_msgs::GeoPoint pt) [inline, static]
Returns:
true if no altitude specified.

Definition at line 111 of file wgs84.h.

static bool geodesy::is2D ( const geographic_msgs::GeoPose pose) [inline, static]
Returns:
true if pose has no altitude.

Definition at line 117 of file wgs84.h.

static bool geodesy::is2D ( const UTMPoint &  pt) [inline, static]
Returns:
true if no altitude specified.

Definition at line 185 of file utm.h.

static bool geodesy::is2D ( const UTMPose &  pose) [inline, static]
Returns:
true if no altitude specified.

Definition at line 192 of file utm.h.

static bool geodesy::isValid ( const geographic_msgs::GeoPoint pt) [inline, static]
Returns:
true if point is valid.

Definition at line 123 of file wgs84.h.

static bool geodesy::isValid ( const geographic_msgs::GeoPose pose) [inline, static]
Returns:
true if pose is valid.

Definition at line 135 of file wgs84.h.

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

Definition at line 265 of file utm_conversions.cpp.

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

Definition at line 302 of file utm_conversions.cpp.

static void geodesy::normalize ( geographic_msgs::GeoPoint pt) [inline, static]

Normalize a WGS 84 geodetic point.

Parameters:
ptpoint to normalize.

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

Definition at line 155 of file wgs84.h.

static void geodesy::normalize ( UTMPoint &  pt) [inline, static]

Normalize UTM point.

Ensures the point is within its canonical grid zone.

Definition at line 205 of file utm.h.

static std::ostream& geodesy::operator<< ( std::ostream &  out,
const UTMPoint &  pt 
) [inline, static]

Output stream operator for UTM point.

Definition at line 213 of file utm.h.

static std::ostream& geodesy::operator<< ( std::ostream &  out,
const UTMPose &  pose 
) [inline, static]

Output stream operator for UTM pose.

Definition at line 222 of file utm.h.

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

Definition at line 233 of file utm.h.

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

Definition at line 239 of file utm.h.

static geometry_msgs::Point geodesy::toGeometry ( const UTMPoint &  from) [inline, static]
Returns:
a geometry Point corresponding to a UTM point.

Definition at line 245 of file utm.h.

static geometry_msgs::Pose geodesy::toGeometry ( const UTMPose &  from) [inline, static]
Returns:
a geometry Pose corresponding to a UTM pose.

Definition at line 255 of file utm.h.

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

Definition at line 163 of file wgs84.h.

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

Definition at line 174 of file wgs84.h.

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

Convert UTM point to WGS 84 geodetic point.

Equations from USGS Bulletin 1532

Parameters:
fromWGS 84 point message.
Returns:
UTM point.

Definition at line 119 of file utm_conversions.cpp.

geographic_msgs::GeoPose geodesy::toMsg ( const UTMPose &  from)
static geographic_msgs::GeoPoint geodesy::toMsg ( const sensor_msgs::NavSatFix &  fix) [inline, static]
Returns:
a WGS 84 geodetic point message from a NavSatFix.

Definition at line 185 of file wgs84.h.

static geographic_msgs::GeoPoint geodesy::toMsg ( const geographic_msgs::GeoPoint from) [inline, static]
Returns:
a WGS 84 geodetic point message from another.

Definition at line 196 of file wgs84.h.

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

Definition at line 205 of file wgs84.h.

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

Definition at line 218 of file wgs84.h.

static geographic_msgs::GeoPose geodesy::toMsg ( const geographic_msgs::GeoPose from) [inline, static]
Returns:
a WGS 84 geodetic pose message from another.

Definition at line 229 of file wgs84.h.

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 Sat Dec 28 2013 17:02:37