From d45526ff426db4bd4208e172f9a110185a920886 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Mon, 30 Aug 2021 00:29:49 -0700 Subject: [PATCH] AP_Compass: fix periph-heavy compile errors with different things enabled --- libraries/AP_Compass/AP_Compass_AK09916.cpp | 6 ++++++ libraries/AP_Compass/AP_Compass_AK8963.cpp | 9 +++++++++ libraries/AP_Compass/AP_Compass_HMC5843.cpp | 2 ++ 3 files changed, 17 insertions(+) diff --git a/libraries/AP_Compass/AP_Compass_AK09916.cpp b/libraries/AP_Compass/AP_Compass_AK09916.cpp index 542f48869b..74f4e93453 100644 --- a/libraries/AP_Compass/AP_Compass_AK09916.cpp +++ b/libraries/AP_Compass/AP_Compass_AK09916.cpp @@ -170,6 +170,7 @@ fail: AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(uint8_t inv2_instance, enum Rotation rotation) { +#if HAL_INS_ENABLED AP_InertialSensor &ins = AP::ins(); AP_AK09916_BusDriver *bus = @@ -185,6 +186,9 @@ AP_Compass_Backend *AP_Compass_AK09916::probe_ICM20948(uint8_t inv2_instance, } return sensor; +#else + return nullptr; +#endif } bool AP_Compass_AK09916::init() @@ -368,12 +372,14 @@ AP_AK09916_BusDriver_Auxiliary::AP_AK09916_BusDriver_Auxiliary(AP_InertialSensor * Only initialize members. Fails are handled by configure or while * getting the semaphore */ +#if HAL_INS_ENABLED _bus = ins.get_auxiliary_bus(backend_id, backend_instance); if (!_bus) { return; } _slave = _bus->request_next_slave(addr); +#endif } AP_AK09916_BusDriver_Auxiliary::~AP_AK09916_BusDriver_Auxiliary() diff --git a/libraries/AP_Compass/AP_Compass_AK8963.cpp b/libraries/AP_Compass/AP_Compass_AK8963.cpp index f6d88ef885..d78f9220f5 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.cpp +++ b/libraries/AP_Compass/AP_Compass_AK8963.cpp @@ -90,10 +90,12 @@ AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(AP_HAL::OwnPtrrequest_next_slave(addr); +#endif } AP_AK8963_BusDriver_Auxiliary::~AP_AK8963_BusDriver_Auxiliary() diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index 189453122e..f17f5675e1 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -498,12 +498,14 @@ AP_HMC5843_BusDriver_Auxiliary::AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor * Only initialize members. Fails are handled by configure or while * getting the semaphore */ +#if HAL_INS_ENABLED _bus = ins.get_auxiliary_bus(backend_id); if (!_bus) { return; } _slave = _bus->request_next_slave(addr); +#endif } AP_HMC5843_BusDriver_Auxiliary::~AP_HMC5843_BusDriver_Auxiliary()