Browse Source

Copter: add adsb to failsafe structure and report in heartbeat to GCS

mission-4.1.18
Randy Mackay 9 years ago
parent
commit
68899ed921
  1. 1
      ArduCopter/Copter.h
  2. 2
      ArduCopter/GCS_Mavlink.cpp

1
ArduCopter/Copter.h

@ -293,6 +293,7 @@ private: @@ -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

2
ArduCopter/GCS_Mavlink.cpp

@ -36,7 +36,7 @@ NOINLINE void Copter::send_heartbeat(mavlink_channel_t chan) @@ -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…
Cancel
Save