Plane: ignore invalid pilot throttle

This commit is contained in:
Iampete1 2023-11-25 23:38:25 +00:00 committed by Andrew Tridgell
parent 97417a1038
commit 483ef18087
2 changed files with 9 additions and 3 deletions

View File

@ -125,6 +125,10 @@ bool Plane::have_reverse_thrust(void) const
*/
float Plane::get_throttle_input(bool no_deadzone) const
{
if (!rc().has_valid_input()) {
// Return 0 if there is no valid input
return 0.0;
}
float ret;
if (no_deadzone) {
ret = channel_throttle->get_control_in_zero_dz();
@ -143,6 +147,10 @@ float Plane::get_throttle_input(bool no_deadzone) const
*/
float Plane::get_adjusted_throttle_input(bool no_deadzone) const
{
if (!rc().has_valid_input()) {
// Return 0 if there is no valid input
return 0.0;
}
if ((plane.channel_throttle->get_type() != RC_Channel::ControlType::RANGE) ||
(flight_option_enabled(FlightOptions::CENTER_THROTTLE_TRIM)) == 0) {
return get_throttle_input(no_deadzone);

View File

@ -551,9 +551,7 @@ void Plane::set_servos_controlled(void)
control_mode == &mode_fbwa ||
control_mode == &mode_autotune) {
// a manual throttle mode
if (!rc().has_valid_input()) {
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, g.throttle_passthru_stabilize ? 0.0 : MAX(min_throttle,0));
} else if (g.throttle_passthru_stabilize) {
if (g.throttle_passthru_stabilize) {
// manual pass through of throttle while in FBWA or
// STABILIZE mode with THR_PASS_STAB set
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true));