mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
Plane: abstract land abort request method
This commit is contained in:
parent
3dcf4cfb55
commit
8c1509ad47
@ -978,7 +978,7 @@ 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.commanded_go_around || flight_stage == AP_SpdHgtControl::FLIGHT_LAND_ABORT) {
|
||||
if (landing.is_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) {
|
||||
|
@ -1360,9 +1360,12 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
||||
if (!is_zero(packet.param1)) {
|
||||
plane.auto_state.takeoff_altitude_rel_cm = packet.param1 * 100;
|
||||
}
|
||||
plane.landing.commanded_go_around = true;
|
||||
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
if (plane.landing.request_go_around()) {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
}
|
||||
|
||||
if (result == MAV_RESULT_ACCEPTED) {
|
||||
plane.gcs_send_text(MAV_SEVERITY_INFO,"Go around command accepted");
|
||||
} else {
|
||||
plane.gcs_send_text(MAV_SEVERITY_NOTICE,"Rejected go around command");
|
||||
|
Loading…
Reference in New Issue
Block a user