mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Plane: separate out slew limit logic for left/right throttles
This commit is contained in:
parent
1a56659eec
commit
82c85de469
@ -989,7 +989,7 @@ private:
|
||||
void calc_nav_yaw_coordinated(float speed_scaler);
|
||||
void calc_nav_yaw_course(void);
|
||||
void calc_nav_yaw_ground(void);
|
||||
void throttle_slew_limit(void);
|
||||
void throttle_slew_limit(SRV_Channel::Aux_servo_function_t func);
|
||||
bool suppress_throttle(void);
|
||||
void channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, SRV_Channel::Aux_servo_function_t func2_in,
|
||||
SRV_Channel::Aux_servo_function_t func1_out, SRV_Channel::Aux_servo_function_t func2_out);
|
||||
|
@ -22,7 +22,7 @@
|
||||
/*****************************************
|
||||
* Throttle slew limit
|
||||
*****************************************/
|
||||
void Plane::throttle_slew_limit(void)
|
||||
void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
|
||||
{
|
||||
uint8_t slewrate = aparm.throttle_slewrate;
|
||||
if (control_mode==AUTO) {
|
||||
@ -34,9 +34,7 @@ void Plane::throttle_slew_limit(void)
|
||||
}
|
||||
// if slew limit rate is set to zero then do not slew limit
|
||||
if (slewrate) {
|
||||
SRV_Channels::limit_slew_rate(SRV_Channel::k_throttle, slewrate, G_Dt);
|
||||
SRV_Channels::limit_slew_rate(SRV_Channel::k_throttleLeft, slewrate, G_Dt);
|
||||
SRV_Channels::limit_slew_rate(SRV_Channel::k_throttleRight, slewrate, G_Dt);
|
||||
SRV_Channels::limit_slew_rate(func, slewrate, G_Dt);
|
||||
}
|
||||
}
|
||||
|
||||
@ -520,6 +518,8 @@ 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);
|
||||
}
|
||||
}
|
||||
|
||||
@ -601,7 +601,7 @@ void Plane::set_servos(void)
|
||||
quadplane.in_vtol_mode()) {
|
||||
/* only do throttle slew limiting in modes where throttle
|
||||
* control is automatic */
|
||||
throttle_slew_limit();
|
||||
throttle_slew_limit(SRV_Channel::k_throttle);
|
||||
}
|
||||
|
||||
if (!arming.is_armed()) {
|
||||
|
Loading…
Reference in New Issue
Block a user