Universal Transverse Mercator coordinates. More...
#include <limits>
#include <ctype.h>
#include <iostream>
#include <iomanip>
#include <tf/tf.h>
#include <geodesy/wgs84.h>
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Pose.h>
Go to the source code of this file.
Classes | |
class | geodesy::UTMPoint |
class | geodesy::UTMPose |
Namespaces | |
geodesy | |
Functions | |
void | geodesy::fromMsg (const geographic_msgs::GeoPoint &from, UTMPoint &to) |
void | geodesy::fromMsg (const geographic_msgs::GeoPose &from, UTMPose &to) |
static bool | geodesy::is2D (const UTMPoint &pt) |
static bool | geodesy::is2D (const UTMPose &pose) |
bool | geodesy::isValid (const UTMPoint &pt) |
bool | geodesy::isValid (const UTMPose &pose) |
static void | geodesy::normalize (UTMPoint &pt) |
static std::ostream & | geodesy::operator<< (std::ostream &out, const UTMPoint &pt) |
static std::ostream & | geodesy::operator<< (std::ostream &out, const UTMPose &pose) |
static bool | geodesy::sameGridZone (const UTMPoint &pt1, const UTMPoint &pt2) |
static bool | geodesy::sameGridZone (const UTMPose &pose1, const UTMPose &pose2) |
static geometry_msgs::Point | geodesy::toGeometry (const UTMPoint &from) |
static geometry_msgs::Pose | geodesy::toGeometry (const UTMPose &from) |
geographic_msgs::GeoPoint | geodesy::toMsg (const UTMPoint &from) |
geographic_msgs::GeoPose | geodesy::toMsg (const UTMPose &from) |
Universal Transverse Mercator coordinates.
For outdoor robotics applications, Euclidean projections like UTM are easier to work with than latitude and longitude. This system is slightly more general than strict UTM. It is based on the Military Grid Reference System (MGRS), which can be extended to cover the poles, allowing well-defined transformations for every latitude and longitude.
Definition in file utm.h.