5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 23:48:31 -04:00

APM_Control: adjust filter for autotune to 0.75 Hz

this should give a better FF estimate
This commit is contained in:
Andrew Tridgell 2021-04-08 15:57:42 +10:00
parent 9e6561e6b5
commit 24d53eade4

View File

@ -126,9 +126,9 @@ void AP_AutoTune::start(void)
next_save = current;
// use 2Hz filters on the actuator and rate to reduce impact of noise
actuator_filter.set_cutoff_frequency(AP::scheduler().get_loop_rate_hz(), 2);
rate_filter.set_cutoff_frequency(AP::scheduler().get_loop_rate_hz(), 2);
// use 0.75Hz filters on the actuator and rate to reduce impact of noise
actuator_filter.set_cutoff_frequency(AP::scheduler().get_loop_rate_hz(), 0.75);
rate_filter.set_cutoff_frequency(AP::scheduler().get_loop_rate_hz(), 0.75);
ff_filter.reset();
actuator_filter.reset();