mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
Plane: fixed transition started airspeed message
this message was lost in recent refactoring
This commit is contained in:
parent
b544081ee6
commit
fa75c75b72
@ -1546,7 +1546,8 @@ void SLT_Transition::update()
|
||||
quadplane.assisted_flight = true;
|
||||
// update transition state for vehicles using airspeed wait
|
||||
if (!in_forced_transition) {
|
||||
if (transition_state != TRANSITION_AIRSPEED_WAIT) {
|
||||
const bool show_message = transition_state != TRANSITION_AIRSPEED_WAIT || transition_start_ms == 0;
|
||||
if (show_message) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Transition started airspeed %.1f", (double)aspeed);
|
||||
}
|
||||
transition_state = TRANSITION_AIRSPEED_WAIT;
|
||||
|
Loading…
Reference in New Issue
Block a user