AP_AHRS: cope with AP_INERTIAL_SENSOR being 0

This commit is contained in:
Peter Barker 2023-07-12 15:40:32 +10:00 committed by Peter Barker
parent eec43c204f
commit 1e41030167
2 changed files with 10 additions and 2 deletions

View File

@ -76,12 +76,20 @@ public:
// get the index of the current primary accelerometer sensor // get the index of the current primary accelerometer sensor
virtual uint8_t get_primary_accel_index(void) const { virtual uint8_t get_primary_accel_index(void) const {
#if AP_INERTIALSENSOR_ENABLED
return AP::ins().get_primary_accel(); return AP::ins().get_primary_accel();
#else
return 0;
#endif
} }
// get the index of the current primary gyro sensor // get the index of the current primary gyro sensor
virtual uint8_t get_primary_gyro_index(void) const { virtual uint8_t get_primary_gyro_index(void) const {
#if AP_INERTIALSENSOR_ENABLED
return AP::ins().get_primary_gyro(); return AP::ins().get_primary_gyro();
#else
return 0;
#endif
} }
// Methods // Methods

View File

@ -21,11 +21,11 @@
#endif #endif
#ifndef HAL_NAVEKF3_AVAILABLE #ifndef HAL_NAVEKF3_AVAILABLE
#define HAL_NAVEKF3_AVAILABLE 1 #define HAL_NAVEKF3_AVAILABLE AP_INERTIALSENSOR_ENABLED
#endif #endif
#ifndef AP_AHRS_SIM_ENABLED #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 #endif
#ifndef AP_AHRS_POSITION_RESET_ENABLED #ifndef AP_AHRS_POSITION_RESET_ENABLED