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