Skip to content

Commit

Permalink
Plane: slew limit all throttles in one place
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Nov 19, 2024
1 parent c415c7f commit 52efe95
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 7 deletions.
2 changes: 1 addition & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -1159,7 +1159,7 @@ class Plane : public AP_Vehicle {
void servos_twin_engine_mix();
void force_flare();
void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle);
void throttle_slew_limit(SRV_Channel::Aux_servo_function_t func);
void throttle_slew_limit();
bool suppress_throttle(void);
void update_throttle_hover();
void channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, SRV_Channel::Aux_servo_function_t func2_in,
Expand Down
14 changes: 8 additions & 6 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
/*****************************************
* Throttle slew limit
*****************************************/
void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
void Plane::throttle_slew_limit()
{
#if HAL_QUADPLANE_ENABLED
const bool do_throttle_slew = (control_mode->does_auto_throttle() || quadplane.in_assisted_flight() || quadplane.in_vtol_mode());
Expand All @@ -32,7 +32,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)

if (!do_throttle_slew) {
// only do throttle slew limiting in modes where throttle control is automatic
SRV_Channels::set_slew_rate(func, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, 0.0, 100, G_Dt);
return;
}

Expand All @@ -55,7 +57,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
slewrate = g.takeoff_throttle_slewrate;
}
#endif
SRV_Channels::set_slew_rate(func, slewrate, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, slewrate, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, slewrate, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, slewrate, 100, G_Dt);
}

/* We want to suppress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
Expand Down Expand Up @@ -793,8 +797,6 @@ void Plane::servos_twin_engine_mix(void)
} else {
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_left);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, throttle_right);
throttle_slew_limit(SRV_Channel::k_throttleLeft);
throttle_slew_limit(SRV_Channel::k_throttleRight);
}
}

Expand Down Expand Up @@ -913,7 +915,7 @@ void Plane::set_servos(void)
airbrake_update();

// slew rate limit throttle
throttle_slew_limit(SRV_Channel::k_throttle);
throttle_slew_limit();

int8_t min_throttle = 0;
#if AP_ICENGINE_ENABLED
Expand Down

0 comments on commit 52efe95

Please sign in to comment.