$search
00001 /* -*- mode: C++ -*- */ 00002 /* $Id: 8fdd0bc075d283abbd67dd0b4e584e47467fb244 $ */ 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 _UTM_H_ 00039 #define _UTM_H_ 00040 00041 #include <limits> 00042 #include <ctype.h> 00043 #include <iostream> 00044 #include <iomanip> 00045 00046 #include <ros/ros.h> 00047 #include <tf/tf.h> 00048 00049 #include <geodesy/wgs84.h> 00050 #include <geometry_msgs/Point.h> 00051 #include <geometry_msgs/Pose.h> 00052 00069 namespace geodesy 00070 { 00071 00083 class UTMPoint 00084 { 00085 public: 00086 00088 UTMPoint(): 00089 easting(0.0), 00090 northing(0.0), 00091 altitude(std::numeric_limits<double>::quiet_NaN()), 00092 zone(0), 00093 band(' ') 00094 {} 00095 00097 UTMPoint(const UTMPoint &that): 00098 easting(that.easting), 00099 northing(that.northing), 00100 altitude(that.altitude), 00101 zone(that.zone), 00102 band(that.band) 00103 {} 00104 00105 UTMPoint(const geographic_msgs::GeoPoint &pt); 00106 00108 UTMPoint(double _easting, double _northing, uint8_t _zone, char _band): 00109 easting(_easting), 00110 northing(_northing), 00111 altitude(std::numeric_limits<double>::quiet_NaN()), 00112 zone(_zone), 00113 band(_band) 00114 {} 00115 00117 UTMPoint(double _easting, double _northing, double _altitude, 00118 uint8_t _zone, char _band): 00119 easting(_easting), 00120 northing(_northing), 00121 altitude(_altitude), 00122 zone(_zone), 00123 band(_band) 00124 {} 00125 00126 // data members 00127 double easting; 00128 double northing; 00129 double altitude; 00130 uint8_t zone; 00131 char band; 00132 00133 }; // class UTMPoint 00134 00136 class UTMPose 00137 { 00138 public: 00139 00141 UTMPose(): 00142 position(), 00143 orientation() 00144 {} 00145 00147 UTMPose(const UTMPose &that): 00148 position(that.position), 00149 orientation(that.orientation) 00150 {} 00151 00153 UTMPose(const geographic_msgs::GeoPose &pose): 00154 position(pose.position), 00155 orientation(pose.orientation) 00156 {} 00157 00159 UTMPose(UTMPoint pt, 00160 const geometry_msgs::Quaternion &q): 00161 position(pt), 00162 orientation(q) 00163 {} 00164 00166 UTMPose(const geographic_msgs::GeoPoint &pt, 00167 const geometry_msgs::Quaternion &q): 00168 position(pt), 00169 orientation(q) 00170 {} 00171 00172 // data members 00173 UTMPoint position; 00174 geometry_msgs::Quaternion orientation; 00175 00176 }; // class UTMPose 00177 00178 // conversion function prototypes 00179 void fromMsg(const geographic_msgs::GeoPoint &from, UTMPoint &to); 00180 void fromMsg(const geographic_msgs::GeoPose &from, UTMPose &to); 00181 geographic_msgs::GeoPoint toMsg(const UTMPoint &from); 00182 geographic_msgs::GeoPose toMsg(const UTMPose &from); 00183 00185 static inline bool is2D(const UTMPoint &pt) 00186 { 00187 // true if altitude is a NaN 00188 return (pt.altitude != pt.altitude); 00189 } 00190 00192 static inline bool is2D(const UTMPose &pose) 00193 { 00194 // true if position has no altitude 00195 return is2D(pose.position); 00196 } 00197 00198 bool isValid(const UTMPoint &pt); 00199 bool isValid(const UTMPose &pose); 00200 00205 static inline void normalize(UTMPoint &pt) 00206 { 00207 geographic_msgs::GeoPoint ll(toMsg(pt)); 00208 normalize(ll); 00209 fromMsg(ll, pt); 00210 } 00211 00213 static inline std::ostream& operator<<(std::ostream& out, const UTMPoint &pt) 00214 { 00215 out << "(" << std::setprecision(10) << pt.easting << ", " 00216 << pt.northing << ", " << std::setprecision(6) << pt.altitude 00217 << " [" << (unsigned) pt.zone << pt.band << "])"; 00218 return out; 00219 } 00220 00222 static inline std::ostream& operator<<(std::ostream& out, const UTMPose &pose) 00223 { 00224 out << pose.position << ", ([" 00225 << pose.orientation.x << ", " 00226 << pose.orientation.y << ", " 00227 << pose.orientation.z << "], " 00228 << pose.orientation.w << ")"; 00229 return out; 00230 } 00231 00233 static inline bool sameGridZone(const UTMPoint &pt1, const UTMPoint &pt2) 00234 { 00235 return ((pt1.zone == pt2.zone) && (pt1.band == pt2.band)); 00236 } 00237 00239 static inline bool sameGridZone(const UTMPose &pose1, const UTMPose &pose2) 00240 { 00241 return sameGridZone(pose1.position, pose2.position); 00242 } 00243 00245 static inline geometry_msgs::Point toGeometry(const UTMPoint &from) 00246 { 00247 geometry_msgs::Point to; 00248 to.x = from.easting; 00249 to.y = from.northing; 00250 to.z = from.altitude; 00251 return to; 00252 } 00253 00255 static inline geometry_msgs::Pose toGeometry(const UTMPose &from) 00256 { 00257 geometry_msgs::Pose to; 00258 to.position = toGeometry(from.position); 00259 to.orientation = from.orientation; 00260 return to; 00261 } 00262 00263 }; // namespace geodesy 00264 00265 #endif // _UTM_H_