this zeros the delta angle and delta velocity accumulators when a
sensor is unavailable for a period of 0.1s. This prevents garbage
values being passed into the EKF when a sensor dies and then becomes
available again some time later
https://github.com/ArduPilot/ardupilot/issues/11346
Allocate a notch filter per-IMU.
Update the notch filters in the backend at the sensor sample rate.
Allow raw logging of post-filtered gyro and accel values.
AP_InertialSensor: add parameters for push-to-log interval and count
AP_InertialSensor: rename BAT_RAW to BAT_OPT
This becomes a bitmask of options for the BatchSampler
AP_InertialSensor: rename 'fast sample' to 'sensorrate sample'
AP_InertialSensor: const sensor-rate filter method
AP_InertialSampler: remove hard-coding of sample rate multiplier
AP_InertialSensor: use parameter to enable/disable sensor-rate logging
AP_InertialSensor: use a parameter to control sensor-rate logging
AP_InertialSensor: allow backends to override sensor data multiplier
e.g. some accelerometers are sensitive over wider ranges than the default 16G
AP_Inertialsensor: correct sample rate multiplier
FIFO sensors produce data at a well known rate, but samples come in
bunches, so we can't use the system clock to calculate deltaT.
non-FIFO sensors produce data when we sample them, but that rate is
less regular due to timing jitter.
For FIFO sensors this changes makes us use a learned sample rate,
which allows for different clock speeds on sensor and system board.
For non-FIFO sensors we use the system clock to measure deltaT
the overall effect is a fix for sensors that produce samples at other
than the claimed datasheet rate.
this moves to using a 1p filter on the high rate data, followed by
averaging down to 1kHz then a 2p filter to apply configured cutoff
frequency.
It also fixes the FIFO reset to not cause data corruption. We need to
disable all FIFO channels before doing the reset, and wait for the
FIFO to stop in the sensor.
Finally it moves sampling of the MPU6000 and MPU9250 into the main
thread. That significantly improves scheduling performance as we no
longer get long FIFO SPI transfers happening during other tasks. All
transfers happen at the start of the fast loop. That makes timing much
more predictable.
Thanks to Leonard and Paul for help with this design!
We only leave the parameter there for backward-compatibility. However
product id on the inertial sensor is not much useful since it's only
kept for the first instance.
A better implementation per-gyro and per-accel is needed in order to
avoid problems with sensors taking the offsets configured for another
sensor.
RC_Channel: To nullptr from NULL.
AC_Fence: To nullptr from NULL.
AC_Avoidance: To nullptr from NULL.
AC_PrecLand: To nullptr from NULL.
DataFlash: To nullptr from NULL.
SITL: To nullptr from NULL.
GCS_MAVLink: To nullptr from NULL.
DataFlash: To nullptr from NULL.
AP_Compass: To nullptr from NULL.
Global: To nullptr from NULL.
Global: To nullptr from NULL.
new functions that get a filtered min/max accel peaks on each axis with fixed 500ms timeout:
Vector3f get_accel_peak_hold_pos()
Vector3f get_accel_peak_hold_neg()
This allows slower mechanisms, such as is_flying, to detect accel spikes which would indicate ground or object impacts. Vibe is too filtered. Independent positive and negative peaks are available
In order to avoid confusion between sample rate from sensor and sample rate
from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to
the former.
The changes in the code were basically done with the following commands:
git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g"
git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g"
git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g"
git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g"
git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g"
git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g"
And also with minor changes on indentation and comments.
Delta angle calculation is now unified, so there is no need for such a method.
That also avoids developers thinking they need that method being called
somewhere in their new drivers.
This commit basically moves delta angle calculation that was previously done in
AP_InertialSensor_PX4 to a common place. Instances must publish their gyro raw
sample rate to enable delta angle calculation.