mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_InertialSensor: remove check for HAL_CPU_CLASS
We don't support HAL_CPU_CLASS <= HAL_CPU_CLASS_16 anymore. This makes INS_MAX_INSTANCES, INS_MAX_BACKENDS and INS_VIBRATION_CHECK constant for all supported boards.
This commit is contained in:
parent
4480956c68
commit
a147b97d2b
@ -12,19 +12,12 @@
|
||||
|
||||
/**
|
||||
maximum number of INS instances available on this platform. If more
|
||||
than 1 then redundent sensors may be available
|
||||
than 1 then redundant sensors may be available
|
||||
*/
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
#define INS_MAX_INSTANCES 3
|
||||
#define INS_MAX_BACKENDS 6
|
||||
#define INS_VIBRATION_CHECK 1
|
||||
#define INS_VIBRATION_CHECK_INSTANCES 2
|
||||
#else
|
||||
#define INS_MAX_INSTANCES 1
|
||||
#define INS_MAX_BACKENDS 1
|
||||
#define INS_VIBRATION_CHECK 0
|
||||
#endif
|
||||
|
||||
|
||||
#include <stdint.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
Loading…
Reference in New Issue
Block a user