mirror of https://github.com/ArduPilot/ardupilot
Plane: corrected land abort gcs msg
This commit is contained in:
parent
38b7d7e1c6
commit
78d6291e2c
|
@ -843,7 +843,7 @@ void Plane::set_flight_stage(AP_SpdHgtControl::FlightStage fs)
|
|||
break;
|
||||
|
||||
case AP_SpdHgtControl::FLIGHT_LAND_ABORT:
|
||||
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Landing aborted via throttle. Climbing to %dm", auto_state.takeoff_altitude_rel_cm/100);
|
||||
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Landing aborted, climbing to %dm", auto_state.takeoff_altitude_rel_cm/100);
|
||||
break;
|
||||
|
||||
case AP_SpdHgtControl::FLIGHT_LAND_PREFLARE:
|
||||
|
|
Loading…
Reference in New Issue