WGS 84 geodetic system for ROS latitude and longitude messages. More...
#include <limits>
#include <ctype.h>
#include <geographic_msgs/GeoPoint.h>
#include <geographic_msgs/GeoPose.h>
#include <sensor_msgs/NavSatFix.h>
#include <tf/tf.h>
Go to the source code of this file.
Namespaces | |
geodesy | |
Functions | |
template<class From , class To > | |
void | geodesy::convert (const From &from, To &to) |
template<class Same > | |
void | geodesy::convert (const Same &from, Same &to) |
static void | geodesy::fromMsg (const geographic_msgs::GeoPoint &from, geographic_msgs::GeoPoint &to) |
static void | geodesy::fromMsg (const geographic_msgs::GeoPose &from, geographic_msgs::GeoPose &to) |
static bool | geodesy::is2D (const geographic_msgs::GeoPoint &pt) |
static bool | geodesy::is2D (const geographic_msgs::GeoPose &pose) |
static bool | geodesy::isValid (const geographic_msgs::GeoPoint &pt) |
static bool | geodesy::isValid (const geographic_msgs::GeoPose &pose) |
static void | geodesy::normalize (geographic_msgs::GeoPoint &pt) |
static geographic_msgs::GeoPoint | geodesy::toMsg (double lat, double lon) |
static geographic_msgs::GeoPoint | geodesy::toMsg (double lat, double lon, double alt) |
static geographic_msgs::GeoPoint | geodesy::toMsg (const sensor_msgs::NavSatFix &fix) |
static geographic_msgs::GeoPoint | geodesy::toMsg (const geographic_msgs::GeoPoint &from) |
static geographic_msgs::GeoPose | geodesy::toMsg (const geographic_msgs::GeoPoint &pt, const geometry_msgs::Quaternion &q) |
static geographic_msgs::GeoPose | geodesy::toMsg (const sensor_msgs::NavSatFix &fix, const geometry_msgs::Quaternion &q) |
static geographic_msgs::GeoPose | geodesy::toMsg (const geographic_msgs::GeoPose &from) |
WGS 84 geodetic system for ROS latitude and longitude messages.
Standard ROS latitude and longitude coordinates are defined in terms of the World Geodetic System (WGS 84) ellipsoid used by most navigation satellite receivers.
Many other geodetic coordinate systems can be defined. They should always be converted to WGS 84 when publishing ROS messages to avoid confusion among subscribers.
Definition in file wgs84.h.