00001
00002 #ifndef ART_MSGS_MESSAGE_GPSINFO_H
00003 #define ART_MSGS_MESSAGE_GPSINFO_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "std_msgs/Header.h"
00014
00015 namespace art_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct GpsInfo_ : public ros::Message
00019 {
00020 typedef GpsInfo_<ContainerAllocator> Type;
00021
00022 GpsInfo_()
00023 : header()
00024 , latitude(0.0)
00025 , longitude(0.0)
00026 , altitude(0.0)
00027 , utm_e(0.0)
00028 , utm_n(0.0)
00029 , zone()
00030 , hdop(0.0)
00031 , vdop(0.0)
00032 , err_horz(0.0)
00033 , err_vert(0.0)
00034 , quality(0)
00035 , num_sats(0)
00036 {
00037 }
00038
00039 GpsInfo_(const ContainerAllocator& _alloc)
00040 : header(_alloc)
00041 , latitude(0.0)
00042 , longitude(0.0)
00043 , altitude(0.0)
00044 , utm_e(0.0)
00045 , utm_n(0.0)
00046 , zone(_alloc)
00047 , hdop(0.0)
00048 , vdop(0.0)
00049 , err_horz(0.0)
00050 , err_vert(0.0)
00051 , quality(0)
00052 , num_sats(0)
00053 {
00054 }
00055
00056 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00057 ::std_msgs::Header_<ContainerAllocator> header;
00058
00059 typedef double _latitude_type;
00060 double latitude;
00061
00062 typedef double _longitude_type;
00063 double longitude;
00064
00065 typedef double _altitude_type;
00066 double altitude;
00067
00068 typedef double _utm_e_type;
00069 double utm_e;
00070
00071 typedef double _utm_n_type;
00072 double utm_n;
00073
00074 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _zone_type;
00075 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > zone;
00076
00077 typedef double _hdop_type;
00078 double hdop;
00079
00080 typedef double _vdop_type;
00081 double vdop;
00082
00083 typedef double _err_horz_type;
00084 double err_horz;
00085
00086 typedef double _err_vert_type;
00087 double err_vert;
00088
00089 typedef uint16_t _quality_type;
00090 uint16_t quality;
00091
00092 typedef uint16_t _num_sats_type;
00093 uint16_t num_sats;
00094
00095 enum { INVALID_FIX = 0 };
00096 enum { GPS_FIX = 1 };
00097 enum { DGPS_FIX = 2 };
00098
00099 private:
00100 static const char* __s_getDataType_() { return "art_msgs/GpsInfo"; }
00101 public:
00102 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00103
00104 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00105
00106 private:
00107 static const char* __s_getMD5Sum_() { return "4f5e197f8744c1a11f1c94dc6e9a77a6"; }
00108 public:
00109 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00110
00111 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00112
00113 private:
00114 static const char* __s_getMessageDefinition_() { return "# GPS position message\n\
00115 #\n\
00116 # Probably to be replaced by a standard ROS message for Diamondback.\n\
00117 \n\
00118 # $Id: GpsInfo.msg 604 2010-09-22 15:50:16Z jack.oquin $\n\
00119 \n\
00120 # standard ROS header, includes time stamp\n\
00121 Header header\n\
00122 \n\
00123 # Latitude in degrees. Positive is north of equator, negative is\n\
00124 # south of equator.\n\
00125 float64 latitude\n\
00126 \n\
00127 # Longitude in degrees. Positive is east of prime meridian, negative\n\
00128 # is west of prime meridian.\n\
00129 float64 longitude\n\
00130 \n\
00131 # Altitude, in meters. Positive is above reference (e.g., sea-level),\n\
00132 # and negative is below.\n\
00133 float64 altitude\n\
00134 \n\
00135 # UTM WGS84 coordinates, easting [m]\n\
00136 float64 utm_e\n\
00137 \n\
00138 # UTM WGS84 coordinates, northing [m]\n\
00139 float64 utm_n\n\
00140 \n\
00141 # UTM zone\n\
00142 string zone\n\
00143 \n\
00144 # Horizontal dilution of position (HDOP)\n\
00145 float64 hdop\n\
00146 \n\
00147 # Vertical dilution of position (VDOP)\n\
00148 float64 vdop\n\
00149 \n\
00150 # Horizonal error [m]\n\
00151 float64 err_horz\n\
00152 \n\
00153 # Vertical error [m]\n\
00154 float64 err_vert\n\
00155 \n\
00156 # Quality of fix 0 = invalid, 1 = GPS fix, 2 = Differential GPS fix\n\
00157 uint16 INVALID_FIX = 0\n\
00158 uint16 GPS_FIX = 1\n\
00159 uint16 DGPS_FIX = 2\n\
00160 uint16 quality\n\
00161 \n\
00162 # Number of satellites in view.\n\
00163 uint16 num_sats\n\
00164 \n\
00165 ================================================================================\n\
00166 MSG: std_msgs/Header\n\
00167 # Standard metadata for higher-level stamped data types.\n\
00168 # This is generally used to communicate timestamped data \n\
00169 # in a particular coordinate frame.\n\
00170 # \n\
00171 # sequence ID: consecutively increasing ID \n\
00172 uint32 seq\n\
00173 #Two-integer timestamp that is expressed as:\n\
00174 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00175 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00176 # time-handling sugar is provided by the client library\n\
00177 time stamp\n\
00178 #Frame this data is associated with\n\
00179 # 0: no frame\n\
00180 # 1: global frame\n\
00181 string frame_id\n\
00182 \n\
00183 "; }
00184 public:
00185 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00186
00187 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00188
00189 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00190 {
00191 ros::serialization::OStream stream(write_ptr, 1000000000);
00192 ros::serialization::serialize(stream, header);
00193 ros::serialization::serialize(stream, latitude);
00194 ros::serialization::serialize(stream, longitude);
00195 ros::serialization::serialize(stream, altitude);
00196 ros::serialization::serialize(stream, utm_e);
00197 ros::serialization::serialize(stream, utm_n);
00198 ros::serialization::serialize(stream, zone);
00199 ros::serialization::serialize(stream, hdop);
00200 ros::serialization::serialize(stream, vdop);
00201 ros::serialization::serialize(stream, err_horz);
00202 ros::serialization::serialize(stream, err_vert);
00203 ros::serialization::serialize(stream, quality);
00204 ros::serialization::serialize(stream, num_sats);
00205 return stream.getData();
00206 }
00207
00208 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00209 {
00210 ros::serialization::IStream stream(read_ptr, 1000000000);
00211 ros::serialization::deserialize(stream, header);
00212 ros::serialization::deserialize(stream, latitude);
00213 ros::serialization::deserialize(stream, longitude);
00214 ros::serialization::deserialize(stream, altitude);
00215 ros::serialization::deserialize(stream, utm_e);
00216 ros::serialization::deserialize(stream, utm_n);
00217 ros::serialization::deserialize(stream, zone);
00218 ros::serialization::deserialize(stream, hdop);
00219 ros::serialization::deserialize(stream, vdop);
00220 ros::serialization::deserialize(stream, err_horz);
00221 ros::serialization::deserialize(stream, err_vert);
00222 ros::serialization::deserialize(stream, quality);
00223 ros::serialization::deserialize(stream, num_sats);
00224 return stream.getData();
00225 }
00226
00227 ROS_DEPRECATED virtual uint32_t serializationLength() const
00228 {
00229 uint32_t size = 0;
00230 size += ros::serialization::serializationLength(header);
00231 size += ros::serialization::serializationLength(latitude);
00232 size += ros::serialization::serializationLength(longitude);
00233 size += ros::serialization::serializationLength(altitude);
00234 size += ros::serialization::serializationLength(utm_e);
00235 size += ros::serialization::serializationLength(utm_n);
00236 size += ros::serialization::serializationLength(zone);
00237 size += ros::serialization::serializationLength(hdop);
00238 size += ros::serialization::serializationLength(vdop);
00239 size += ros::serialization::serializationLength(err_horz);
00240 size += ros::serialization::serializationLength(err_vert);
00241 size += ros::serialization::serializationLength(quality);
00242 size += ros::serialization::serializationLength(num_sats);
00243 return size;
00244 }
00245
00246 typedef boost::shared_ptr< ::art_msgs::GpsInfo_<ContainerAllocator> > Ptr;
00247 typedef boost::shared_ptr< ::art_msgs::GpsInfo_<ContainerAllocator> const> ConstPtr;
00248 };
00249 typedef ::art_msgs::GpsInfo_<std::allocator<void> > GpsInfo;
00250
00251 typedef boost::shared_ptr< ::art_msgs::GpsInfo> GpsInfoPtr;
00252 typedef boost::shared_ptr< ::art_msgs::GpsInfo const> GpsInfoConstPtr;
00253
00254
00255 template<typename ContainerAllocator>
00256 std::ostream& operator<<(std::ostream& s, const ::art_msgs::GpsInfo_<ContainerAllocator> & v)
00257 {
00258 ros::message_operations::Printer< ::art_msgs::GpsInfo_<ContainerAllocator> >::stream(s, "", v);
00259 return s;}
00260
00261 }
00262
00263 namespace ros
00264 {
00265 namespace message_traits
00266 {
00267 template<class ContainerAllocator>
00268 struct MD5Sum< ::art_msgs::GpsInfo_<ContainerAllocator> > {
00269 static const char* value()
00270 {
00271 return "4f5e197f8744c1a11f1c94dc6e9a77a6";
00272 }
00273
00274 static const char* value(const ::art_msgs::GpsInfo_<ContainerAllocator> &) { return value(); }
00275 static const uint64_t static_value1 = 0x4f5e197f8744c1a1ULL;
00276 static const uint64_t static_value2 = 0x1f1c94dc6e9a77a6ULL;
00277 };
00278
00279 template<class ContainerAllocator>
00280 struct DataType< ::art_msgs::GpsInfo_<ContainerAllocator> > {
00281 static const char* value()
00282 {
00283 return "art_msgs/GpsInfo";
00284 }
00285
00286 static const char* value(const ::art_msgs::GpsInfo_<ContainerAllocator> &) { return value(); }
00287 };
00288
00289 template<class ContainerAllocator>
00290 struct Definition< ::art_msgs::GpsInfo_<ContainerAllocator> > {
00291 static const char* value()
00292 {
00293 return "# GPS position message\n\
00294 #\n\
00295 # Probably to be replaced by a standard ROS message for Diamondback.\n\
00296 \n\
00297 # $Id: GpsInfo.msg 604 2010-09-22 15:50:16Z jack.oquin $\n\
00298 \n\
00299 # standard ROS header, includes time stamp\n\
00300 Header header\n\
00301 \n\
00302 # Latitude in degrees. Positive is north of equator, negative is\n\
00303 # south of equator.\n\
00304 float64 latitude\n\
00305 \n\
00306 # Longitude in degrees. Positive is east of prime meridian, negative\n\
00307 # is west of prime meridian.\n\
00308 float64 longitude\n\
00309 \n\
00310 # Altitude, in meters. Positive is above reference (e.g., sea-level),\n\
00311 # and negative is below.\n\
00312 float64 altitude\n\
00313 \n\
00314 # UTM WGS84 coordinates, easting [m]\n\
00315 float64 utm_e\n\
00316 \n\
00317 # UTM WGS84 coordinates, northing [m]\n\
00318 float64 utm_n\n\
00319 \n\
00320 # UTM zone\n\
00321 string zone\n\
00322 \n\
00323 # Horizontal dilution of position (HDOP)\n\
00324 float64 hdop\n\
00325 \n\
00326 # Vertical dilution of position (VDOP)\n\
00327 float64 vdop\n\
00328 \n\
00329 # Horizonal error [m]\n\
00330 float64 err_horz\n\
00331 \n\
00332 # Vertical error [m]\n\
00333 float64 err_vert\n\
00334 \n\
00335 # Quality of fix 0 = invalid, 1 = GPS fix, 2 = Differential GPS fix\n\
00336 uint16 INVALID_FIX = 0\n\
00337 uint16 GPS_FIX = 1\n\
00338 uint16 DGPS_FIX = 2\n\
00339 uint16 quality\n\
00340 \n\
00341 # Number of satellites in view.\n\
00342 uint16 num_sats\n\
00343 \n\
00344 ================================================================================\n\
00345 MSG: std_msgs/Header\n\
00346 # Standard metadata for higher-level stamped data types.\n\
00347 # This is generally used to communicate timestamped data \n\
00348 # in a particular coordinate frame.\n\
00349 # \n\
00350 # sequence ID: consecutively increasing ID \n\
00351 uint32 seq\n\
00352 #Two-integer timestamp that is expressed as:\n\
00353 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00354 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00355 # time-handling sugar is provided by the client library\n\
00356 time stamp\n\
00357 #Frame this data is associated with\n\
00358 # 0: no frame\n\
00359 # 1: global frame\n\
00360 string frame_id\n\
00361 \n\
00362 ";
00363 }
00364
00365 static const char* value(const ::art_msgs::GpsInfo_<ContainerAllocator> &) { return value(); }
00366 };
00367
00368 template<class ContainerAllocator> struct HasHeader< ::art_msgs::GpsInfo_<ContainerAllocator> > : public TrueType {};
00369 template<class ContainerAllocator> struct HasHeader< const ::art_msgs::GpsInfo_<ContainerAllocator> > : public TrueType {};
00370 }
00371 }
00372
00373 namespace ros
00374 {
00375 namespace serialization
00376 {
00377
00378 template<class ContainerAllocator> struct Serializer< ::art_msgs::GpsInfo_<ContainerAllocator> >
00379 {
00380 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00381 {
00382 stream.next(m.header);
00383 stream.next(m.latitude);
00384 stream.next(m.longitude);
00385 stream.next(m.altitude);
00386 stream.next(m.utm_e);
00387 stream.next(m.utm_n);
00388 stream.next(m.zone);
00389 stream.next(m.hdop);
00390 stream.next(m.vdop);
00391 stream.next(m.err_horz);
00392 stream.next(m.err_vert);
00393 stream.next(m.quality);
00394 stream.next(m.num_sats);
00395 }
00396
00397 ROS_DECLARE_ALLINONE_SERIALIZER;
00398 };
00399 }
00400 }
00401
00402 namespace ros
00403 {
00404 namespace message_operations
00405 {
00406
00407 template<class ContainerAllocator>
00408 struct Printer< ::art_msgs::GpsInfo_<ContainerAllocator> >
00409 {
00410 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::art_msgs::GpsInfo_<ContainerAllocator> & v)
00411 {
00412 s << indent << "header: ";
00413 s << std::endl;
00414 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00415 s << indent << "latitude: ";
00416 Printer<double>::stream(s, indent + " ", v.latitude);
00417 s << indent << "longitude: ";
00418 Printer<double>::stream(s, indent + " ", v.longitude);
00419 s << indent << "altitude: ";
00420 Printer<double>::stream(s, indent + " ", v.altitude);
00421 s << indent << "utm_e: ";
00422 Printer<double>::stream(s, indent + " ", v.utm_e);
00423 s << indent << "utm_n: ";
00424 Printer<double>::stream(s, indent + " ", v.utm_n);
00425 s << indent << "zone: ";
00426 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.zone);
00427 s << indent << "hdop: ";
00428 Printer<double>::stream(s, indent + " ", v.hdop);
00429 s << indent << "vdop: ";
00430 Printer<double>::stream(s, indent + " ", v.vdop);
00431 s << indent << "err_horz: ";
00432 Printer<double>::stream(s, indent + " ", v.err_horz);
00433 s << indent << "err_vert: ";
00434 Printer<double>::stream(s, indent + " ", v.err_vert);
00435 s << indent << "quality: ";
00436 Printer<uint16_t>::stream(s, indent + " ", v.quality);
00437 s << indent << "num_sats: ";
00438 Printer<uint16_t>::stream(s, indent + " ", v.num_sats);
00439 }
00440 };
00441
00442
00443 }
00444 }
00445
00446 #endif // ART_MSGS_MESSAGE_GPSINFO_H
00447