|
|
|
@ -3681,10 +3681,14 @@ void Commander::battery_status_check()
@@ -3681,10 +3681,14 @@ void Commander::battery_status_check()
|
|
|
|
|
// Try to trigger RTL
|
|
|
|
|
if (main_state_transition(_status, commander_state_s::MAIN_STATE_AUTO_RTL, _status_flags, |
|
|
|
|
_internal_state) == TRANSITION_CHANGED) { |
|
|
|
|
mavlink_log_emergency(&_mavlink_log_pub, "Flight time low, returning to land"); |
|
|
|
|
mavlink_log_emergency(&_mavlink_log_pub, "Remaining flight time low, returning to land\t"); |
|
|
|
|
events::send(events::ID("commander_remaining_flight_time_rtl"), {events::Log::Critical, events::LogInternal::Info}, |
|
|
|
|
"Remaining flight time low, returning to land"); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
mavlink_log_emergency(&_mavlink_log_pub, "Flight time low, land now!"); |
|
|
|
|
mavlink_log_emergency(&_mavlink_log_pub, "Remaining flight time low, land now!\t"); |
|
|
|
|
events::send(events::ID("commander_remaining_flight_time_land"), {events::Log::Critical, events::LogInternal::Info}, |
|
|
|
|
"Remaining flight time low, land now!"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_rtl_time_actions_done = true; |
|
|
|
|