Browse Source

Plane: set heartbeat.system_status to Critical for low-battery failsafe events

master
Tom Pittenger 9 years ago
parent
commit
204abfd45e
  1. 2
      ArduPlane/GCS_Mavlink.cpp

2
ArduPlane/GCS_Mavlink.cpp

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

Loading…
Cancel
Save