GPSFix.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-groovy-clearpath_common/doc_stacks/2014-10-05_22-49-25.060876/clearpath_common/clearpath_sensors/msg/GPSFix.msg */
00002 #ifndef CLEARPATH_SENSORS_MESSAGE_GPSFIX_H
00003 #define CLEARPATH_SENSORS_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 "clearpath_sensors/GPSStatus.h"
00019 
00020 namespace clearpath_sensors
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  ::clearpath_sensors::GPSStatus_<ContainerAllocator>  _status_type;
00098    ::clearpath_sensors::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   typedef boost::shared_ptr< ::clearpath_sensors::GPSFix_<ContainerAllocator> > Ptr;
00187   typedef boost::shared_ptr< ::clearpath_sensors::GPSFix_<ContainerAllocator>  const> ConstPtr;
00188   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00189 }; // struct GPSFix
00190 typedef  ::clearpath_sensors::GPSFix_<std::allocator<void> > GPSFix;
00191 
00192 typedef boost::shared_ptr< ::clearpath_sensors::GPSFix> GPSFixPtr;
00193 typedef boost::shared_ptr< ::clearpath_sensors::GPSFix const> GPSFixConstPtr;
00194 
00195 
00196 template<typename ContainerAllocator>
00197 std::ostream& operator<<(std::ostream& s, const  ::clearpath_sensors::GPSFix_<ContainerAllocator> & v)
00198 {
00199   ros::message_operations::Printer< ::clearpath_sensors::GPSFix_<ContainerAllocator> >::stream(s, "", v);
00200   return s;}
00201 
00202 } // namespace clearpath_sensors
00203 
00204 namespace ros
00205 {
00206 namespace message_traits
00207 {
00208 template<class ContainerAllocator> struct IsMessage< ::clearpath_sensors::GPSFix_<ContainerAllocator> > : public TrueType {};
00209 template<class ContainerAllocator> struct IsMessage< ::clearpath_sensors::GPSFix_<ContainerAllocator>  const> : public TrueType {};
00210 template<class ContainerAllocator>
00211 struct MD5Sum< ::clearpath_sensors::GPSFix_<ContainerAllocator> > {
00212   static const char* value() 
00213   {
00214     return "3db3d0a7bc53054c67c528af84710b70";
00215   }
00216 
00217   static const char* value(const  ::clearpath_sensors::GPSFix_<ContainerAllocator> &) { return value(); } 
00218   static const uint64_t static_value1 = 0x3db3d0a7bc53054cULL;
00219   static const uint64_t static_value2 = 0x67c528af84710b70ULL;
00220 };
00221 
00222 template<class ContainerAllocator>
00223 struct DataType< ::clearpath_sensors::GPSFix_<ContainerAllocator> > {
00224   static const char* value() 
00225   {
00226     return "clearpath_sensors/GPSFix";
00227   }
00228 
00229   static const char* value(const  ::clearpath_sensors::GPSFix_<ContainerAllocator> &) { return value(); } 
00230 };
00231 
00232 template<class ContainerAllocator>
00233 struct Definition< ::clearpath_sensors::GPSFix_<ContainerAllocator> > {
00234   static const char* value() 
00235   {
00236     return "# A more complete GPS fix to supplement sensor_msgs/NavSatFix.\n\
00237 Header header\n\
00238 \n\
00239 GPSStatus status\n\
00240 \n\
00241 # Latitude (degrees). Positive is north of equator; negative is south.\n\
00242 float64 latitude\n\
00243 \n\
00244 # Longitude (degrees). Positive is east of prime meridian, negative west.\n\
00245 float64 longitude\n\
00246 \n\
00247 # Altitude (meters). Positive is above reference (e.g., sea level).\n\
00248 float64 altitude\n\
00249 \n\
00250 # Direction (degrees from north)\n\
00251 float64 track\n\
00252 \n\
00253 # Ground speed (meters/second)\n\
00254 float64 speed\n\
00255 \n\
00256 # Vertical speed (meters/second)\n\
00257 float64 climb\n\
00258 \n\
00259 # Device orientation (units in degrees)\n\
00260 float64 pitch\n\
00261 float64 roll\n\
00262 float64 dip\n\
00263 \n\
00264 # GPS time\n\
00265 float64 time\n\
00266 \n\
00267 ## Dilution of precision; Xdop<=0 means the value is unknown\n\
00268 \n\
00269 # Total (positional-temporal) dilution of precision\n\
00270 float64 gdop\n\
00271 \n\
00272 # Positional (3D) dilution of precision\n\
00273 float64 pdop\n\
00274 \n\
00275 # Horizontal dilution of precision\n\
00276 float64 hdop\n\
00277 \n\
00278 # Vertical dilution of precision\n\
00279 float64 vdop\n\
00280 \n\
00281 # Temporal dilution of precision\n\
00282 float64 tdop\n\
00283 \n\
00284 ## Uncertainty of measurement, 95% confidence\n\
00285 \n\
00286 # Spherical position uncertainty (meters) [epe]\n\
00287 float64 err\n\
00288 \n\
00289 # Horizontal position uncertainty (meters) [eph]\n\
00290 float64 err_horz\n\
00291 \n\
00292 # Vertical position uncertainty (meters) [epv]\n\
00293 float64 err_vert\n\
00294 \n\
00295 # Track uncertainty (degrees) [epd]\n\
00296 float64 err_track\n\
00297 \n\
00298 # Ground speed uncertainty (meters/second) [eps]\n\
00299 float64 err_speed\n\
00300 \n\
00301 # Vertical speed uncertainty (meters/second) [epc]\n\
00302 float64 err_climb\n\
00303 \n\
00304 # Temporal uncertainty [ept]\n\
00305 float64 err_time\n\
00306 \n\
00307 # Orientation uncertainty (degrees)\n\
00308 float64 err_pitch\n\
00309 float64 err_roll\n\
00310 float64 err_dip\n\
00311 \n\
00312 # Position covariance [m^2] defined relative to a tangential plane\n\
00313 # through the reported position. The components are East, North, and\n\
00314 # Up (ENU), in row-major order.\n\
00315 \n\
00316 float64[9] position_covariance\n\
00317 \n\
00318 uint8 COVARIANCE_TYPE_UNKNOWN = 0\n\
00319 uint8 COVARIANCE_TYPE_APPROXIMATED = 1\n\
00320 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\n\
00321 uint8 COVARIANCE_TYPE_KNOWN = 3\n\
00322 \n\
00323 uint8 position_covariance_type\n\
00324 \n\
00325 \n\
00326 ================================================================================\n\
00327 MSG: std_msgs/Header\n\
00328 # Standard metadata for higher-level stamped data types.\n\
00329 # This is generally used to communicate timestamped data \n\
00330 # in a particular coordinate frame.\n\
00331 # \n\
00332 # sequence ID: consecutively increasing ID \n\
00333 uint32 seq\n\
00334 #Two-integer timestamp that is expressed as:\n\
00335 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00336 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00337 # time-handling sugar is provided by the client library\n\
00338 time stamp\n\
00339 #Frame this data is associated with\n\
00340 # 0: no frame\n\
00341 # 1: global frame\n\
00342 string frame_id\n\
00343 \n\
00344 ================================================================================\n\
00345 MSG: clearpath_sensors/GPSStatus\n\
00346 Header header\n\
00347 \n\
00348 # Satellites used in solution\n\
00349 uint16 satellites_used # Number of satellites\n\
00350 int32[] satellite_used_prn # PRN identifiers\n\
00351 \n\
00352 # Satellites visible\n\
00353 uint16 satellites_visible\n\
00354 int32[] satellite_visible_prn # PRN identifiers\n\
00355 int32[] satellite_visible_z # Elevation of satellites\n\
00356 int32[] satellite_visible_azimuth # Azimuth of satellites\n\
00357 int32[] satellite_visible_snr # Signal-to-noise ratios (dB)\n\
00358 \n\
00359 # Measurement status\n\
00360 int16 STATUS_NO_FIX=-1   # Unable to fix position\n\
00361 int16 STATUS_FIX=0       # Normal fix\n\
00362 int16 STATUS_SBAS_FIX=1  # Fixed using a satellite-based augmentation system\n\
00363 int16 STATUS_GBAS_FIX=2  #          or a ground-based augmentation system\n\
00364 int16 STATUS_DGPS_FIX=18 # Fixed with DGPS\n\
00365 int16 STATUS_WAAS_FIX=33 # Fixed with WAAS\n\
00366 int16 status\n\
00367 \n\
00368 uint16 SOURCE_NONE=0 # No information is available\n\
00369 uint16 SOURCE_GPS=1 # Using standard GPS location [only valid for position_source]\n\
00370 uint16 SOURCE_POINTS=2 # Motion/orientation fix is derived from successive points\n\
00371 uint16 SOURCE_DOPPLER=4 # Motion is derived using the Doppler effect\n\
00372 uint16 SOURCE_ALTIMETER=8 # Using an altimeter\n\
00373 uint16 SOURCE_MAGNETIC=16 # Using magnetic sensors\n\
00374 uint16 SOURCE_GYRO=32 # Using gyroscopes\n\
00375 uint16 SOURCE_ACCEL=64 # Using accelerometers\n\
00376 \n\
00377 uint16 motion_source # Source for speed, climb and track\n\
00378 uint16 orientation_source # Source for device orientation\n\
00379 uint16 position_source # Source for position\n\
00380 \n\
00381 \n\
00382 ";
00383   }
00384 
00385   static const char* value(const  ::clearpath_sensors::GPSFix_<ContainerAllocator> &) { return value(); } 
00386 };
00387 
00388 template<class ContainerAllocator> struct HasHeader< ::clearpath_sensors::GPSFix_<ContainerAllocator> > : public TrueType {};
00389 template<class ContainerAllocator> struct HasHeader< const ::clearpath_sensors::GPSFix_<ContainerAllocator> > : public TrueType {};
00390 } // namespace message_traits
00391 } // namespace ros
00392 
00393 namespace ros
00394 {
00395 namespace serialization
00396 {
00397 
00398 template<class ContainerAllocator> struct Serializer< ::clearpath_sensors::GPSFix_<ContainerAllocator> >
00399 {
00400   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00401   {
00402     stream.next(m.header);
00403     stream.next(m.status);
00404     stream.next(m.latitude);
00405     stream.next(m.longitude);
00406     stream.next(m.altitude);
00407     stream.next(m.track);
00408     stream.next(m.speed);
00409     stream.next(m.climb);
00410     stream.next(m.pitch);
00411     stream.next(m.roll);
00412     stream.next(m.dip);
00413     stream.next(m.time);
00414     stream.next(m.gdop);
00415     stream.next(m.pdop);
00416     stream.next(m.hdop);
00417     stream.next(m.vdop);
00418     stream.next(m.tdop);
00419     stream.next(m.err);
00420     stream.next(m.err_horz);
00421     stream.next(m.err_vert);
00422     stream.next(m.err_track);
00423     stream.next(m.err_speed);
00424     stream.next(m.err_climb);
00425     stream.next(m.err_time);
00426     stream.next(m.err_pitch);
00427     stream.next(m.err_roll);
00428     stream.next(m.err_dip);
00429     stream.next(m.position_covariance);
00430     stream.next(m.position_covariance_type);
00431   }
00432 
00433   ROS_DECLARE_ALLINONE_SERIALIZER;
00434 }; // struct GPSFix_
00435 } // namespace serialization
00436 } // namespace ros
00437 
00438 namespace ros
00439 {
00440 namespace message_operations
00441 {
00442 
00443 template<class ContainerAllocator>
00444 struct Printer< ::clearpath_sensors::GPSFix_<ContainerAllocator> >
00445 {
00446   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::clearpath_sensors::GPSFix_<ContainerAllocator> & v) 
00447   {
00448     s << indent << "header: ";
00449 s << std::endl;
00450     Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + "  ", v.header);
00451     s << indent << "status: ";
00452 s << std::endl;
00453     Printer< ::clearpath_sensors::GPSStatus_<ContainerAllocator> >::stream(s, indent + "  ", v.status);
00454     s << indent << "latitude: ";
00455     Printer<double>::stream(s, indent + "  ", v.latitude);
00456     s << indent << "longitude: ";
00457     Printer<double>::stream(s, indent + "  ", v.longitude);
00458     s << indent << "altitude: ";
00459     Printer<double>::stream(s, indent + "  ", v.altitude);
00460     s << indent << "track: ";
00461     Printer<double>::stream(s, indent + "  ", v.track);
00462     s << indent << "speed: ";
00463     Printer<double>::stream(s, indent + "  ", v.speed);
00464     s << indent << "climb: ";
00465     Printer<double>::stream(s, indent + "  ", v.climb);
00466     s << indent << "pitch: ";
00467     Printer<double>::stream(s, indent + "  ", v.pitch);
00468     s << indent << "roll: ";
00469     Printer<double>::stream(s, indent + "  ", v.roll);
00470     s << indent << "dip: ";
00471     Printer<double>::stream(s, indent + "  ", v.dip);
00472     s << indent << "time: ";
00473     Printer<double>::stream(s, indent + "  ", v.time);
00474     s << indent << "gdop: ";
00475     Printer<double>::stream(s, indent + "  ", v.gdop);
00476     s << indent << "pdop: ";
00477     Printer<double>::stream(s, indent + "  ", v.pdop);
00478     s << indent << "hdop: ";
00479     Printer<double>::stream(s, indent + "  ", v.hdop);
00480     s << indent << "vdop: ";
00481     Printer<double>::stream(s, indent + "  ", v.vdop);
00482     s << indent << "tdop: ";
00483     Printer<double>::stream(s, indent + "  ", v.tdop);
00484     s << indent << "err: ";
00485     Printer<double>::stream(s, indent + "  ", v.err);
00486     s << indent << "err_horz: ";
00487     Printer<double>::stream(s, indent + "  ", v.err_horz);
00488     s << indent << "err_vert: ";
00489     Printer<double>::stream(s, indent + "  ", v.err_vert);
00490     s << indent << "err_track: ";
00491     Printer<double>::stream(s, indent + "  ", v.err_track);
00492     s << indent << "err_speed: ";
00493     Printer<double>::stream(s, indent + "  ", v.err_speed);
00494     s << indent << "err_climb: ";
00495     Printer<double>::stream(s, indent + "  ", v.err_climb);
00496     s << indent << "err_time: ";
00497     Printer<double>::stream(s, indent + "  ", v.err_time);
00498     s << indent << "err_pitch: ";
00499     Printer<double>::stream(s, indent + "  ", v.err_pitch);
00500     s << indent << "err_roll: ";
00501     Printer<double>::stream(s, indent + "  ", v.err_roll);
00502     s << indent << "err_dip: ";
00503     Printer<double>::stream(s, indent + "  ", v.err_dip);
00504     s << indent << "position_covariance[]" << std::endl;
00505     for (size_t i = 0; i < v.position_covariance.size(); ++i)
00506     {
00507       s << indent << "  position_covariance[" << i << "]: ";
00508       Printer<double>::stream(s, indent + "  ", v.position_covariance[i]);
00509     }
00510     s << indent << "position_covariance_type: ";
00511     Printer<uint8_t>::stream(s, indent + "  ", v.position_covariance_type);
00512   }
00513 };
00514 
00515 
00516 } // namespace message_operations
00517 } // namespace ros
00518 
00519 #endif // CLEARPATH_SENSORS_MESSAGE_GPSFIX_H
00520 


clearpath_sensors
Author(s): Ryan Gariepy
autogenerated on Sun Oct 5 2014 22:52:23