From a147b97d2b710cb79ab0e6d538bafc772674ccc3 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Wed, 14 Oct 2015 10:59:40 -0300 Subject: [PATCH] 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. --- libraries/AP_InertialSensor/AP_InertialSensor.h | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 7bf4ccb6a0..93f9783893 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -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 #include