diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index 0fb02eae9b..ae71df9c0a 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -76,12 +76,20 @@ public: // get the index of the current primary accelerometer sensor virtual uint8_t get_primary_accel_index(void) const { +#if AP_INERTIALSENSOR_ENABLED return AP::ins().get_primary_accel(); +#else + return 0; +#endif } // get the index of the current primary gyro sensor virtual uint8_t get_primary_gyro_index(void) const { +#if AP_INERTIALSENSOR_ENABLED return AP::ins().get_primary_gyro(); +#else + return 0; +#endif } // Methods diff --git a/libraries/AP_AHRS/AP_AHRS_config.h b/libraries/AP_AHRS/AP_AHRS_config.h index 559d0403b0..7338a02787 100644 --- a/libraries/AP_AHRS/AP_AHRS_config.h +++ b/libraries/AP_AHRS/AP_AHRS_config.h @@ -21,11 +21,11 @@ #endif #ifndef HAL_NAVEKF3_AVAILABLE -#define HAL_NAVEKF3_AVAILABLE 1 +#define HAL_NAVEKF3_AVAILABLE AP_INERTIALSENSOR_ENABLED #endif #ifndef AP_AHRS_SIM_ENABLED -#define AP_AHRS_SIM_ENABLED AP_SIM_ENABLED +#define AP_AHRS_SIM_ENABLED AP_SIM_ENABLED && AP_INERTIALSENSOR_ENABLED #endif #ifndef AP_AHRS_POSITION_RESET_ENABLED