mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SRV_Channel: fixed output slew rate handling
this fixes a bug that happens when the RC output speed is much lower than the main loop speed, such as with forward throttle for quadplanes. We need to base the slew on the last sent output, not the last value read back (at 50Hz) from the IO board, or we will slew the channel at 6x to 8x slower than the correct rate.
This commit is contained in:
parent
3ce7e4b322
commit
29b06d2d4a
@ -558,7 +558,7 @@ void SRV_Channels::limit_slew_rate(SRV_Channel::Aux_servo_function_t function, f
|
||||
SRV_Channel &ch = channels[i];
|
||||
if (ch.function == function) {
|
||||
ch.calc_pwm(functions[function].output_scaled);
|
||||
uint16_t last_pwm = hal.rcout->read(ch.ch_num);
|
||||
uint16_t last_pwm = hal.rcout->read_last_sent(ch.ch_num);
|
||||
if (last_pwm == ch.output_pwm) {
|
||||
continue;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user