Ardupilot2/libraries/AP_DDS/Idl/NavSatStatus.idl
Ryan Friedman 80a0373717 AP_DDS: Bump to using latest MicroXRCEDDSGen
* Adds -cs argument to fix case sensitive issue with PoseStamped
* Adds support for uint8_t type alias
* Updated the copies of IDL to remove these mods, matching upstream
* Solves #23302

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
2023-03-29 21:50:12 +11:00

43 lines
1.5 KiB
Plaintext

// generated from rosidl_adapter/resource/msg.idl.em
// with input from sensor_msgs/msg/NavSatStatus.msg
// generated code does not contain a copyright notice
module sensor_msgs {
module msg {
module NavSatStatus_Constants {
@verbatim (language="comment", text=
"unable to fix position")
const int8 STATUS_NO_FIX = -1;
@verbatim (language="comment", text=
"unaugmented fix")
const int8 STATUS_FIX = 0;
@verbatim (language="comment", text=
"with satellite-based augmentation")
const int8 STATUS_SBAS_FIX = 1;
@verbatim (language="comment", text=
"with ground-based augmentation")
const int8 STATUS_GBAS_FIX = 2;
@verbatim (language="comment", text=
"Bits defining which Global Navigation Satellite System signals were" "\n" "used by the receiver.")
const uint16 SERVICE_GPS = 1;
const uint16 SERVICE_GLONASS = 2;
@verbatim (language="comment", text=
"includes BeiDou.")
const uint16 SERVICE_COMPASS = 4;
const uint16 SERVICE_GALILEO = 8;
};
@verbatim (language="comment", text=
"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.")
struct NavSatStatus {
int8 status;
uint16 service;
};
};
};