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

This commit is contained in:
Tom Pittenger 2016-08-12 12:20:13 -07:00
parent b564616db0
commit fa326de7fa
2 changed files with 4 additions and 1 deletions

View File

@ -14,7 +14,7 @@ void Plane::send_heartbeat(mavlink_channel_t chan)
uint8_t system_status; uint8_t system_status;
uint32_t custom_mode = control_mode; uint32_t custom_mode = control_mode;
if (failsafe.state != FAILSAFE_NONE || failsafe.low_battery) { if (failsafe.state != FAILSAFE_NONE || failsafe.low_battery || failsafe.adsb) {
system_status = MAV_STATE_CRITICAL; system_status = MAV_STATE_CRITICAL;
} else if (plane.crash_state.is_crashed) { } else if (plane.crash_state.is_crashed) {
system_status = MAV_STATE_EMERGENCY; system_status = MAV_STATE_EMERGENCY;

View File

@ -350,6 +350,9 @@ private:
// flag to hold whether battery low voltage threshold has been breached // flag to hold whether battery low voltage threshold has been breached
uint8_t low_battery:1; uint8_t low_battery:1;
// true if an adsb related failsafe has occurred
uint8_t adsb:1;
// saved flight mode // saved flight mode
enum FlightMode saved_mode; enum FlightMode saved_mode;