5 #ifndef SENSOR_MSGS_MESSAGE_NAVSATFIX_H 6 #define SENSOR_MSGS_MESSAGE_NAVSATFIX_H 23 template <
class ContainerAllocator>
55 typedef ::sensor_msgs::NavSatStatus_<ContainerAllocator>
_status_type;
85 typedef ::sensor_msgs::NavSatFix_<std::allocator<void> >
NavSatFix;
102 template<
typename ContainerAllocator>
103 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::NavSatFix_<ContainerAllocator> &
v)
113 namespace message_traits
126 template <
class ContainerAllocator>
131 template <
class ContainerAllocator>
136 template <
class ContainerAllocator>
141 template <
class ContainerAllocator>
146 template <
class ContainerAllocator>
151 template <
class ContainerAllocator>
157 template<
class ContainerAllocator>
162 return "2d3a8cd499b9b4a0249fb98fd05cfa48";
165 static const char*
value(const ::sensor_msgs::NavSatFix_<ContainerAllocator>&) {
return value(); }
166 static const uint64_t static_value1 = 0x2d3a8cd499b9b4a0ULL;
167 static const uint64_t static_value2 = 0x249fb98fd05cfa48ULL;
170 template<
class ContainerAllocator>
175 return "sensor_msgs/NavSatFix";
178 static const char*
value(const ::sensor_msgs::NavSatFix_<ContainerAllocator>&) {
return value(); }
181 template<
class ContainerAllocator>
186 return "# Navigation Satellite fix for any Global Navigation Satellite System\n\ 188 # Specified using the WGS 84 reference ellipsoid\n\ 190 # header.stamp specifies the ROS time for this measurement (the\n\ 191 # corresponding satellite time may be reported using the\n\ 192 # sensor_msgs/TimeReference message).\n\ 194 # header.frame_id is the frame of reference reported by the satellite\n\ 195 # receiver, usually the location of the antenna. This is a\n\ 196 # Euclidean frame relative to the vehicle, not a reference\n\ 200 # satellite fix status information\n\ 201 NavSatStatus status\n\ 203 # Latitude [degrees]. Positive is north of equator; negative is south.\n\ 206 # Longitude [degrees]. Positive is east of prime meridian; negative is west.\n\ 209 # Altitude [m]. Positive is above the WGS 84 ellipsoid\n\ 210 # (quiet NaN if no altitude is available).\n\ 213 # Position covariance [m^2] defined relative to a tangential plane\n\ 214 # through the reported position. The components are East, North, and\n\ 215 # Up (ENU), in row-major order.\n\ 217 # Beware: this coordinate system exhibits singularities at the poles.\n\ 219 float64[9] position_covariance\n\ 221 # If the covariance of the fix is known, fill it in completely. If the\n\ 222 # GPS receiver provides the variance of each measurement, put them\n\ 223 # along the diagonal. If only Dilution of Precision is available,\n\ 224 # estimate an approximate covariance from that.\n\ 226 uint8 COVARIANCE_TYPE_UNKNOWN = 0\n\ 227 uint8 COVARIANCE_TYPE_APPROXIMATED = 1\n\ 228 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\n\ 229 uint8 COVARIANCE_TYPE_KNOWN = 3\n\ 231 uint8 position_covariance_type\n\ 233 ================================================================================\n\ 234 MSG: std_msgs/Header\n\ 235 # Standard metadata for higher-level stamped data types.\n\ 236 # This is generally used to communicate timestamped data \n\ 237 # in a particular coordinate frame.\n\ 239 # sequence ID: consecutively increasing ID \n\ 241 #Two-integer timestamp that is expressed as:\n\ 242 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 243 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 244 # time-handling sugar is provided by the client library\n\ 246 #Frame this data is associated with\n\ 251 ================================================================================\n\ 252 MSG: sensor_msgs/NavSatStatus\n\ 253 # Navigation Satellite fix status for any Global Navigation Satellite System\n\ 255 # Whether to output an augmented fix is determined by both the fix\n\ 256 # type and the last time differential corrections were received. A\n\ 257 # fix is valid when status >= STATUS_FIX.\n\ 259 int8 STATUS_NO_FIX = -1 # unable to fix position\n\ 260 int8 STATUS_FIX = 0 # unaugmented fix\n\ 261 int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation\n\ 262 int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation\n\ 266 # Bits defining which Global Navigation Satellite System signals were\n\ 267 # used by the receiver.\n\ 269 uint16 SERVICE_GPS = 1\n\ 270 uint16 SERVICE_GLONASS = 2\n\ 271 uint16 SERVICE_COMPASS = 4 # includes BeiDou.\n\ 272 uint16 SERVICE_GALILEO = 8\n\ 278 static const char*
value(const ::sensor_msgs::NavSatFix_<ContainerAllocator>&) {
return value(); }
286 namespace serialization
293 stream.next(m.header);
294 stream.next(m.status);
295 stream.next(m.latitude);
296 stream.next(m.longitude);
297 stream.next(m.altitude);
298 stream.next(m.position_covariance);
299 stream.next(m.position_covariance_type);
310 namespace message_operations
313 template<
class ContainerAllocator>
316 template<
typename Stream>
static void stream(Stream&
s,
const std::string& indent, const ::sensor_msgs::NavSatFix_<ContainerAllocator>&
v)
318 s << indent <<
"header: ";
321 s << indent <<
"status: ";
324 s << indent <<
"latitude: ";
326 s << indent <<
"longitude: ";
328 s << indent <<
"altitude: ";
330 s << indent <<
"position_covariance[]" << std::endl;
331 for (
size_t i = 0;
i < v.position_covariance.size(); ++
i)
333 s << indent <<
" position_covariance[" <<
i <<
"]: ";
336 s << indent <<
"position_covariance_type: ";
344 #endif // SENSOR_MSGS_MESSAGE_NAVSATFIX_H
boost::shared_ptr< ::sensor_msgs::NavSatFix > NavSatFixPtr
boost::array< double, 9 > _position_covariance_type
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
static const char * value()
NavSatFix_< ContainerAllocator > Type
Specialize to provide the md5sum for a message.
static const char * value(const ::sensor_msgs::NavSatFix_< ContainerAllocator > &)
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
uint8_t _position_covariance_type_type
GLsizei const GLchar *const * string
Specialize to provide the datatype for a message.
::sensor_msgs::NavSatStatus_< ContainerAllocator > _status_type
static void allInOne(Stream &stream, T m)
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::NavSatFix_< ContainerAllocator > &v)
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
static const char * value(const ::sensor_msgs::NavSatFix_< ContainerAllocator > &)
Stream base-class, provides common functionality for IStream and OStream.
::std_msgs::Header_< ContainerAllocator > _header_type
NavSatFix_(const ContainerAllocator &_alloc)
_position_covariance_type position_covariance
Tools for manipulating sensor_msgs.
_position_covariance_type_type position_covariance_type
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
unsigned __int64 uint64_t
Specialize to provide the definition for a message.
static const char * value()
boost::shared_ptr< ::sensor_msgs::NavSatFix_< ContainerAllocator > > Ptr
_longitude_type longitude
static const char * value(const ::sensor_msgs::NavSatFix_< ContainerAllocator > &)
boost::shared_ptr< ::sensor_msgs::NavSatFix const > NavSatFixConstPtr
Templated serialization class. Default implementation provides backwards compatibility with old messa...
static const char * value()
boost::shared_ptr< ::sensor_msgs::NavSatFix_< ContainerAllocator > const > ConstPtr
::sensor_msgs::NavSatFix_< std::allocator< void > > NavSatFix