diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index bc9a8e3853..f067b6b0c8 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -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;