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) |
| void geodesy::convert | ( | const From & | from, |
| To & | to | ||
| ) |
| void geodesy::convert | ( | const Same & | from, |
| Same & | to | ||
| ) |
| static void geodesy::fromMsg | ( | const geographic_msgs::GeoPoint & | from, |
| geographic_msgs::GeoPoint & | to | ||
| ) | [inline, static] |
| static void geodesy::fromMsg | ( | const geographic_msgs::GeoPose & | from, |
| geographic_msgs::GeoPose & | to | ||
| ) | [inline, static] |
| void geodesy::fromMsg | ( | const geographic_msgs::GeoPoint & | from, |
| UTMPoint & | to | ||
| ) |
Convert WGS 84 geodetic point to UTM point.
Equations from USGS Bulletin 1532
| from | WGS 84 point message. |
| to | UTM 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.
| from | WGS 84 pose message. |
| to | UTM pose. |
Definition at line 295 of file utm_conversions.cpp.
| static bool geodesy::is2D | ( | const geographic_msgs::GeoPoint & | pt | ) | [inline, static] |
| static bool geodesy::is2D | ( | const geographic_msgs::GeoPose & | pose | ) | [inline, static] |
| static bool geodesy::is2D | ( | const UTMPoint & | pt | ) | [inline, static] |
| static bool geodesy::is2D | ( | const UTMPose & | pose | ) | [inline, static] |
| static bool geodesy::isValid | ( | const geographic_msgs::GeoPoint & | pt | ) | [inline, static] |
| static bool geodesy::isValid | ( | const geographic_msgs::GeoPose & | pose | ) | [inline, static] |
| bool geodesy::isValid | ( | const UTMPoint & | pt | ) |
Definition at line 265 of file utm_conversions.cpp.
| bool geodesy::isValid | ( | const UTMPose & | pose | ) |
Definition at line 302 of file utm_conversions.cpp.
| static void geodesy::normalize | ( | geographic_msgs::GeoPoint & | pt | ) | [inline, static] |
| static void geodesy::normalize | ( | UTMPoint & | pt | ) | [inline, static] |
| static std::ostream& geodesy::operator<< | ( | std::ostream & | out, |
| const UTMPoint & | pt | ||
| ) | [inline, static] |
| static std::ostream& geodesy::operator<< | ( | std::ostream & | out, |
| const UTMPose & | pose | ||
| ) | [inline, static] |
| static bool geodesy::sameGridZone | ( | const UTMPoint & | pt1, |
| const UTMPoint & | pt2 | ||
| ) | [inline, static] |
| static bool geodesy::sameGridZone | ( | const UTMPose & | pose1, |
| const UTMPose & | pose2 | ||
| ) | [inline, static] |
| static geometry_msgs::Point geodesy::toGeometry | ( | const UTMPoint & | from | ) | [inline, static] |
| static geometry_msgs::Pose geodesy::toGeometry | ( | const UTMPose & | from | ) | [inline, static] |
| static geographic_msgs::GeoPoint geodesy::toMsg | ( | double | lat, |
| double | lon | ||
| ) | [inline, static] |
| static geographic_msgs::GeoPoint geodesy::toMsg | ( | double | lat, |
| double | lon, | ||
| double | alt | ||
| ) | [inline, static] |
| geographic_msgs::GeoPoint geodesy::toMsg | ( | const UTMPoint & | from | ) |
Convert UTM point to WGS 84 geodetic point.
Equations from USGS Bulletin 1532
| from | WGS 84 point message. |
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] |
| static geographic_msgs::GeoPoint geodesy::toMsg | ( | const geographic_msgs::GeoPoint & | from | ) | [inline, static] |
| static geographic_msgs::GeoPose geodesy::toMsg | ( | const geographic_msgs::GeoPoint & | pt, |
| const geometry_msgs::Quaternion & | q | ||
| ) | [inline, static] |
| static geographic_msgs::GeoPose geodesy::toMsg | ( | const sensor_msgs::NavSatFix & | fix, |
| const geometry_msgs::Quaternion & | q | ||
| ) | [inline, static] |
| static geographic_msgs::GeoPose geodesy::toMsg | ( | const geographic_msgs::GeoPose & | from | ) | [inline, static] |
| 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).
Definition at line 82 of file utm_conversions.cpp.