mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_InertialSensor: call init for harmonic notch params
This commit is contained in:
parent
b68ece1007
commit
e35a459090
@ -895,6 +895,11 @@ AP_InertialSensor::init(uint16_t loop_rate)
|
|||||||
// cause divergence of state estimators
|
// cause divergence of state estimators
|
||||||
_loop_delta_t_max = 10 * _loop_delta_t;
|
_loop_delta_t_max = 10 * _loop_delta_t;
|
||||||
|
|
||||||
|
// Initialize notch params
|
||||||
|
for (auto ¬ch : harmonic_notches) {
|
||||||
|
notch.params.init();
|
||||||
|
}
|
||||||
|
|
||||||
if (_gyro_count == 0 && _accel_count == 0) {
|
if (_gyro_count == 0 && _accel_count == 0) {
|
||||||
_start_backends();
|
_start_backends();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user