Sub: update PID notch centers at 1Hz with average loop rate

This commit is contained in:
Andy Piper 2023-08-27 20:01:39 +01:00 committed by Andrew Tridgell
parent 0d10f74bf7
commit 2442bca978
1 changed files with 3 additions and 0 deletions

View File

@ -291,6 +291,9 @@ void Sub::one_hz_loop()
// need to set "likely flying" when armed to allow for compass
// learning to run
set_likely_flying(hal.util->get_soft_armed());
attitude_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
pos_control.get_accel_z_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
}
void Sub::read_AHRS()