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