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