$search
00001 /* -*- mode: C++ -*- */ 00002 /* $Id: fb960a260c7cab4ceece860288539d1a5bbd2506 $ */ 00003 00004 /********************************************************************* 00005 * Software License Agreement (BSD License) 00006 * 00007 * Copyright (C) 2011 Jack O'Quin 00008 * All rights reserved. 00009 * 00010 * Redistribution and use in source and binary forms, with or without 00011 * modification, are permitted provided that the following conditions 00012 * are met: 00013 * 00014 * * Redistributions of source code must retain the above copyright 00015 * notice, this list of conditions and the following disclaimer. 00016 * * Redistributions in binary form must reproduce the above 00017 * copyright notice, this list of conditions and the following 00018 * disclaimer in the documentation and/or other materials provided 00019 * with the distribution. 00020 * * Neither the name of the author nor other contributors may be 00021 * used to endorse or promote products derived from this software 00022 * without specific prior written permission. 00023 * 00024 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00025 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00026 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00027 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00028 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00029 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00030 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00031 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00032 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00033 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00034 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00035 * POSSIBILITY OF SUCH DAMAGE. 00036 *********************************************************************/ 00037 00038 #ifndef _WGS84_H_ 00039 #define _WGS84_H_ 00040 00041 #include <limits> 00042 #include <ctype.h> 00043 #include <ros/ros.h> 00044 #include <geographic_msgs/GeoPoint.h> 00045 #include <geographic_msgs/GeoPose.h> 00046 #include <sensor_msgs/NavSatFix.h> 00047 #include <tf/tf.h> 00048 00064 namespace geodesy 00065 { 00074 template <class From, class To> 00075 void convert(const From &from, To &to) 00076 { 00077 fromMsg(toMsg(from), to); 00078 } 00079 00081 template <class Same> 00082 void convert(const Same &from, Same &to) 00083 { 00084 if (&from != &to) 00085 to = from; 00086 } 00087 00093 static inline void fromMsg(const geographic_msgs::GeoPoint &from, 00094 geographic_msgs::GeoPoint &to) 00095 { 00096 convert(from, to); 00097 } 00098 00104 static inline void fromMsg(const geographic_msgs::GeoPose &from, 00105 geographic_msgs::GeoPose &to) 00106 { 00107 convert(from, to); 00108 } 00109 00111 static inline bool is2D(const geographic_msgs::GeoPoint &pt) 00112 { 00113 return (pt.altitude != pt.altitude); 00114 } 00115 00117 static inline bool is2D(const geographic_msgs::GeoPose &pose) 00118 { 00119 return is2D(pose.position); 00120 } 00121 00123 static inline bool isValid(const geographic_msgs::GeoPoint &pt) 00124 { 00125 if (pt.latitude < -90.0 || pt.latitude > 90.0) 00126 return false; 00127 00128 if (pt.longitude < -180.0 || pt.longitude >= 180.0) 00129 return false; 00130 00131 return true; 00132 } 00133 00135 static inline bool isValid(const geographic_msgs::GeoPose &pose) 00136 { 00137 // check that orientation quaternion is normalized 00138 double len2 = (pose.orientation.x * pose.orientation.x 00139 + pose.orientation.y * pose.orientation.y 00140 + pose.orientation.z * pose.orientation.z 00141 + pose.orientation.w * pose.orientation.w); 00142 if (fabs(len2 - 1.0) > tf::QUATERNION_TOLERANCE) 00143 return false; 00144 00145 return isValid(pose.position); 00146 } 00147 00155 static inline void normalize(geographic_msgs::GeoPoint &pt) 00156 { 00157 pt.longitude = 00158 (fmod(fmod((pt.longitude + 180.0), 360.0) + 360.0, 360.0) - 180.0); 00159 pt.latitude = std::min(std::max(pt.latitude, -90.0), 90.0); 00160 } 00161 00163 static inline geographic_msgs::GeoPoint toMsg(double lat, double lon) 00164 { 00165 geographic_msgs::GeoPoint pt; 00166 pt.latitude = lat; 00167 pt.longitude = lon; 00168 pt.altitude = std::numeric_limits<double>::quiet_NaN(); 00169 return pt; 00170 } 00171 00173 static inline geographic_msgs::GeoPoint 00174 toMsg(double lat, double lon, double alt) 00175 { 00176 geographic_msgs::GeoPoint pt; 00177 pt.latitude = lat; 00178 pt.longitude = lon; 00179 pt.altitude = alt; 00180 return pt; 00181 } 00182 00184 static inline geographic_msgs::GeoPoint 00185 toMsg(const sensor_msgs::NavSatFix &fix) 00186 { 00187 geographic_msgs::GeoPoint pt; 00188 pt.latitude = fix.latitude; 00189 pt.longitude = fix.longitude; 00190 pt.altitude = fix.altitude; 00191 return pt; 00192 } 00193 00195 static inline geographic_msgs::GeoPoint 00196 toMsg(const geographic_msgs::GeoPoint &from) 00197 { 00198 return from; 00199 } 00200 00204 static inline geographic_msgs::GeoPose 00205 toMsg(const geographic_msgs::GeoPoint &pt, 00206 const geometry_msgs::Quaternion &q) 00207 { 00208 geographic_msgs::GeoPose pose; 00209 pose.position = pt; 00210 pose.orientation = q; 00211 return pose; 00212 } 00213 00217 static inline geographic_msgs::GeoPose 00218 toMsg(const sensor_msgs::NavSatFix &fix, 00219 const geometry_msgs::Quaternion &q) 00220 { 00221 geographic_msgs::GeoPose pose; 00222 pose.position = toMsg(fix); 00223 pose.orientation = q; 00224 return pose; 00225 } 00226 00228 static inline geographic_msgs::GeoPose 00229 toMsg(const geographic_msgs::GeoPose &from) 00230 { 00231 return from; 00232 } 00233 00234 }; // namespace geodesy 00235 00236 #endif // _WGS84_H_