$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-gps_umd/doc_stacks/2013-03-01_15-36-48.211129/gps_umd/gps_common/msg/GPSFix.msg */ 00002 #ifndef GPS_COMMON_MESSAGE_GPSFIX_H 00003 #define GPS_COMMON_MESSAGE_GPSFIX_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 #include "gps_common/GPSStatus.h" 00019 00020 namespace gps_common 00021 { 00022 template <class ContainerAllocator> 00023 struct GPSFix_ { 00024 typedef GPSFix_<ContainerAllocator> Type; 00025 00026 GPSFix_() 00027 : header() 00028 , status() 00029 , latitude(0.0) 00030 , longitude(0.0) 00031 , altitude(0.0) 00032 , track(0.0) 00033 , speed(0.0) 00034 , climb(0.0) 00035 , pitch(0.0) 00036 , roll(0.0) 00037 , dip(0.0) 00038 , time(0.0) 00039 , gdop(0.0) 00040 , pdop(0.0) 00041 , hdop(0.0) 00042 , vdop(0.0) 00043 , tdop(0.0) 00044 , err(0.0) 00045 , err_horz(0.0) 00046 , err_vert(0.0) 00047 , err_track(0.0) 00048 , err_speed(0.0) 00049 , err_climb(0.0) 00050 , err_time(0.0) 00051 , err_pitch(0.0) 00052 , err_roll(0.0) 00053 , err_dip(0.0) 00054 , position_covariance() 00055 , position_covariance_type(0) 00056 { 00057 position_covariance.assign(0.0); 00058 } 00059 00060 GPSFix_(const ContainerAllocator& _alloc) 00061 : header(_alloc) 00062 , status(_alloc) 00063 , latitude(0.0) 00064 , longitude(0.0) 00065 , altitude(0.0) 00066 , track(0.0) 00067 , speed(0.0) 00068 , climb(0.0) 00069 , pitch(0.0) 00070 , roll(0.0) 00071 , dip(0.0) 00072 , time(0.0) 00073 , gdop(0.0) 00074 , pdop(0.0) 00075 , hdop(0.0) 00076 , vdop(0.0) 00077 , tdop(0.0) 00078 , err(0.0) 00079 , err_horz(0.0) 00080 , err_vert(0.0) 00081 , err_track(0.0) 00082 , err_speed(0.0) 00083 , err_climb(0.0) 00084 , err_time(0.0) 00085 , err_pitch(0.0) 00086 , err_roll(0.0) 00087 , err_dip(0.0) 00088 , position_covariance() 00089 , position_covariance_type(0) 00090 { 00091 position_covariance.assign(0.0); 00092 } 00093 00094 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00095 ::std_msgs::Header_<ContainerAllocator> header; 00096 00097 typedef ::gps_common::GPSStatus_<ContainerAllocator> _status_type; 00098 ::gps_common::GPSStatus_<ContainerAllocator> status; 00099 00100 typedef double _latitude_type; 00101 double latitude; 00102 00103 typedef double _longitude_type; 00104 double longitude; 00105 00106 typedef double _altitude_type; 00107 double altitude; 00108 00109 typedef double _track_type; 00110 double track; 00111 00112 typedef double _speed_type; 00113 double speed; 00114 00115 typedef double _climb_type; 00116 double climb; 00117 00118 typedef double _pitch_type; 00119 double pitch; 00120 00121 typedef double _roll_type; 00122 double roll; 00123 00124 typedef double _dip_type; 00125 double dip; 00126 00127 typedef double _time_type; 00128 double time; 00129 00130 typedef double _gdop_type; 00131 double gdop; 00132 00133 typedef double _pdop_type; 00134 double pdop; 00135 00136 typedef double _hdop_type; 00137 double hdop; 00138 00139 typedef double _vdop_type; 00140 double vdop; 00141 00142 typedef double _tdop_type; 00143 double tdop; 00144 00145 typedef double _err_type; 00146 double err; 00147 00148 typedef double _err_horz_type; 00149 double err_horz; 00150 00151 typedef double _err_vert_type; 00152 double err_vert; 00153 00154 typedef double _err_track_type; 00155 double err_track; 00156 00157 typedef double _err_speed_type; 00158 double err_speed; 00159 00160 typedef double _err_climb_type; 00161 double err_climb; 00162 00163 typedef double _err_time_type; 00164 double err_time; 00165 00166 typedef double _err_pitch_type; 00167 double err_pitch; 00168 00169 typedef double _err_roll_type; 00170 double err_roll; 00171 00172 typedef double _err_dip_type; 00173 double err_dip; 00174 00175 typedef boost::array<double, 9> _position_covariance_type; 00176 boost::array<double, 9> position_covariance; 00177 00178 typedef uint8_t _position_covariance_type_type; 00179 uint8_t position_covariance_type; 00180 00181 enum { COVARIANCE_TYPE_UNKNOWN = 0 }; 00182 enum { COVARIANCE_TYPE_APPROXIMATED = 1 }; 00183 enum { COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 }; 00184 enum { COVARIANCE_TYPE_KNOWN = 3 }; 00185 00186 ROS_DEPRECATED uint32_t get_position_covariance_size() const { return (uint32_t)position_covariance.size(); } 00187 private: 00188 static const char* __s_getDataType_() { return "gps_common/GPSFix"; } 00189 public: 00190 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00191 00192 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00193 00194 private: 00195 static const char* __s_getMD5Sum_() { return "3db3d0a7bc53054c67c528af84710b70"; } 00196 public: 00197 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00198 00199 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00200 00201 private: 00202 static const char* __s_getMessageDefinition_() { return "# A more complete GPS fix to supplement sensor_msgs/NavSatFix.\n\ 00203 Header header\n\ 00204 \n\ 00205 GPSStatus status\n\ 00206 \n\ 00207 # Latitude (degrees). Positive is north of equator; negative is south.\n\ 00208 float64 latitude\n\ 00209 \n\ 00210 # Longitude (degrees). Positive is east of prime meridian, negative west.\n\ 00211 float64 longitude\n\ 00212 \n\ 00213 # Altitude (meters). Positive is above reference (e.g., sea level).\n\ 00214 float64 altitude\n\ 00215 \n\ 00216 # Direction (degrees from north)\n\ 00217 float64 track\n\ 00218 \n\ 00219 # Ground speed (meters/second)\n\ 00220 float64 speed\n\ 00221 \n\ 00222 # Vertical speed (meters/second)\n\ 00223 float64 climb\n\ 00224 \n\ 00225 # Device orientation (units in degrees)\n\ 00226 float64 pitch\n\ 00227 float64 roll\n\ 00228 float64 dip\n\ 00229 \n\ 00230 # GPS time\n\ 00231 float64 time\n\ 00232 \n\ 00233 ## Dilution of precision; Xdop<=0 means the value is unknown\n\ 00234 \n\ 00235 # Total (positional-temporal) dilution of precision\n\ 00236 float64 gdop\n\ 00237 \n\ 00238 # Positional (3D) dilution of precision\n\ 00239 float64 pdop\n\ 00240 \n\ 00241 # Horizontal dilution of precision\n\ 00242 float64 hdop\n\ 00243 \n\ 00244 # Vertical dilution of precision\n\ 00245 float64 vdop\n\ 00246 \n\ 00247 # Temporal dilution of precision\n\ 00248 float64 tdop\n\ 00249 \n\ 00250 ## Uncertainty of measurement, 95% confidence\n\ 00251 \n\ 00252 # Spherical position uncertainty (meters) [epe]\n\ 00253 float64 err\n\ 00254 \n\ 00255 # Horizontal position uncertainty (meters) [eph]\n\ 00256 float64 err_horz\n\ 00257 \n\ 00258 # Vertical position uncertainty (meters) [epv]\n\ 00259 float64 err_vert\n\ 00260 \n\ 00261 # Track uncertainty (degrees) [epd]\n\ 00262 float64 err_track\n\ 00263 \n\ 00264 # Ground speed uncertainty (meters/second) [eps]\n\ 00265 float64 err_speed\n\ 00266 \n\ 00267 # Vertical speed uncertainty (meters/second) [epc]\n\ 00268 float64 err_climb\n\ 00269 \n\ 00270 # Temporal uncertainty [ept]\n\ 00271 float64 err_time\n\ 00272 \n\ 00273 # Orientation uncertainty (degrees)\n\ 00274 float64 err_pitch\n\ 00275 float64 err_roll\n\ 00276 float64 err_dip\n\ 00277 \n\ 00278 # Position covariance [m^2] defined relative to a tangential plane\n\ 00279 # through the reported position. The components are East, North, and\n\ 00280 # Up (ENU), in row-major order.\n\ 00281 \n\ 00282 float64[9] position_covariance\n\ 00283 \n\ 00284 uint8 COVARIANCE_TYPE_UNKNOWN = 0\n\ 00285 uint8 COVARIANCE_TYPE_APPROXIMATED = 1\n\ 00286 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\n\ 00287 uint8 COVARIANCE_TYPE_KNOWN = 3\n\ 00288 \n\ 00289 uint8 position_covariance_type\n\ 00290 \n\ 00291 \n\ 00292 ================================================================================\n\ 00293 MSG: std_msgs/Header\n\ 00294 # Standard metadata for higher-level stamped data types.\n\ 00295 # This is generally used to communicate timestamped data \n\ 00296 # in a particular coordinate frame.\n\ 00297 # \n\ 00298 # sequence ID: consecutively increasing ID \n\ 00299 uint32 seq\n\ 00300 #Two-integer timestamp that is expressed as:\n\ 00301 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00302 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00303 # time-handling sugar is provided by the client library\n\ 00304 time stamp\n\ 00305 #Frame this data is associated with\n\ 00306 # 0: no frame\n\ 00307 # 1: global frame\n\ 00308 string frame_id\n\ 00309 \n\ 00310 ================================================================================\n\ 00311 MSG: gps_common/GPSStatus\n\ 00312 Header header\n\ 00313 \n\ 00314 # Satellites used in solution\n\ 00315 uint16 satellites_used # Number of satellites\n\ 00316 int32[] satellite_used_prn # PRN identifiers\n\ 00317 \n\ 00318 # Satellites visible\n\ 00319 uint16 satellites_visible\n\ 00320 int32[] satellite_visible_prn # PRN identifiers\n\ 00321 int32[] satellite_visible_z # Elevation of satellites\n\ 00322 int32[] satellite_visible_azimuth # Azimuth of satellites\n\ 00323 int32[] satellite_visible_snr # Signal-to-noise ratios (dB)\n\ 00324 \n\ 00325 # Measurement status\n\ 00326 int16 STATUS_NO_FIX=-1 # Unable to fix position\n\ 00327 int16 STATUS_FIX=0 # Normal fix\n\ 00328 int16 STATUS_SBAS_FIX=1 # Fixed using a satellite-based augmentation system\n\ 00329 int16 STATUS_GBAS_FIX=2 # or a ground-based augmentation system\n\ 00330 int16 STATUS_DGPS_FIX=18 # Fixed with DGPS\n\ 00331 int16 STATUS_WAAS_FIX=33 # Fixed with WAAS\n\ 00332 int16 status\n\ 00333 \n\ 00334 uint16 SOURCE_NONE=0 # No information is available\n\ 00335 uint16 SOURCE_GPS=1 # Using standard GPS location [only valid for position_source]\n\ 00336 uint16 SOURCE_POINTS=2 # Motion/orientation fix is derived from successive points\n\ 00337 uint16 SOURCE_DOPPLER=4 # Motion is derived using the Doppler effect\n\ 00338 uint16 SOURCE_ALTIMETER=8 # Using an altimeter\n\ 00339 uint16 SOURCE_MAGNETIC=16 # Using magnetic sensors\n\ 00340 uint16 SOURCE_GYRO=32 # Using gyroscopes\n\ 00341 uint16 SOURCE_ACCEL=64 # Using accelerometers\n\ 00342 \n\ 00343 uint16 motion_source # Source for speed, climb and track\n\ 00344 uint16 orientation_source # Source for device orientation\n\ 00345 uint16 position_source # Source for position\n\ 00346 \n\ 00347 \n\ 00348 "; } 00349 public: 00350 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00351 00352 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00353 00354 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00355 { 00356 ros::serialization::OStream stream(write_ptr, 1000000000); 00357 ros::serialization::serialize(stream, header); 00358 ros::serialization::serialize(stream, status); 00359 ros::serialization::serialize(stream, latitude); 00360 ros::serialization::serialize(stream, longitude); 00361 ros::serialization::serialize(stream, altitude); 00362 ros::serialization::serialize(stream, track); 00363 ros::serialization::serialize(stream, speed); 00364 ros::serialization::serialize(stream, climb); 00365 ros::serialization::serialize(stream, pitch); 00366 ros::serialization::serialize(stream, roll); 00367 ros::serialization::serialize(stream, dip); 00368 ros::serialization::serialize(stream, time); 00369 ros::serialization::serialize(stream, gdop); 00370 ros::serialization::serialize(stream, pdop); 00371 ros::serialization::serialize(stream, hdop); 00372 ros::serialization::serialize(stream, vdop); 00373 ros::serialization::serialize(stream, tdop); 00374 ros::serialization::serialize(stream, err); 00375 ros::serialization::serialize(stream, err_horz); 00376 ros::serialization::serialize(stream, err_vert); 00377 ros::serialization::serialize(stream, err_track); 00378 ros::serialization::serialize(stream, err_speed); 00379 ros::serialization::serialize(stream, err_climb); 00380 ros::serialization::serialize(stream, err_time); 00381 ros::serialization::serialize(stream, err_pitch); 00382 ros::serialization::serialize(stream, err_roll); 00383 ros::serialization::serialize(stream, err_dip); 00384 ros::serialization::serialize(stream, position_covariance); 00385 ros::serialization::serialize(stream, position_covariance_type); 00386 return stream.getData(); 00387 } 00388 00389 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00390 { 00391 ros::serialization::IStream stream(read_ptr, 1000000000); 00392 ros::serialization::deserialize(stream, header); 00393 ros::serialization::deserialize(stream, status); 00394 ros::serialization::deserialize(stream, latitude); 00395 ros::serialization::deserialize(stream, longitude); 00396 ros::serialization::deserialize(stream, altitude); 00397 ros::serialization::deserialize(stream, track); 00398 ros::serialization::deserialize(stream, speed); 00399 ros::serialization::deserialize(stream, climb); 00400 ros::serialization::deserialize(stream, pitch); 00401 ros::serialization::deserialize(stream, roll); 00402 ros::serialization::deserialize(stream, dip); 00403 ros::serialization::deserialize(stream, time); 00404 ros::serialization::deserialize(stream, gdop); 00405 ros::serialization::deserialize(stream, pdop); 00406 ros::serialization::deserialize(stream, hdop); 00407 ros::serialization::deserialize(stream, vdop); 00408 ros::serialization::deserialize(stream, tdop); 00409 ros::serialization::deserialize(stream, err); 00410 ros::serialization::deserialize(stream, err_horz); 00411 ros::serialization::deserialize(stream, err_vert); 00412 ros::serialization::deserialize(stream, err_track); 00413 ros::serialization::deserialize(stream, err_speed); 00414 ros::serialization::deserialize(stream, err_climb); 00415 ros::serialization::deserialize(stream, err_time); 00416 ros::serialization::deserialize(stream, err_pitch); 00417 ros::serialization::deserialize(stream, err_roll); 00418 ros::serialization::deserialize(stream, err_dip); 00419 ros::serialization::deserialize(stream, position_covariance); 00420 ros::serialization::deserialize(stream, position_covariance_type); 00421 return stream.getData(); 00422 } 00423 00424 ROS_DEPRECATED virtual uint32_t serializationLength() const 00425 { 00426 uint32_t size = 0; 00427 size += ros::serialization::serializationLength(header); 00428 size += ros::serialization::serializationLength(status); 00429 size += ros::serialization::serializationLength(latitude); 00430 size += ros::serialization::serializationLength(longitude); 00431 size += ros::serialization::serializationLength(altitude); 00432 size += ros::serialization::serializationLength(track); 00433 size += ros::serialization::serializationLength(speed); 00434 size += ros::serialization::serializationLength(climb); 00435 size += ros::serialization::serializationLength(pitch); 00436 size += ros::serialization::serializationLength(roll); 00437 size += ros::serialization::serializationLength(dip); 00438 size += ros::serialization::serializationLength(time); 00439 size += ros::serialization::serializationLength(gdop); 00440 size += ros::serialization::serializationLength(pdop); 00441 size += ros::serialization::serializationLength(hdop); 00442 size += ros::serialization::serializationLength(vdop); 00443 size += ros::serialization::serializationLength(tdop); 00444 size += ros::serialization::serializationLength(err); 00445 size += ros::serialization::serializationLength(err_horz); 00446 size += ros::serialization::serializationLength(err_vert); 00447 size += ros::serialization::serializationLength(err_track); 00448 size += ros::serialization::serializationLength(err_speed); 00449 size += ros::serialization::serializationLength(err_climb); 00450 size += ros::serialization::serializationLength(err_time); 00451 size += ros::serialization::serializationLength(err_pitch); 00452 size += ros::serialization::serializationLength(err_roll); 00453 size += ros::serialization::serializationLength(err_dip); 00454 size += ros::serialization::serializationLength(position_covariance); 00455 size += ros::serialization::serializationLength(position_covariance_type); 00456 return size; 00457 } 00458 00459 typedef boost::shared_ptr< ::gps_common::GPSFix_<ContainerAllocator> > Ptr; 00460 typedef boost::shared_ptr< ::gps_common::GPSFix_<ContainerAllocator> const> ConstPtr; 00461 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00462 }; // struct GPSFix 00463 typedef ::gps_common::GPSFix_<std::allocator<void> > GPSFix; 00464 00465 typedef boost::shared_ptr< ::gps_common::GPSFix> GPSFixPtr; 00466 typedef boost::shared_ptr< ::gps_common::GPSFix const> GPSFixConstPtr; 00467 00468 00469 template<typename ContainerAllocator> 00470 std::ostream& operator<<(std::ostream& s, const ::gps_common::GPSFix_<ContainerAllocator> & v) 00471 { 00472 ros::message_operations::Printer< ::gps_common::GPSFix_<ContainerAllocator> >::stream(s, "", v); 00473 return s;} 00474 00475 } // namespace gps_common 00476 00477 namespace ros 00478 { 00479 namespace message_traits 00480 { 00481 template<class ContainerAllocator> struct IsMessage< ::gps_common::GPSFix_<ContainerAllocator> > : public TrueType {}; 00482 template<class ContainerAllocator> struct IsMessage< ::gps_common::GPSFix_<ContainerAllocator> const> : public TrueType {}; 00483 template<class ContainerAllocator> 00484 struct MD5Sum< ::gps_common::GPSFix_<ContainerAllocator> > { 00485 static const char* value() 00486 { 00487 return "3db3d0a7bc53054c67c528af84710b70"; 00488 } 00489 00490 static const char* value(const ::gps_common::GPSFix_<ContainerAllocator> &) { return value(); } 00491 static const uint64_t static_value1 = 0x3db3d0a7bc53054cULL; 00492 static const uint64_t static_value2 = 0x67c528af84710b70ULL; 00493 }; 00494 00495 template<class ContainerAllocator> 00496 struct DataType< ::gps_common::GPSFix_<ContainerAllocator> > { 00497 static const char* value() 00498 { 00499 return "gps_common/GPSFix"; 00500 } 00501 00502 static const char* value(const ::gps_common::GPSFix_<ContainerAllocator> &) { return value(); } 00503 }; 00504 00505 template<class ContainerAllocator> 00506 struct Definition< ::gps_common::GPSFix_<ContainerAllocator> > { 00507 static const char* value() 00508 { 00509 return "# A more complete GPS fix to supplement sensor_msgs/NavSatFix.\n\ 00510 Header header\n\ 00511 \n\ 00512 GPSStatus status\n\ 00513 \n\ 00514 # Latitude (degrees). Positive is north of equator; negative is south.\n\ 00515 float64 latitude\n\ 00516 \n\ 00517 # Longitude (degrees). Positive is east of prime meridian, negative west.\n\ 00518 float64 longitude\n\ 00519 \n\ 00520 # Altitude (meters). Positive is above reference (e.g., sea level).\n\ 00521 float64 altitude\n\ 00522 \n\ 00523 # Direction (degrees from north)\n\ 00524 float64 track\n\ 00525 \n\ 00526 # Ground speed (meters/second)\n\ 00527 float64 speed\n\ 00528 \n\ 00529 # Vertical speed (meters/second)\n\ 00530 float64 climb\n\ 00531 \n\ 00532 # Device orientation (units in degrees)\n\ 00533 float64 pitch\n\ 00534 float64 roll\n\ 00535 float64 dip\n\ 00536 \n\ 00537 # GPS time\n\ 00538 float64 time\n\ 00539 \n\ 00540 ## Dilution of precision; Xdop<=0 means the value is unknown\n\ 00541 \n\ 00542 # Total (positional-temporal) dilution of precision\n\ 00543 float64 gdop\n\ 00544 \n\ 00545 # Positional (3D) dilution of precision\n\ 00546 float64 pdop\n\ 00547 \n\ 00548 # Horizontal dilution of precision\n\ 00549 float64 hdop\n\ 00550 \n\ 00551 # Vertical dilution of precision\n\ 00552 float64 vdop\n\ 00553 \n\ 00554 # Temporal dilution of precision\n\ 00555 float64 tdop\n\ 00556 \n\ 00557 ## Uncertainty of measurement, 95% confidence\n\ 00558 \n\ 00559 # Spherical position uncertainty (meters) [epe]\n\ 00560 float64 err\n\ 00561 \n\ 00562 # Horizontal position uncertainty (meters) [eph]\n\ 00563 float64 err_horz\n\ 00564 \n\ 00565 # Vertical position uncertainty (meters) [epv]\n\ 00566 float64 err_vert\n\ 00567 \n\ 00568 # Track uncertainty (degrees) [epd]\n\ 00569 float64 err_track\n\ 00570 \n\ 00571 # Ground speed uncertainty (meters/second) [eps]\n\ 00572 float64 err_speed\n\ 00573 \n\ 00574 # Vertical speed uncertainty (meters/second) [epc]\n\ 00575 float64 err_climb\n\ 00576 \n\ 00577 # Temporal uncertainty [ept]\n\ 00578 float64 err_time\n\ 00579 \n\ 00580 # Orientation uncertainty (degrees)\n\ 00581 float64 err_pitch\n\ 00582 float64 err_roll\n\ 00583 float64 err_dip\n\ 00584 \n\ 00585 # Position covariance [m^2] defined relative to a tangential plane\n\ 00586 # through the reported position. The components are East, North, and\n\ 00587 # Up (ENU), in row-major order.\n\ 00588 \n\ 00589 float64[9] position_covariance\n\ 00590 \n\ 00591 uint8 COVARIANCE_TYPE_UNKNOWN = 0\n\ 00592 uint8 COVARIANCE_TYPE_APPROXIMATED = 1\n\ 00593 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\n\ 00594 uint8 COVARIANCE_TYPE_KNOWN = 3\n\ 00595 \n\ 00596 uint8 position_covariance_type\n\ 00597 \n\ 00598 \n\ 00599 ================================================================================\n\ 00600 MSG: std_msgs/Header\n\ 00601 # Standard metadata for higher-level stamped data types.\n\ 00602 # This is generally used to communicate timestamped data \n\ 00603 # in a particular coordinate frame.\n\ 00604 # \n\ 00605 # sequence ID: consecutively increasing ID \n\ 00606 uint32 seq\n\ 00607 #Two-integer timestamp that is expressed as:\n\ 00608 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00609 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00610 # time-handling sugar is provided by the client library\n\ 00611 time stamp\n\ 00612 #Frame this data is associated with\n\ 00613 # 0: no frame\n\ 00614 # 1: global frame\n\ 00615 string frame_id\n\ 00616 \n\ 00617 ================================================================================\n\ 00618 MSG: gps_common/GPSStatus\n\ 00619 Header header\n\ 00620 \n\ 00621 # Satellites used in solution\n\ 00622 uint16 satellites_used # Number of satellites\n\ 00623 int32[] satellite_used_prn # PRN identifiers\n\ 00624 \n\ 00625 # Satellites visible\n\ 00626 uint16 satellites_visible\n\ 00627 int32[] satellite_visible_prn # PRN identifiers\n\ 00628 int32[] satellite_visible_z # Elevation of satellites\n\ 00629 int32[] satellite_visible_azimuth # Azimuth of satellites\n\ 00630 int32[] satellite_visible_snr # Signal-to-noise ratios (dB)\n\ 00631 \n\ 00632 # Measurement status\n\ 00633 int16 STATUS_NO_FIX=-1 # Unable to fix position\n\ 00634 int16 STATUS_FIX=0 # Normal fix\n\ 00635 int16 STATUS_SBAS_FIX=1 # Fixed using a satellite-based augmentation system\n\ 00636 int16 STATUS_GBAS_FIX=2 # or a ground-based augmentation system\n\ 00637 int16 STATUS_DGPS_FIX=18 # Fixed with DGPS\n\ 00638 int16 STATUS_WAAS_FIX=33 # Fixed with WAAS\n\ 00639 int16 status\n\ 00640 \n\ 00641 uint16 SOURCE_NONE=0 # No information is available\n\ 00642 uint16 SOURCE_GPS=1 # Using standard GPS location [only valid for position_source]\n\ 00643 uint16 SOURCE_POINTS=2 # Motion/orientation fix is derived from successive points\n\ 00644 uint16 SOURCE_DOPPLER=4 # Motion is derived using the Doppler effect\n\ 00645 uint16 SOURCE_ALTIMETER=8 # Using an altimeter\n\ 00646 uint16 SOURCE_MAGNETIC=16 # Using magnetic sensors\n\ 00647 uint16 SOURCE_GYRO=32 # Using gyroscopes\n\ 00648 uint16 SOURCE_ACCEL=64 # Using accelerometers\n\ 00649 \n\ 00650 uint16 motion_source # Source for speed, climb and track\n\ 00651 uint16 orientation_source # Source for device orientation\n\ 00652 uint16 position_source # Source for position\n\ 00653 \n\ 00654 \n\ 00655 "; 00656 } 00657 00658 static const char* value(const ::gps_common::GPSFix_<ContainerAllocator> &) { return value(); } 00659 }; 00660 00661 template<class ContainerAllocator> struct HasHeader< ::gps_common::GPSFix_<ContainerAllocator> > : public TrueType {}; 00662 template<class ContainerAllocator> struct HasHeader< const ::gps_common::GPSFix_<ContainerAllocator> > : public TrueType {}; 00663 } // namespace message_traits 00664 } // namespace ros 00665 00666 namespace ros 00667 { 00668 namespace serialization 00669 { 00670 00671 template<class ContainerAllocator> struct Serializer< ::gps_common::GPSFix_<ContainerAllocator> > 00672 { 00673 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00674 { 00675 stream.next(m.header); 00676 stream.next(m.status); 00677 stream.next(m.latitude); 00678 stream.next(m.longitude); 00679 stream.next(m.altitude); 00680 stream.next(m.track); 00681 stream.next(m.speed); 00682 stream.next(m.climb); 00683 stream.next(m.pitch); 00684 stream.next(m.roll); 00685 stream.next(m.dip); 00686 stream.next(m.time); 00687 stream.next(m.gdop); 00688 stream.next(m.pdop); 00689 stream.next(m.hdop); 00690 stream.next(m.vdop); 00691 stream.next(m.tdop); 00692 stream.next(m.err); 00693 stream.next(m.err_horz); 00694 stream.next(m.err_vert); 00695 stream.next(m.err_track); 00696 stream.next(m.err_speed); 00697 stream.next(m.err_climb); 00698 stream.next(m.err_time); 00699 stream.next(m.err_pitch); 00700 stream.next(m.err_roll); 00701 stream.next(m.err_dip); 00702 stream.next(m.position_covariance); 00703 stream.next(m.position_covariance_type); 00704 } 00705 00706 ROS_DECLARE_ALLINONE_SERIALIZER; 00707 }; // struct GPSFix_ 00708 } // namespace serialization 00709 } // namespace ros 00710 00711 namespace ros 00712 { 00713 namespace message_operations 00714 { 00715 00716 template<class ContainerAllocator> 00717 struct Printer< ::gps_common::GPSFix_<ContainerAllocator> > 00718 { 00719 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::gps_common::GPSFix_<ContainerAllocator> & v) 00720 { 00721 s << indent << "header: "; 00722 s << std::endl; 00723 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00724 s << indent << "status: "; 00725 s << std::endl; 00726 Printer< ::gps_common::GPSStatus_<ContainerAllocator> >::stream(s, indent + " ", v.status); 00727 s << indent << "latitude: "; 00728 Printer<double>::stream(s, indent + " ", v.latitude); 00729 s << indent << "longitude: "; 00730 Printer<double>::stream(s, indent + " ", v.longitude); 00731 s << indent << "altitude: "; 00732 Printer<double>::stream(s, indent + " ", v.altitude); 00733 s << indent << "track: "; 00734 Printer<double>::stream(s, indent + " ", v.track); 00735 s << indent << "speed: "; 00736 Printer<double>::stream(s, indent + " ", v.speed); 00737 s << indent << "climb: "; 00738 Printer<double>::stream(s, indent + " ", v.climb); 00739 s << indent << "pitch: "; 00740 Printer<double>::stream(s, indent + " ", v.pitch); 00741 s << indent << "roll: "; 00742 Printer<double>::stream(s, indent + " ", v.roll); 00743 s << indent << "dip: "; 00744 Printer<double>::stream(s, indent + " ", v.dip); 00745 s << indent << "time: "; 00746 Printer<double>::stream(s, indent + " ", v.time); 00747 s << indent << "gdop: "; 00748 Printer<double>::stream(s, indent + " ", v.gdop); 00749 s << indent << "pdop: "; 00750 Printer<double>::stream(s, indent + " ", v.pdop); 00751 s << indent << "hdop: "; 00752 Printer<double>::stream(s, indent + " ", v.hdop); 00753 s << indent << "vdop: "; 00754 Printer<double>::stream(s, indent + " ", v.vdop); 00755 s << indent << "tdop: "; 00756 Printer<double>::stream(s, indent + " ", v.tdop); 00757 s << indent << "err: "; 00758 Printer<double>::stream(s, indent + " ", v.err); 00759 s << indent << "err_horz: "; 00760 Printer<double>::stream(s, indent + " ", v.err_horz); 00761 s << indent << "err_vert: "; 00762 Printer<double>::stream(s, indent + " ", v.err_vert); 00763 s << indent << "err_track: "; 00764 Printer<double>::stream(s, indent + " ", v.err_track); 00765 s << indent << "err_speed: "; 00766 Printer<double>::stream(s, indent + " ", v.err_speed); 00767 s << indent << "err_climb: "; 00768 Printer<double>::stream(s, indent + " ", v.err_climb); 00769 s << indent << "err_time: "; 00770 Printer<double>::stream(s, indent + " ", v.err_time); 00771 s << indent << "err_pitch: "; 00772 Printer<double>::stream(s, indent + " ", v.err_pitch); 00773 s << indent << "err_roll: "; 00774 Printer<double>::stream(s, indent + " ", v.err_roll); 00775 s << indent << "err_dip: "; 00776 Printer<double>::stream(s, indent + " ", v.err_dip); 00777 s << indent << "position_covariance[]" << std::endl; 00778 for (size_t i = 0; i < v.position_covariance.size(); ++i) 00779 { 00780 s << indent << " position_covariance[" << i << "]: "; 00781 Printer<double>::stream(s, indent + " ", v.position_covariance[i]); 00782 } 00783 s << indent << "position_covariance_type: "; 00784 Printer<uint8_t>::stream(s, indent + " ", v.position_covariance_type); 00785 } 00786 }; 00787 00788 00789 } // namespace message_operations 00790 } // namespace ros 00791 00792 #endif // GPS_COMMON_MESSAGE_GPSFIX_H 00793