mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: post msg if aborting via throttle
fixes https://github.com/ArduPilot/ardupilot/issues/4906
This commit is contained in:
parent
608da33d80
commit
9dd46aa03a
@ -978,11 +978,12 @@ void Plane::update_flight_stage(void)
|
||||
set_flight_stage(AP_SpdHgtControl::FLIGHT_TAKEOFF);
|
||||
} else if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND) {
|
||||
|
||||
if ((landing.get_abort_throttle_enable() && channel_throttle->get_control_in() >= 90) ||
|
||||
landing.commanded_go_around ||
|
||||
flight_stage == AP_SpdHgtControl::FLIGHT_LAND_ABORT){
|
||||
if (landing.commanded_go_around || flight_stage == AP_SpdHgtControl::FLIGHT_LAND_ABORT) {
|
||||
// abort mode is sticky, it must complete while executing NAV_LAND
|
||||
set_flight_stage(AP_SpdHgtControl::FLIGHT_LAND_ABORT);
|
||||
} else if (landing.get_abort_throttle_enable() && channel_throttle->get_control_in() >= 90) {
|
||||
plane.gcs_send_text(MAV_SEVERITY_INFO,"Landing aborted via throttle");
|
||||
set_flight_stage(AP_SpdHgtControl::FLIGHT_LAND_ABORT);
|
||||
} else if (landing.complete == true) {
|
||||
set_flight_stage(AP_SpdHgtControl::FLIGHT_LAND_FINAL);
|
||||
} else if (landing.pre_flare == true) {
|
||||
|
Loading…
Reference in New Issue
Block a user