From 68899ed921968f8a52b8a82ca43a243036820175 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 19 Jul 2016 15:42:46 +0900 Subject: [PATCH] Copter: add adsb to failsafe structure and report in heartbeat to GCS --- ArduCopter/Copter.h | 1 + ArduCopter/GCS_Mavlink.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 58cc6e698b..280fb8383e 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -293,6 +293,7 @@ private: uint8_t gcs : 1; // 4 // A status flag for the ground station failsafe uint8_t ekf : 1; // 5 // true if ekf failsafe has occurred uint8_t terrain : 1; // 6 // true if the missing terrain data failsafe has occurred + uint8_t adsb : 1; // 7 // true if an adsb related failsafe has occurred int8_t radio_counter; // number of iterations with throttle below throttle_fs_value diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index b71c1e9824..924e89a827 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -36,7 +36,7 @@ NOINLINE void Copter::send_heartbeat(mavlink_channel_t chan) uint32_t custom_mode = control_mode; // set system as critical if any failsafe have triggered - if (failsafe.radio || failsafe.battery || failsafe.gcs || failsafe.ekf || failsafe.terrain) { + if (failsafe.radio || failsafe.battery || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb) { system_status = MAV_STATE_CRITICAL; }