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:
Lucas De Marchi 2015-10-14 10:59:40 -03:00 committed by Andrew Tridgell
parent 4480956c68
commit a147b97d2b

View File

@ -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>