Plane: fixed yaw on the ground when rudder disarming in AUTO

when a quadplane touches down in an auto throttle mode the pilot may
use rudder to disarm. The check for rudder disarm was only active in
modes without auto-throttle. This expands it to all modes if the
throttle has hit the lower limit
This commit is contained in:
Andrew Tridgell 2022-03-23 14:34:22 +11:00
parent 7a62b5429b
commit 48881eeb55
2 changed files with 6 additions and 3 deletions

View File

@ -67,7 +67,8 @@ void Plane::fence_check()
if (fence_act == AC_FENCE_ACTION_RTL_AND_LAND) { if (fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
if (control_mode == &mode_auto && if (control_mode == &mode_auto &&
mission.get_in_landing_sequence_flag() && mission.get_in_landing_sequence_flag() &&
(g.rtl_autoland == 1 || g.rtl_autoland == 2)) { (g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START ||
g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START)) {
// already landing // already landing
return; return;
} }

View File

@ -1174,8 +1174,10 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
{ {
bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active(); bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active();
if (!manual_air_mode && if (!manual_air_mode &&
!is_positive(plane.get_throttle_input()) && !plane.control_mode->does_auto_throttle() && !is_positive(plane.get_throttle_input()) &&
plane.arming.get_rudder_arming_type() != AP_Arming::RudderArming::IS_DISABLED && !(inertial_nav.get_velocity_z_up_cms() < -0.5 * get_pilot_velocity_z_max_dn())) { (!plane.control_mode->does_auto_throttle() || motors->limit.throttle_lower) &&
plane.arming.get_rudder_arming_type() != AP_Arming::RudderArming::IS_DISABLED &&
fabsf(inertial_nav.get_velocity_z_up_cms()) < 0.5 * get_pilot_velocity_z_max_dn()) {
// the user may be trying to disarm // the user may be trying to disarm
return 0; return 0;
} }