Plane: fixed transition started airspeed message

this message was lost in recent refactoring
This commit is contained in:
Andrew Tridgell 2023-07-03 09:14:17 +10:00
parent 9bcc26046c
commit 40ce471fec
1 changed files with 2 additions and 1 deletions

View File

@ -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;