From 2673cde52bddc595805cc43c8fd17fb5a026b893 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 15 Sep 2021 12:18:45 +0530 Subject: [PATCH] AP_UAVCAN: add dsdl for sending vehicle notify state --- .../indication/20007.NotifyState.uavcan | 35 +++++++++++++++++++ 1 file changed, 35 insertions(+) create mode 100644 libraries/AP_UAVCAN/dsdl/ardupilot/indication/20007.NotifyState.uavcan diff --git a/libraries/AP_UAVCAN/dsdl/ardupilot/indication/20007.NotifyState.uavcan b/libraries/AP_UAVCAN/dsdl/ardupilot/indication/20007.NotifyState.uavcan new file mode 100644 index 0000000000..a4aadc9c5d --- /dev/null +++ b/libraries/AP_UAVCAN/dsdl/ardupilot/indication/20007.NotifyState.uavcan @@ -0,0 +1,35 @@ +uint8 VEHICLE_STATE_INITIALISING = 0 +uint8 VEHICLE_STATE_ARMED = 1 +uint8 VEHICLE_STATE_FLYING = 2 +uint8 VEHICLE_STATE_PREARM = 3 +uint8 VEHICLE_STATE_PREARM_GPS = 4 +uint8 VEHICLE_STATE_SAVE_TRIM = 5 +uint8 VEHICLE_STATE_ESC_CALIBRATION = 6 +uint8 VEHICLE_STATE_FAILSAFE_RADIO = 7 +uint8 VEHICLE_STATE_FAILSAFE_BATT = 8 +uint8 VEHICLE_STATE_FAILSAFE_GCS = 9 +uint8 VEHICLE_STATE_CHUTE_RELEASED = 10 +uint8 VEHICLE_STATE_EKF_BAD = 11 +uint8 VEHICLE_STATE_FW_UPDATE = 12 +uint8 VEHICLE_STATE_MAGCAL_RUN = 13 +uint8 VEHICLE_STATE_LEAK_DET = 14 +uint8 VEHICLE_STATE_GPS_FUSION = 15 +uint8 VEHICLE_STATE_GPS_GLITCH = 16 +uint8 VEHICLE_STATE_POS_ABS_AVAIL = 17 +uint8 VEHICLE_STATE_LOST = 18 +uint8 VEHICLE_STATE_THROW_READY = 19 +uint8 VEHICLE_STATE_POWERING_OFF = 20 +uint8 VEHICLE_STATE_VIDEO_RECORDING = 21 + + +uint8 VEHICLE_YAW_EARTH_CENTIDEGREES = 0 + +# set the type of aux data to be sent +uint8 aux_data_type + +# bytes containing packed auxiliary data +# placing it first so we don't do TAO +uint8[<=255] aux_data + +# Current Vehicle State Mask +uint64 vehicle_state