if the user arms within 30s of startup then stop the re-init of the
sensors. This can give less accurate frequency as the sample rate may
not have settled yet, but it is better than doing init of the filters
while the vehicle may be flying
also fix a 32 bit millis wrap
when doing the init() we must use the reference frequency, not the
current frequency. Using the current frequency leaves us with an
incorrect value for Q. If the current frequency is below the reference
frequency (which shouldn't happen in 4.5, but has been seen in 4.3)
then the Q can be much too low and massive phase lag can happen.
The vulnerability in 4.5.x is that the current frequency could be well
above the reference frequency. For example, the user may be doing a
motor test at 30s after boot, which is when we stop the
sensors_converging() test, and thus is the last time we call
init(). In that case we can end up with a Q which is much larger than
the one that should come from INS_HNTCH_FREQ and INS_HNTCH_BW, and
thus end up with a filter that produces a lot less attenuation than is
desired, potentially leading to instability due to high noise.
There are other scenarios that can cause this - for example a motor
test of a fwd motor at 30s after boot, or a spurious FFT peak due to
someone knocking the aircraft, or the vibration of a IC engine.
If the Gyro/Accel ID is already in the registered list, do not try to add it again.
This stops an issue seen on a CubeOrangePlus BG3 where, during the very first boot after a parameter wipe, software incorrectly registers a fourth IMU.
The Fourth IMU is registered because the AUX IMU is the same DevID as the third ICM45686.
INS_TCAL_OPTIONS parameter description indicates a singular bit in a bitmask to persist Accels/TCAL parameters, however there are two separate bits for persistence.
this is for supporting external visual odomotry systems which need the
IMU data to correctly process image data
# Conflicts:
# libraries/AP_InertialSensor/AP_InertialSensor.cpp
we use the instance numbers during filter configuration to check if
fast sampling is enabled. We need to ensure these instance numbers
have been setup before the filtering functions get called
enable high-resolution support on all ICM4xxxx sensors
create INS_HIRES_SAMPLE mask
adjust high-resolution sampling for correct byte ordering and depth
correct high resolution scaling on 18bit ICM4xxxx IMUs
control highres via HAL_INS_HIGHRES_SAMPLE
these undocumented bits in register 0x4d control the "adaptive full
scale range" mode of the ICM42688. The feature is enabled by default
but has a bug where it gives "stuck" gyro values for short periods
(between 1ms and 2ms):, leading to a significant gyro bias at longer
time scales, enough to in some cases cause a vehicle to crash if it is
unable to switch to an alternative IMU
this fixes https://github.com/ArduPilot/ardupilot/issues/25025
the bad value is -32768 not 0xffff (which is -1)
-32768 badly corrupts the low-pass filter, and is what we see in logs
(a large negative spike on all 3 axes)
update to bug fix from:
https://github.com/ArduPilot/ardupilot/pull/23033
this error happens often enough that it is frustrating for users who
can't arm, which just encourages use of forced arming.
logs show this happening at a rate of once every few seconds, which
doesn't impact on the usability of the gyro (which is at 2kHz), but
does prevent arming with this error incremement