|
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) |
|
static geographic_msgs::GeoPoint | toMsg (const sensor_msgs::NavSatFix &fix) |
|
geographic_msgs::GeoPoint | toMsg (const UTMPoint &from) |
|
geographic_msgs::GeoPose | toMsg (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 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) |
|