// Generated by gencpp from file sensor_msgs/NavSatFix.msg // DO NOT EDIT! #ifndef SENSOR_MSGS_MESSAGE_NAVSATFIX_H #define SENSOR_MSGS_MESSAGE_NAVSATFIX_H #include #include #include #include #include #include #include #include #include namespace sensor_msgs { template struct NavSatFix_ { typedef NavSatFix_ Type; NavSatFix_() : header() , status() , latitude(0.0) , longitude(0.0) , altitude(0.0) , position_covariance() , position_covariance_type(0) { position_covariance.assign(0.0); } NavSatFix_(const ContainerAllocator& _alloc) : header(_alloc) , status(_alloc) , latitude(0.0) , longitude(0.0) , altitude(0.0) , position_covariance() , position_covariance_type(0) { (void)_alloc; position_covariance.assign(0.0); } typedef ::std_msgs::Header_ _header_type; _header_type header; typedef ::sensor_msgs::NavSatStatus_ _status_type; _status_type status; typedef double _latitude_type; _latitude_type latitude; typedef double _longitude_type; _longitude_type longitude; typedef double _altitude_type; _altitude_type altitude; typedef boost::array _position_covariance_type; _position_covariance_type position_covariance; typedef uint8_t _position_covariance_type_type; _position_covariance_type_type position_covariance_type; enum { COVARIANCE_TYPE_UNKNOWN = 0u, COVARIANCE_TYPE_APPROXIMATED = 1u, COVARIANCE_TYPE_DIAGONAL_KNOWN = 2u, COVARIANCE_TYPE_KNOWN = 3u, }; typedef boost::shared_ptr< ::sensor_msgs::NavSatFix_ > Ptr; typedef boost::shared_ptr< ::sensor_msgs::NavSatFix_ const> ConstPtr; }; // struct NavSatFix_ typedef ::sensor_msgs::NavSatFix_ > NavSatFix; typedef boost::shared_ptr< ::sensor_msgs::NavSatFix > NavSatFixPtr; typedef boost::shared_ptr< ::sensor_msgs::NavSatFix const> NavSatFixConstPtr; // constants requiring out of line definition template std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::NavSatFix_ & v) { ros::message_operations::Printer< ::sensor_msgs::NavSatFix_ >::stream(s, "", v); return s; } } // namespace sensor_msgs namespace ros { namespace message_traits { // BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} // {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} // !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] template struct IsFixedSize< ::sensor_msgs::NavSatFix_ > : FalseType { }; template struct IsFixedSize< ::sensor_msgs::NavSatFix_ const> : FalseType { }; template struct IsMessage< ::sensor_msgs::NavSatFix_ > : TrueType { }; template struct IsMessage< ::sensor_msgs::NavSatFix_ const> : TrueType { }; template struct HasHeader< ::sensor_msgs::NavSatFix_ > : TrueType { }; template struct HasHeader< ::sensor_msgs::NavSatFix_ const> : TrueType { }; template struct MD5Sum< ::sensor_msgs::NavSatFix_ > { static const char* value() { return "2d3a8cd499b9b4a0249fb98fd05cfa48"; } static const char* value(const ::sensor_msgs::NavSatFix_&) { return value(); } static const uint64_t static_value1 = 0x2d3a8cd499b9b4a0ULL; static const uint64_t static_value2 = 0x249fb98fd05cfa48ULL; }; template struct DataType< ::sensor_msgs::NavSatFix_ > { static const char* value() { return "sensor_msgs/NavSatFix"; } static const char* value(const ::sensor_msgs::NavSatFix_&) { return value(); } }; template struct Definition< ::sensor_msgs::NavSatFix_ > { static const char* value() { return "# Navigation Satellite fix for any Global Navigation Satellite System\n\ #\n\ # Specified using the WGS 84 reference ellipsoid\n\ \n\ # header.stamp specifies the ROS time for this measurement (the\n\ # corresponding satellite time may be reported using the\n\ # sensor_msgs/TimeReference message).\n\ #\n\ # header.frame_id is the frame of reference reported by the satellite\n\ # receiver, usually the location of the antenna. This is a\n\ # Euclidean frame relative to the vehicle, not a reference\n\ # ellipsoid.\n\ Header header\n\ \n\ # satellite fix status information\n\ NavSatStatus status\n\ \n\ # Latitude [degrees]. Positive is north of equator; negative is south.\n\ float64 latitude\n\ \n\ # Longitude [degrees]. Positive is east of prime meridian; negative is west.\n\ float64 longitude\n\ \n\ # Altitude [m]. Positive is above the WGS 84 ellipsoid\n\ # (quiet NaN if no altitude is available).\n\ float64 altitude\n\ \n\ # Position covariance [m^2] defined relative to a tangential plane\n\ # through the reported position. The components are East, North, and\n\ # Up (ENU), in row-major order.\n\ #\n\ # Beware: this coordinate system exhibits singularities at the poles.\n\ \n\ float64[9] position_covariance\n\ \n\ # If the covariance of the fix is known, fill it in completely. If the\n\ # GPS receiver provides the variance of each measurement, put them\n\ # along the diagonal. If only Dilution of Precision is available,\n\ # estimate an approximate covariance from that.\n\ \n\ uint8 COVARIANCE_TYPE_UNKNOWN = 0\n\ uint8 COVARIANCE_TYPE_APPROXIMATED = 1\n\ uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\n\ uint8 COVARIANCE_TYPE_KNOWN = 3\n\ \n\ uint8 position_covariance_type\n\ \n\ ================================================================================\n\ MSG: std_msgs/Header\n\ # Standard metadata for higher-level stamped data types.\n\ # This is generally used to communicate timestamped data \n\ # in a particular coordinate frame.\n\ # \n\ # sequence ID: consecutively increasing ID \n\ uint32 seq\n\ #Two-integer timestamp that is expressed as:\n\ # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ # time-handling sugar is provided by the client library\n\ time stamp\n\ #Frame this data is associated with\n\ # 0: no frame\n\ # 1: global frame\n\ string frame_id\n\ \n\ ================================================================================\n\ MSG: sensor_msgs/NavSatStatus\n\ # Navigation Satellite fix status for any Global Navigation Satellite System\n\ \n\ # Whether to output an augmented fix is determined by both the fix\n\ # type and the last time differential corrections were received. A\n\ # fix is valid when status >= STATUS_FIX.\n\ \n\ int8 STATUS_NO_FIX = -1 # unable to fix position\n\ int8 STATUS_FIX = 0 # unaugmented fix\n\ int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation\n\ int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation\n\ \n\ int8 status\n\ \n\ # Bits defining which Global Navigation Satellite System signals were\n\ # used by the receiver.\n\ \n\ uint16 SERVICE_GPS = 1\n\ uint16 SERVICE_GLONASS = 2\n\ uint16 SERVICE_COMPASS = 4 # includes BeiDou.\n\ uint16 SERVICE_GALILEO = 8\n\ \n\ uint16 service\n\ "; } static const char* value(const ::sensor_msgs::NavSatFix_&) { return value(); } }; } // namespace message_traits } // namespace ros namespace ros { namespace serialization { template struct Serializer< ::sensor_msgs::NavSatFix_ > { template inline static void allInOne(Stream& stream, T m) { stream.next(m.header); stream.next(m.status); stream.next(m.latitude); stream.next(m.longitude); stream.next(m.altitude); stream.next(m.position_covariance); stream.next(m.position_covariance_type); } ROS_DECLARE_ALLINONE_SERIALIZER }; // struct NavSatFix_ } // namespace serialization } // namespace ros namespace ros { namespace message_operations { template struct Printer< ::sensor_msgs::NavSatFix_ > { template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::NavSatFix_& v) { s << indent << "header: "; s << std::endl; Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); s << indent << "status: "; s << std::endl; Printer< ::sensor_msgs::NavSatStatus_ >::stream(s, indent + " ", v.status); s << indent << "latitude: "; Printer::stream(s, indent + " ", v.latitude); s << indent << "longitude: "; Printer::stream(s, indent + " ", v.longitude); s << indent << "altitude: "; Printer::stream(s, indent + " ", v.altitude); s << indent << "position_covariance[]" << std::endl; for (size_t i = 0; i < v.position_covariance.size(); ++i) { s << indent << " position_covariance[" << i << "]: "; Printer::stream(s, indent + " ", v.position_covariance[i]); } s << indent << "position_covariance_type: "; Printer::stream(s, indent + " ", v.position_covariance_type); } }; } // namespace message_operations } // namespace ros #endif // SENSOR_MSGS_MESSAGE_NAVSATFIX_H