00001
00002 #ifndef SENSOR_MSGS_MESSAGE_NAVSATFIX_H
00003 #define SENSOR_MSGS_MESSAGE_NAVSATFIX_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 "sensor_msgs/NavSatStatus.h"
00019
00020 namespace sensor_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct NavSatFix_ {
00024 typedef NavSatFix_<ContainerAllocator> Type;
00025
00026 NavSatFix_()
00027 : header()
00028 , status()
00029 , latitude(0.0)
00030 , longitude(0.0)
00031 , altitude(0.0)
00032 , position_covariance()
00033 , position_covariance_type(0)
00034 {
00035 position_covariance.assign(0.0);
00036 }
00037
00038 NavSatFix_(const ContainerAllocator& _alloc)
00039 : header(_alloc)
00040 , status(_alloc)
00041 , latitude(0.0)
00042 , longitude(0.0)
00043 , altitude(0.0)
00044 , position_covariance()
00045 , position_covariance_type(0)
00046 {
00047 position_covariance.assign(0.0);
00048 }
00049
00050 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00051 ::std_msgs::Header_<ContainerAllocator> header;
00052
00053 typedef ::sensor_msgs::NavSatStatus_<ContainerAllocator> _status_type;
00054 ::sensor_msgs::NavSatStatus_<ContainerAllocator> status;
00055
00056 typedef double _latitude_type;
00057 double latitude;
00058
00059 typedef double _longitude_type;
00060 double longitude;
00061
00062 typedef double _altitude_type;
00063 double altitude;
00064
00065 typedef boost::array<double, 9> _position_covariance_type;
00066 boost::array<double, 9> position_covariance;
00067
00068 typedef uint8_t _position_covariance_type_type;
00069 uint8_t position_covariance_type;
00070
00071 enum { COVARIANCE_TYPE_UNKNOWN = 0 };
00072 enum { COVARIANCE_TYPE_APPROXIMATED = 1 };
00073 enum { COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 };
00074 enum { COVARIANCE_TYPE_KNOWN = 3 };
00075
00076 ROS_DEPRECATED uint32_t get_position_covariance_size() const { return (uint32_t)position_covariance.size(); }
00077 private:
00078 static const char* __s_getDataType_() { return "sensor_msgs/NavSatFix"; }
00079 public:
00080 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00081
00082 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00083
00084 private:
00085 static const char* __s_getMD5Sum_() { return "2d3a8cd499b9b4a0249fb98fd05cfa48"; }
00086 public:
00087 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00088
00089 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00090
00091 private:
00092 static const char* __s_getMessageDefinition_() { return "# Navigation Satellite fix for any Global Navigation Satellite System\n\
00093 #\n\
00094 # Specified using the WGS 84 reference ellipsoid\n\
00095 \n\
00096 # Header specifies ROS time and frame of reference for this fix.\n\
00097 Header header\n\
00098 \n\
00099 # satellite fix status information\n\
00100 sensor_msgs/NavSatStatus status\n\
00101 \n\
00102 # Latitude [degrees]. Positive is north of equator; negative is south.\n\
00103 float64 latitude\n\
00104 \n\
00105 # Longitude [degrees]. Positive is east of prime meridian; negative is west.\n\
00106 float64 longitude\n\
00107 \n\
00108 # Altitude [m]. Positive is above the WGS 84 ellipsoid.\n\
00109 float64 altitude\n\
00110 \n\
00111 # Position covariance [m^2] defined relative to a tangential plane\n\
00112 # through the reported position. The components are East, North, and\n\
00113 # Up (ENU), in row-major order.\n\
00114 #\n\
00115 # Beware: this coordinate system exhibits singularities at the poles.\n\
00116 \n\
00117 float64[9] position_covariance\n\
00118 \n\
00119 # If the covariance of the fix is known, fill it in completely. If the\n\
00120 # GPS receiver provides the variance of each measurement, put them\n\
00121 # along the diagonal. If only Dilution of Precision is available,\n\
00122 # estimate an approximate covariance from that.\n\
00123 \n\
00124 uint8 COVARIANCE_TYPE_UNKNOWN = 0\n\
00125 uint8 COVARIANCE_TYPE_APPROXIMATED = 1\n\
00126 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\n\
00127 uint8 COVARIANCE_TYPE_KNOWN = 3\n\
00128 \n\
00129 uint8 position_covariance_type\n\
00130 \n\
00131 ================================================================================\n\
00132 MSG: std_msgs/Header\n\
00133 # Standard metadata for higher-level stamped data types.\n\
00134 # This is generally used to communicate timestamped data \n\
00135 # in a particular coordinate frame.\n\
00136 # \n\
00137 # sequence ID: consecutively increasing ID \n\
00138 uint32 seq\n\
00139 #Two-integer timestamp that is expressed as:\n\
00140 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00141 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00142 # time-handling sugar is provided by the client library\n\
00143 time stamp\n\
00144 #Frame this data is associated with\n\
00145 # 0: no frame\n\
00146 # 1: global frame\n\
00147 string frame_id\n\
00148 \n\
00149 ================================================================================\n\
00150 MSG: sensor_msgs/NavSatStatus\n\
00151 # Navigation Satellite fix status for any Global Navigation Satellite System\n\
00152 \n\
00153 # Whether to output an augmented fix is determined by both the fix\n\
00154 # type and the last time differential corrections were received. A\n\
00155 # fix is valid when status >= STATUS_FIX.\n\
00156 \n\
00157 int8 STATUS_NO_FIX = -1 # unable to fix position\n\
00158 int8 STATUS_FIX = 0 # unaugmented fix\n\
00159 int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation\n\
00160 int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation\n\
00161 \n\
00162 int8 status\n\
00163 \n\
00164 # Bits defining which Global Navigation Satellite System signals were\n\
00165 # used by the receiver.\n\
00166 \n\
00167 uint16 SERVICE_GPS = 1\n\
00168 uint16 SERVICE_GLONASS = 2\n\
00169 uint16 SERVICE_COMPASS = 4 # includes BeiDou.\n\
00170 uint16 SERVICE_GALILEO = 8\n\
00171 \n\
00172 uint16 service\n\
00173 \n\
00174 "; }
00175 public:
00176 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00177
00178 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00179
00180 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00181 {
00182 ros::serialization::OStream stream(write_ptr, 1000000000);
00183 ros::serialization::serialize(stream, header);
00184 ros::serialization::serialize(stream, status);
00185 ros::serialization::serialize(stream, latitude);
00186 ros::serialization::serialize(stream, longitude);
00187 ros::serialization::serialize(stream, altitude);
00188 ros::serialization::serialize(stream, position_covariance);
00189 ros::serialization::serialize(stream, position_covariance_type);
00190 return stream.getData();
00191 }
00192
00193 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00194 {
00195 ros::serialization::IStream stream(read_ptr, 1000000000);
00196 ros::serialization::deserialize(stream, header);
00197 ros::serialization::deserialize(stream, status);
00198 ros::serialization::deserialize(stream, latitude);
00199 ros::serialization::deserialize(stream, longitude);
00200 ros::serialization::deserialize(stream, altitude);
00201 ros::serialization::deserialize(stream, position_covariance);
00202 ros::serialization::deserialize(stream, position_covariance_type);
00203 return stream.getData();
00204 }
00205
00206 ROS_DEPRECATED virtual uint32_t serializationLength() const
00207 {
00208 uint32_t size = 0;
00209 size += ros::serialization::serializationLength(header);
00210 size += ros::serialization::serializationLength(status);
00211 size += ros::serialization::serializationLength(latitude);
00212 size += ros::serialization::serializationLength(longitude);
00213 size += ros::serialization::serializationLength(altitude);
00214 size += ros::serialization::serializationLength(position_covariance);
00215 size += ros::serialization::serializationLength(position_covariance_type);
00216 return size;
00217 }
00218
00219 typedef boost::shared_ptr< ::sensor_msgs::NavSatFix_<ContainerAllocator> > Ptr;
00220 typedef boost::shared_ptr< ::sensor_msgs::NavSatFix_<ContainerAllocator> const> ConstPtr;
00221 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00222 };
00223 typedef ::sensor_msgs::NavSatFix_<std::allocator<void> > NavSatFix;
00224
00225 typedef boost::shared_ptr< ::sensor_msgs::NavSatFix> NavSatFixPtr;
00226 typedef boost::shared_ptr< ::sensor_msgs::NavSatFix const> NavSatFixConstPtr;
00227
00228
00229 template<typename ContainerAllocator>
00230 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::NavSatFix_<ContainerAllocator> & v)
00231 {
00232 ros::message_operations::Printer< ::sensor_msgs::NavSatFix_<ContainerAllocator> >::stream(s, "", v);
00233 return s;}
00234
00235 }
00236
00237 namespace ros
00238 {
00239 namespace message_traits
00240 {
00241 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::NavSatFix_<ContainerAllocator> > : public TrueType {};
00242 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::NavSatFix_<ContainerAllocator> const> : public TrueType {};
00243 template<class ContainerAllocator>
00244 struct MD5Sum< ::sensor_msgs::NavSatFix_<ContainerAllocator> > {
00245 static const char* value()
00246 {
00247 return "2d3a8cd499b9b4a0249fb98fd05cfa48";
00248 }
00249
00250 static const char* value(const ::sensor_msgs::NavSatFix_<ContainerAllocator> &) { return value(); }
00251 static const uint64_t static_value1 = 0x2d3a8cd499b9b4a0ULL;
00252 static const uint64_t static_value2 = 0x249fb98fd05cfa48ULL;
00253 };
00254
00255 template<class ContainerAllocator>
00256 struct DataType< ::sensor_msgs::NavSatFix_<ContainerAllocator> > {
00257 static const char* value()
00258 {
00259 return "sensor_msgs/NavSatFix";
00260 }
00261
00262 static const char* value(const ::sensor_msgs::NavSatFix_<ContainerAllocator> &) { return value(); }
00263 };
00264
00265 template<class ContainerAllocator>
00266 struct Definition< ::sensor_msgs::NavSatFix_<ContainerAllocator> > {
00267 static const char* value()
00268 {
00269 return "# Navigation Satellite fix for any Global Navigation Satellite System\n\
00270 #\n\
00271 # Specified using the WGS 84 reference ellipsoid\n\
00272 \n\
00273 # Header specifies ROS time and frame of reference for this fix.\n\
00274 Header header\n\
00275 \n\
00276 # satellite fix status information\n\
00277 sensor_msgs/NavSatStatus status\n\
00278 \n\
00279 # Latitude [degrees]. Positive is north of equator; negative is south.\n\
00280 float64 latitude\n\
00281 \n\
00282 # Longitude [degrees]. Positive is east of prime meridian; negative is west.\n\
00283 float64 longitude\n\
00284 \n\
00285 # Altitude [m]. Positive is above the WGS 84 ellipsoid.\n\
00286 float64 altitude\n\
00287 \n\
00288 # Position covariance [m^2] defined relative to a tangential plane\n\
00289 # through the reported position. The components are East, North, and\n\
00290 # Up (ENU), in row-major order.\n\
00291 #\n\
00292 # Beware: this coordinate system exhibits singularities at the poles.\n\
00293 \n\
00294 float64[9] position_covariance\n\
00295 \n\
00296 # If the covariance of the fix is known, fill it in completely. If the\n\
00297 # GPS receiver provides the variance of each measurement, put them\n\
00298 # along the diagonal. If only Dilution of Precision is available,\n\
00299 # estimate an approximate covariance from that.\n\
00300 \n\
00301 uint8 COVARIANCE_TYPE_UNKNOWN = 0\n\
00302 uint8 COVARIANCE_TYPE_APPROXIMATED = 1\n\
00303 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\n\
00304 uint8 COVARIANCE_TYPE_KNOWN = 3\n\
00305 \n\
00306 uint8 position_covariance_type\n\
00307 \n\
00308 ================================================================================\n\
00309 MSG: std_msgs/Header\n\
00310 # Standard metadata for higher-level stamped data types.\n\
00311 # This is generally used to communicate timestamped data \n\
00312 # in a particular coordinate frame.\n\
00313 # \n\
00314 # sequence ID: consecutively increasing ID \n\
00315 uint32 seq\n\
00316 #Two-integer timestamp that is expressed as:\n\
00317 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00318 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00319 # time-handling sugar is provided by the client library\n\
00320 time stamp\n\
00321 #Frame this data is associated with\n\
00322 # 0: no frame\n\
00323 # 1: global frame\n\
00324 string frame_id\n\
00325 \n\
00326 ================================================================================\n\
00327 MSG: sensor_msgs/NavSatStatus\n\
00328 # Navigation Satellite fix status for any Global Navigation Satellite System\n\
00329 \n\
00330 # Whether to output an augmented fix is determined by both the fix\n\
00331 # type and the last time differential corrections were received. A\n\
00332 # fix is valid when status >= STATUS_FIX.\n\
00333 \n\
00334 int8 STATUS_NO_FIX = -1 # unable to fix position\n\
00335 int8 STATUS_FIX = 0 # unaugmented fix\n\
00336 int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation\n\
00337 int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation\n\
00338 \n\
00339 int8 status\n\
00340 \n\
00341 # Bits defining which Global Navigation Satellite System signals were\n\
00342 # used by the receiver.\n\
00343 \n\
00344 uint16 SERVICE_GPS = 1\n\
00345 uint16 SERVICE_GLONASS = 2\n\
00346 uint16 SERVICE_COMPASS = 4 # includes BeiDou.\n\
00347 uint16 SERVICE_GALILEO = 8\n\
00348 \n\
00349 uint16 service\n\
00350 \n\
00351 ";
00352 }
00353
00354 static const char* value(const ::sensor_msgs::NavSatFix_<ContainerAllocator> &) { return value(); }
00355 };
00356
00357 template<class ContainerAllocator> struct HasHeader< ::sensor_msgs::NavSatFix_<ContainerAllocator> > : public TrueType {};
00358 template<class ContainerAllocator> struct HasHeader< const ::sensor_msgs::NavSatFix_<ContainerAllocator> > : public TrueType {};
00359 }
00360 }
00361
00362 namespace ros
00363 {
00364 namespace serialization
00365 {
00366
00367 template<class ContainerAllocator> struct Serializer< ::sensor_msgs::NavSatFix_<ContainerAllocator> >
00368 {
00369 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00370 {
00371 stream.next(m.header);
00372 stream.next(m.status);
00373 stream.next(m.latitude);
00374 stream.next(m.longitude);
00375 stream.next(m.altitude);
00376 stream.next(m.position_covariance);
00377 stream.next(m.position_covariance_type);
00378 }
00379
00380 ROS_DECLARE_ALLINONE_SERIALIZER;
00381 };
00382 }
00383 }
00384
00385 namespace ros
00386 {
00387 namespace message_operations
00388 {
00389
00390 template<class ContainerAllocator>
00391 struct Printer< ::sensor_msgs::NavSatFix_<ContainerAllocator> >
00392 {
00393 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::NavSatFix_<ContainerAllocator> & v)
00394 {
00395 s << indent << "header: ";
00396 s << std::endl;
00397 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00398 s << indent << "status: ";
00399 s << std::endl;
00400 Printer< ::sensor_msgs::NavSatStatus_<ContainerAllocator> >::stream(s, indent + " ", v.status);
00401 s << indent << "latitude: ";
00402 Printer<double>::stream(s, indent + " ", v.latitude);
00403 s << indent << "longitude: ";
00404 Printer<double>::stream(s, indent + " ", v.longitude);
00405 s << indent << "altitude: ";
00406 Printer<double>::stream(s, indent + " ", v.altitude);
00407 s << indent << "position_covariance[]" << std::endl;
00408 for (size_t i = 0; i < v.position_covariance.size(); ++i)
00409 {
00410 s << indent << " position_covariance[" << i << "]: ";
00411 Printer<double>::stream(s, indent + " ", v.position_covariance[i]);
00412 }
00413 s << indent << "position_covariance_type: ";
00414 Printer<uint8_t>::stream(s, indent + " ", v.position_covariance_type);
00415 }
00416 };
00417
00418
00419 }
00420 }
00421
00422 #endif // SENSOR_MSGS_MESSAGE_NAVSATFIX_H
00423