AP_InertialSensor: Run vibration monitoring on all instances

This commit is contained in:
Michael du Breuil 2020-10-03 20:18:30 -07:00 committed by Peter Barker
parent 284fb53f75
commit c86dcf91d6
1 changed files with 9 additions and 1 deletions

View File

@ -7,6 +7,8 @@
#define AP_INERTIAL_SENSOR_ACCEL_VIBE_FILT_HZ 2.0f // accel vibration filter hz #define AP_INERTIAL_SENSOR_ACCEL_VIBE_FILT_HZ 2.0f // accel vibration filter hz
#define AP_INERTIAL_SENSOR_ACCEL_PEAK_DETECT_TIMEOUT_MS 500 // peak-hold detector timeout #define AP_INERTIAL_SENSOR_ACCEL_PEAK_DETECT_TIMEOUT_MS 500 // peak-hold detector timeout
#include <AP_HAL/AP_HAL.h>
/** /**
maximum number of INS instances available on this platform. If more maximum number of INS instances available on this platform. If more
than 1 then redundant sensors may be available than 1 then redundant sensors may be available
@ -14,7 +16,13 @@
#define INS_MAX_INSTANCES 3 #define INS_MAX_INSTANCES 3
#define INS_MAX_BACKENDS 6 #define INS_MAX_BACKENDS 6
#define INS_MAX_NOTCHES 4 #define INS_MAX_NOTCHES 4
#define INS_VIBRATION_CHECK_INSTANCES 2 #ifndef INS_VIBRATION_CHECK_INSTANCES
#if HAL_MEM_CLASS >= HAL_MEM_CLASS_300
#define INS_VIBRATION_CHECK_INSTANCES INS_MAX_INSTANCES
#else
#define INS_VIBRATION_CHECK_INSTANCES 1
#endif
#endif
#define XYZ_AXIS_COUNT 3 #define XYZ_AXIS_COUNT 3
// The maximum we need to store is gyro-rate / loop-rate, worst case ArduCopter with BMI088 is 2000/400 // The maximum we need to store is gyro-rate / loop-rate, worst case ArduCopter with BMI088 is 2000/400
#define INS_MAX_GYRO_WINDOW_SAMPLES 8 #define INS_MAX_GYRO_WINDOW_SAMPLES 8