mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed takeoff throttle slew rate
when TKOFF_THR_SLEW is zero use the normal slew rate
This commit is contained in:
parent
2b0f142a17
commit
24325a5c62
|
@ -475,11 +475,11 @@ static void calc_nav_roll()
|
||||||
static void throttle_slew_limit(int16_t last_throttle)
|
static void throttle_slew_limit(int16_t last_throttle)
|
||||||
{
|
{
|
||||||
uint8_t slewrate = aparm.throttle_slewrate;
|
uint8_t slewrate = aparm.throttle_slewrate;
|
||||||
if (control_mode==AUTO && auto_state.takeoff_complete == false) {
|
if (control_mode==AUTO && auto_state.takeoff_complete == false && g.takeoff_throttle_slewrate != 0) {
|
||||||
slewrate = g.takeoff_throttle_slewrate;
|
slewrate = g.takeoff_throttle_slewrate;
|
||||||
}
|
}
|
||||||
// if slew limit rate is set to zero then do not slew limit
|
// if slew limit rate is set to zero then do not slew limit
|
||||||
if (aparm.throttle_slewrate) {
|
if (slewrate) {
|
||||||
// limit throttle change by the given percentage per second
|
// limit throttle change by the given percentage per second
|
||||||
float temp = slewrate * G_Dt * 0.01f * fabsf(channel_throttle->radio_max - channel_throttle->radio_min);
|
float temp = slewrate * G_Dt * 0.01f * fabsf(channel_throttle->radio_max - channel_throttle->radio_min);
|
||||||
// allow a minimum change of 1 PWM per cycle
|
// allow a minimum change of 1 PWM per cycle
|
||||||
|
|
Loading…
Reference in New Issue