|
|
|
@ -226,6 +226,12 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance,
@@ -226,6 +226,12 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance,
|
|
|
|
|
|
|
|
|
|
// apply the low pass filter
|
|
|
|
|
_imu._gyro_filtered[instance] = _imu._gyro_filter[instance].apply(gyro); |
|
|
|
|
|
|
|
|
|
// apply the harmonic notch filter
|
|
|
|
|
if (_gyro_harmonic_notch_enabled()) { |
|
|
|
|
_imu._gyro_filtered[instance] = _imu._gyro_harmonic_notch_filter[instance].apply(_imu._gyro_filtered[instance]); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// apply the notch filter
|
|
|
|
|
if (_gyro_notch_enabled()) { |
|
|
|
|
_imu._gyro_filtered[instance] = _imu._gyro_notch_filter[instance].apply(_imu._gyro_filtered[instance]); |
|
|
|
@ -233,6 +239,7 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance,
@@ -233,6 +239,7 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance,
|
|
|
|
|
if (_imu._gyro_filtered[instance].is_nan() || _imu._gyro_filtered[instance].is_inf()) { |
|
|
|
|
_imu._gyro_filter[instance].reset(); |
|
|
|
|
_imu._gyro_notch_filter[instance].reset(); |
|
|
|
|
_imu._gyro_harmonic_notch_filter[instance].reset(); |
|
|
|
|
} |
|
|
|
|
_imu._new_gyro_data[instance] = true; |
|
|
|
|
} |
|
|
|
@ -493,18 +500,31 @@ void AP_InertialSensor_Backend::update_gyro(uint8_t instance)
@@ -493,18 +500,31 @@ void AP_InertialSensor_Backend::update_gyro(uint8_t instance)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// possibly update filter frequency
|
|
|
|
|
if (_last_gyro_filter_hz[instance] != _gyro_filter_cutoff()) { |
|
|
|
|
if (_last_gyro_filter_hz != _gyro_filter_cutoff()) { |
|
|
|
|
_imu._gyro_filter[instance].set_cutoff_frequency(_gyro_raw_sample_rate(instance), _gyro_filter_cutoff()); |
|
|
|
|
_last_gyro_filter_hz[instance] = _gyro_filter_cutoff(); |
|
|
|
|
_last_gyro_filter_hz = _gyro_filter_cutoff(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// possily update the harmonic notch filter parameters
|
|
|
|
|
if (!is_equal(_last_harmonic_notch_bandwidth_hz, _gyro_harmonic_notch_bandwidth_hz()) || |
|
|
|
|
!is_equal(_last_harmonic_notch_attenuation_dB, _gyro_harmonic_notch_attenuation_dB())) { |
|
|
|
|
_imu._gyro_harmonic_notch_filter[instance].init(_gyro_raw_sample_rate(instance), _gyro_harmonic_notch_center_freq_hz(), _gyro_harmonic_notch_bandwidth_hz(), _gyro_harmonic_notch_attenuation_dB()); |
|
|
|
|
_last_harmonic_notch_center_freq_hz = _gyro_harmonic_notch_center_freq_hz(); |
|
|
|
|
_last_harmonic_notch_bandwidth_hz = _gyro_harmonic_notch_bandwidth_hz(); |
|
|
|
|
_last_harmonic_notch_attenuation_dB = _gyro_harmonic_notch_attenuation_dB(); |
|
|
|
|
} |
|
|
|
|
else if (!is_equal(_last_harmonic_notch_center_freq_hz, _gyro_harmonic_notch_center_freq_hz())) { |
|
|
|
|
_imu._gyro_harmonic_notch_filter[instance].update(_gyro_harmonic_notch_center_freq_hz()); |
|
|
|
|
_last_harmonic_notch_center_freq_hz = _gyro_harmonic_notch_center_freq_hz(); |
|
|
|
|
} |
|
|
|
|
// possily update the notch filter parameters
|
|
|
|
|
if (_last_notch_center_freq_hz[instance] != _gyro_notch_center_freq_hz() || |
|
|
|
|
_last_notch_bandwidth_hz[instance] != _gyro_notch_bandwidth_hz() || |
|
|
|
|
!is_equal(_last_notch_attenuation_dB[instance], _gyro_notch_attenuation_dB())) { |
|
|
|
|
if (!is_equal(_last_notch_center_freq_hz, _gyro_notch_center_freq_hz()) || |
|
|
|
|
!is_equal(_last_notch_bandwidth_hz, _gyro_notch_bandwidth_hz()) || |
|
|
|
|
!is_equal(_last_notch_attenuation_dB, _gyro_notch_attenuation_dB())) { |
|
|
|
|
_imu._gyro_notch_filter[instance].init(_gyro_raw_sample_rate(instance), _gyro_notch_center_freq_hz(), _gyro_notch_bandwidth_hz(), _gyro_notch_attenuation_dB()); |
|
|
|
|
_last_notch_center_freq_hz[instance] = _gyro_notch_center_freq_hz(); |
|
|
|
|
_last_notch_bandwidth_hz[instance] = _gyro_notch_bandwidth_hz(); |
|
|
|
|
_last_notch_attenuation_dB[instance] = _gyro_notch_attenuation_dB(); |
|
|
|
|
_last_notch_center_freq_hz = _gyro_notch_center_freq_hz(); |
|
|
|
|
_last_notch_bandwidth_hz = _gyro_notch_bandwidth_hz(); |
|
|
|
|
_last_notch_attenuation_dB = _gyro_notch_attenuation_dB(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -524,9 +544,9 @@ void AP_InertialSensor_Backend::update_accel(uint8_t instance)
@@ -524,9 +544,9 @@ void AP_InertialSensor_Backend::update_accel(uint8_t instance)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// possibly update filter frequency
|
|
|
|
|
if (_last_accel_filter_hz[instance] != _accel_filter_cutoff()) { |
|
|
|
|
if (_last_accel_filter_hz != _accel_filter_cutoff()) { |
|
|
|
|
_imu._accel_filter[instance].set_cutoff_frequency(_accel_raw_sample_rate(instance), _accel_filter_cutoff()); |
|
|
|
|
_last_accel_filter_hz[instance] = _accel_filter_cutoff(); |
|
|
|
|
_last_accel_filter_hz = _accel_filter_cutoff(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|