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

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

View File

@ -357,6 +357,16 @@ void Plane::one_second_loop()
!is_equal(G_Dt, scheduler.get_loop_period_s())) {
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
}
const float loop_rate = AP::scheduler().get_filtered_loop_rate_hz();
#if HAL_QUADPLANE_ENABLED
if (quadplane.available()) {
quadplane.attitude_control->set_notch_sample_rate(loop_rate);
}
#endif
rollController.set_notch_sample_rate(loop_rate);
pitchController.set_notch_sample_rate(loop_rate);
yawController.set_notch_sample_rate(loop_rate);
}
void Plane::three_hz_loop()