Browse Source

APM_Control: adjust filter for autotune to 0.75 Hz

this should give a better FF estimate
c415-sdk
Andrew Tridgell 4 years ago
parent
commit
24d53eade4
  1. 6
      libraries/APM_Control/AP_AutoTune.cpp

6
libraries/APM_Control/AP_AutoTune.cpp

@ -126,9 +126,9 @@ void AP_AutoTune::start(void) @@ -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();

Loading…
Cancel
Save