mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: slew limit all throttles in one place
This commit is contained in:
parent
c415c7fbc7
commit
52efe952cd
@ -1159,7 +1159,7 @@ private:
|
|||||||
void servos_twin_engine_mix();
|
void servos_twin_engine_mix();
|
||||||
void force_flare();
|
void force_flare();
|
||||||
void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle);
|
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);
|
bool suppress_throttle(void);
|
||||||
void update_throttle_hover();
|
void update_throttle_hover();
|
||||||
void channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, SRV_Channel::Aux_servo_function_t func2_in,
|
void channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, SRV_Channel::Aux_servo_function_t func2_in,
|
||||||
|
@ -22,7 +22,7 @@
|
|||||||
/*****************************************
|
/*****************************************
|
||||||
* Throttle slew limit
|
* Throttle slew limit
|
||||||
*****************************************/
|
*****************************************/
|
||||||
void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
|
void Plane::throttle_slew_limit()
|
||||||
{
|
{
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
const bool do_throttle_slew = (control_mode->does_auto_throttle() || quadplane.in_assisted_flight() || quadplane.in_vtol_mode());
|
const bool do_throttle_slew = (control_mode->does_auto_throttle() || quadplane.in_assisted_flight() || quadplane.in_vtol_mode());
|
||||||
@ -32,7 +32,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
|
|||||||
|
|
||||||
if (!do_throttle_slew) {
|
if (!do_throttle_slew) {
|
||||||
// only do throttle slew limiting in modes where throttle control is automatic
|
// 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;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -55,7 +57,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
|
|||||||
slewrate = g.takeoff_throttle_slewrate;
|
slewrate = g.takeoff_throttle_slewrate;
|
||||||
}
|
}
|
||||||
#endif
|
#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.
|
/* We want to suppress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
|
||||||
@ -793,8 +797,6 @@ void Plane::servos_twin_engine_mix(void)
|
|||||||
} else {
|
} else {
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_left);
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_left);
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, throttle_right);
|
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);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -913,7 +915,7 @@ void Plane::set_servos(void)
|
|||||||
airbrake_update();
|
airbrake_update();
|
||||||
|
|
||||||
// slew rate limit throttle
|
// slew rate limit throttle
|
||||||
throttle_slew_limit(SRV_Channel::k_throttle);
|
throttle_slew_limit();
|
||||||
|
|
||||||
int8_t min_throttle = 0;
|
int8_t min_throttle = 0;
|
||||||
#if AP_ICENGINE_ENABLED
|
#if AP_ICENGINE_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user