mirror of https://github.com/ArduPilot/ardupilot
Copter: update PID notch centers at 1Hz with average loop rate
This commit is contained in:
parent
bc03918ea4
commit
aad51b7066
|
@ -671,6 +671,13 @@ void Copter::one_hz_loop()
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_Notify::flags.flying = !ap.land_complete;
|
AP_Notify::flags.flying = !ap.land_complete;
|
||||||
|
|
||||||
|
// slowly update the PID notches with the average loop rate
|
||||||
|
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());
|
||||||
|
#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED
|
||||||
|
custom_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void Copter::init_simple_bearing()
|
void Copter::init_simple_bearing()
|
||||||
|
|
Loading…
Reference in New Issue