plane: restore thr_min behaviour and update description
This commit is contained in:
parent
b22d3a0103
commit
fb4b092917
@ -401,7 +401,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
|
||||
// @Param: THR_MIN
|
||||
// @DisplayName: Minimum Throttle
|
||||
// @Description: Minimum throttle percentage used in automatic throttle modes. Negative values allow reverse thrust if hardware supports it.
|
||||
// @Description: Minimum throttle percentage used in all modes except manual, provided THR_PASS_STAB is not set. Negative values allow reverse thrust if hardware supports it.
|
||||
// @Units: %
|
||||
// @Range: -100 100
|
||||
// @Increment: 1
|
||||
|
@ -442,9 +442,10 @@ void Plane::set_servos_controlled(void)
|
||||
} else 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, channel_throttle->get_control_in_zero_dz());
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true));
|
||||
} else {
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in());
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle,
|
||||
constrain_int16(get_throttle_input(true), min_throttle, max_throttle));
|
||||
}
|
||||
} else if ((control_mode == &mode_guided || control_mode == &mode_avoidADSB) &&
|
||||
guided_throttle_passthru) {
|
||||
@ -749,9 +750,10 @@ void Plane::set_servos(void)
|
||||
|
||||
case AP_Arming::Required::YES_MIN_PWM:
|
||||
default:
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0);
|
||||
int8_t min_throttle = MAX(aparm.throttle_min.get(),0);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, min_throttle);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, min_throttle);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, min_throttle);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user