Plane: allow set_throttle in manual and move disarmed override up

This commit is contained in:
Iampete1 2024-02-14 11:51:45 +00:00 committed by Andrew Tridgell
parent 5907e49cb1
commit 8a1872bd2a
2 changed files with 27 additions and 16 deletions

View File

@ -398,6 +398,13 @@ public:
void update() override;
void run() override;
// true if throttle min/max limits should be applied
bool use_throttle_limits() const { return false; }
// true if voltage correction should be applied to throttle
bool use_battery_compensation() const { return false; }
};

View File

@ -73,6 +73,11 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
*/
bool Plane::suppress_throttle(void)
{
if (control_mode == &mode_manual) {
// Throttle is never suppressed in manual mode
return false;
}
#if PARACHUTE == ENABLED
if (control_mode->does_auto_throttle() && parachute.release_initiated()) {
// throttle always suppressed in auto-throttle modes after parachute release initiated
@ -562,20 +567,7 @@ void Plane::set_throttle(void)
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, limited_throttle);
}
if (!arming.is_armed_and_safety_off()) {
// Always set 0 scaled even if overriding to zero pwm.
// This ensures slew limits and other functions using the scaled value pick up in the correct place
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0);
if (arming.arming_required() == AP_Arming::Required::YES_ZERO_PWM) {
SRV_Channels::set_output_limit(SRV_Channel::k_throttle, SRV_Channel::Limit::ZERO_PWM);
SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::Limit::ZERO_PWM);
SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, SRV_Channel::Limit::ZERO_PWM);
}
} else if (suppress_throttle()) {
if (suppress_throttle()) {
if (g.throttle_suppress_manual) {
// manual pass through of throttle while throttle is suppressed
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true));
@ -842,8 +834,20 @@ void Plane::set_servos(void)
landing.override_servos();
}
if (control_mode != &mode_manual) {
set_throttle();
set_throttle();
if ((control_mode != &mode_manual) && !arming.is_armed_and_safety_off()) {
// Always set 0 scaled even if overriding to zero pwm.
// This ensures slew limits and other functions using the scaled value pick up in the correct place
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0);
if (arming.arming_required() == AP_Arming::Required::YES_ZERO_PWM) {
SRV_Channels::set_output_limit(SRV_Channel::k_throttle, SRV_Channel::Limit::ZERO_PWM);
SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::Limit::ZERO_PWM);
SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, SRV_Channel::Limit::ZERO_PWM);
}
}
// Warn AHRS if we might take off soon