diff --git a/libraries/AP_EFI/AP_EFI_Backend.h b/libraries/AP_EFI/AP_EFI_Backend.h index e3db976dbf578..fa5e180259aa3 100644 --- a/libraries/AP_EFI/AP_EFI_Backend.h +++ b/libraries/AP_EFI/AP_EFI_Backend.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_EFI_config.h" + +#if HAL_EFI_ENABLED + #include "AP_EFI.h" #include "AP_EFI_State.h" #include @@ -60,3 +64,4 @@ class AP_EFI_Backend { private: AP_EFI &frontend; }; +#endif // HAL_EFI_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp index 50388c1508084..21d374250f5d9 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp @@ -1,5 +1,7 @@ #include +#include "AP_EFI_config.h" +#if HAL_EFI_ENABLED #include "AP_EFI_DroneCAN.h" #if HAL_EFI_DRONECAN_ENABLED @@ -166,4 +168,4 @@ void AP_EFI_DroneCAN::handle_status(const uavcan::equipment::ice::reciprocating: } #endif // HAL_EFI_DRONECAN_ENABLED - +#endif // HAL_EFI_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp b/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp index 84637996cadff..723d73b38c0fa 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp @@ -17,7 +17,7 @@ #include "AP_EFI_config.h" -#if AP_EFI_SERIAL_HIRTH_ENABLED +#if HAL_EFI_ENABLED && AP_EFI_SERIAL_HIRTH_ENABLED #include #include #include @@ -387,4 +387,4 @@ void AP_EFI_Serial_Hirth::log_status(void) } #endif // HAL_LOGGING_ENABLED -#endif // AP_EFI_SERIAL_HIRTH_ENABLED +#endif // HAL_EFI_ENABLED && AP_EFI_SERIAL_HIRTH_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_Serial_Lutan.h b/libraries/AP_EFI/AP_EFI_Serial_Lutan.h index 51832d65b6a99..e16a7128306be 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_Lutan.h +++ b/libraries/AP_EFI/AP_EFI_Serial_Lutan.h @@ -17,6 +17,10 @@ */ #pragma once +#include "AP_EFI_config.h" + +#if HAL_EFI_ENABLED + #include "AP_EFI.h" #include "AP_EFI_Backend.h" @@ -81,3 +85,5 @@ class AP_EFI_Serial_Lutan: public AP_EFI_Backend { uint32_t last_request_ms; uint32_t last_recv_ms; }; + +#endif // HAL_EFI_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_Serial_MS.h b/libraries/AP_EFI/AP_EFI_Serial_MS.h index f72701d3b664a..4454a7fcc3e23 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_MS.h +++ b/libraries/AP_EFI/AP_EFI_Serial_MS.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_EFI_config.h" + +#if HAL_EFI_ENABLED + #include "AP_EFI.h" #include "AP_EFI_Backend.h" @@ -108,3 +112,5 @@ class AP_EFI_Serial_MS: public AP_EFI_Backend { RT_LAST_OFFSET = FUEL_PRESSURE_LSB }; }; + +#endif // HAL_EFI_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_ThrottleLinearisation.cpp b/libraries/AP_EFI/AP_EFI_ThrottleLinearisation.cpp index 5b63474672fda..c4aec96beecdf 100644 --- a/libraries/AP_EFI/AP_EFI_ThrottleLinearisation.cpp +++ b/libraries/AP_EFI/AP_EFI_ThrottleLinearisation.cpp @@ -1,6 +1,6 @@ #include "AP_EFI_config.h" -#if AP_EFI_THROTTLE_LINEARISATION_ENABLED +#if HAL_EFI_ENABLED && AP_EFI_THROTTLE_LINEARISATION_ENABLED #include "AP_EFI.h" #include @@ -70,5 +70,5 @@ float AP_EFI_ThrLin::linearise_throttle(float throttle_percent) return ret; } -#endif // AP_EFI_THROTTLE_LINEARISATION_ENABLED +#endif // HAL_EFI_ENABLED && AP_EFI_THROTTLE_LINEARISATION_ENABLED