43 #include <geographic_msgs/GeoPoint.h> 44 #include <geographic_msgs/GeoPose.h> 45 #include <sensor_msgs/NavSatFix.h> 73 template <
class From,
class To>
74 void convert(
const From &from, To &to);
78 void convert(
const Same &from, Same &to);
85 static inline void fromMsg(
const geographic_msgs::GeoPoint &from,
86 geographic_msgs::GeoPoint &to)
96 static inline void fromMsg(
const geographic_msgs::GeoPose &from,
97 geographic_msgs::GeoPose &to)
103 static inline bool is2D(
const geographic_msgs::GeoPoint &pt)
105 return (pt.altitude != pt.altitude);
109 static inline bool is2D(
const geographic_msgs::GeoPose &pose)
111 return is2D(pose.position);
115 static inline bool isValid(
const geographic_msgs::GeoPoint &pt)
117 if (pt.latitude < -90.0 || pt.latitude > 90.0)
120 if (pt.longitude < -180.0 || pt.longitude >= 180.0)
127 static inline bool isValid(
const geographic_msgs::GeoPose &pose)
130 double len2 = (pose.orientation.x * pose.orientation.x
131 + pose.orientation.y * pose.orientation.y
132 + pose.orientation.z * pose.orientation.z
133 + pose.orientation.w * pose.orientation.w);
147 static inline void normalize(geographic_msgs::GeoPoint &pt)
150 (fmod(fmod((pt.longitude + 180.0), 360.0) + 360.0, 360.0) - 180.0);
151 pt.latitude = std::min(std::max(pt.latitude, -90.0), 90.0);
155 static inline geographic_msgs::GeoPoint
toMsg(
double lat,
double lon)
157 geographic_msgs::GeoPoint pt;
160 pt.altitude = std::numeric_limits<double>::quiet_NaN();
165 static inline geographic_msgs::GeoPoint
166 toMsg(
double lat,
double lon,
double alt)
168 geographic_msgs::GeoPoint pt;
176 static inline geographic_msgs::GeoPoint
177 toMsg(
const sensor_msgs::NavSatFix &fix)
179 geographic_msgs::GeoPoint pt;
180 pt.latitude = fix.latitude;
181 pt.longitude = fix.longitude;
182 pt.altitude = fix.altitude;
187 static inline geographic_msgs::GeoPoint
188 toMsg(
const geographic_msgs::GeoPoint &from)
196 static inline geographic_msgs::GeoPose
197 toMsg(
const geographic_msgs::GeoPoint &pt,
198 const geometry_msgs::Quaternion &q)
200 geographic_msgs::GeoPose pose;
202 pose.orientation = q;
209 static inline geographic_msgs::GeoPose
210 toMsg(
const sensor_msgs::NavSatFix &fix,
211 const geometry_msgs::Quaternion &q)
213 geographic_msgs::GeoPose pose;
214 pose.position =
toMsg(fix);
215 pose.orientation = q;
220 static inline geographic_msgs::GeoPose
221 toMsg(
const geographic_msgs::GeoPose &from)
226 template <
class From,
class To>
232 template <
class Same>
static const double QUATERNION_TOLERANCE
void fromMsg(const geographic_msgs::GeoPoint &from, UTMPoint &to)
static bool is2D(const UTMPoint &pt)
static void normalize(UTMPoint &pt)
bool isValid(const UTMPoint &pt)
void convert(const From &from, To &to)
geographic_msgs::GeoPoint toMsg(const UTMPoint &from)