mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: add adsb to failsafe structure and report in heartbeat to GCS
This commit is contained in:
parent
f4db4bdb08
commit
68899ed921
@ -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
|
||||
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user