mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed transition started airspeed message
this message was lost in recent refactoring
This commit is contained in:
parent
5554ad4311
commit
5ea3d8bde2
|
@ -1546,7 +1546,8 @@ void SLT_Transition::update()
|
||||||
quadplane.assisted_flight = true;
|
quadplane.assisted_flight = true;
|
||||||
// update transition state for vehicles using airspeed wait
|
// update transition state for vehicles using airspeed wait
|
||||||
if (!in_forced_transition) {
|
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);
|
gcs().send_text(MAV_SEVERITY_INFO, "Transition started airspeed %.1f", (double)aspeed);
|
||||||
}
|
}
|
||||||
transition_state = TRANSITION_AIRSPEED_WAIT;
|
transition_state = TRANSITION_AIRSPEED_WAIT;
|
||||||
|
|
Loading…
Reference in New Issue