mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 02:28:29 -04:00
Plane: account for sprung throttle in VTOL throttle suppression
when RC_OPTIONS has been changed to not check throttle for arming then treat this like a sprung throttle for quadplane throttle suppression in auto-throttle modes, and only unsuppress when throttle goes above trim+dz
This commit is contained in:
parent
eed5079295
commit
669e11b80d
@ -1793,8 +1793,17 @@ void QuadPlane::update_throttle_suppression(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if the users throttle is above zero then allow motors to run
|
/* if the users throttle is above zero then allow motors to run
|
||||||
if (!is_zero(plane.get_throttle_input())) {
|
|
||||||
|
if the user has unset the "check throttle zero when arming"
|
||||||
|
then the RC controller has a sprung throttle and we should not
|
||||||
|
consider non-zero throttle to mean that pilot is commanding
|
||||||
|
takeoff unless in a manual thottle mode
|
||||||
|
*/
|
||||||
|
if (!is_zero(plane.get_throttle_input()) &&
|
||||||
|
(rc().arming_check_throttle() ||
|
||||||
|
plane.control_mode->is_vtol_man_throttle() ||
|
||||||
|
plane.channel_throttle->norm_input_dz() > 0)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user