Skip to content

Commit

Permalink
AP_EFI: fixed build on boards without EFI support
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Nov 17, 2023
1 parent 9c2c08f commit cfa37c7
Show file tree
Hide file tree
Showing 6 changed files with 24 additions and 5 deletions.
5 changes: 5 additions & 0 deletions libraries/AP_EFI/AP_EFI_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <AP_HAL/Semaphores.h>
Expand Down Expand Up @@ -60,3 +64,4 @@ class AP_EFI_Backend {
private:
AP_EFI &frontend;
};
#endif // HAL_EFI_ENABLED
4 changes: 3 additions & 1 deletion libraries/AP_EFI/AP_EFI_DroneCAN.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#include <AP_HAL/AP_HAL.h>
#include "AP_EFI_config.h"

#if HAL_EFI_ENABLED
#include "AP_EFI_DroneCAN.h"

#if HAL_EFI_DRONECAN_ENABLED
Expand Down Expand Up @@ -166,4 +168,4 @@ void AP_EFI_DroneCAN::handle_status(const uavcan::equipment::ice::reciprocating:
}

#endif // HAL_EFI_DRONECAN_ENABLED

#endif // HAL_EFI_ENABLED
4 changes: 2 additions & 2 deletions libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <AP_HAL/AP_HAL.h>
#include <AP_EFI/AP_EFI_Serial_Hirth.h>
#include <AP_SerialManager/AP_SerialManager.h>
Expand Down Expand Up @@ -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
6 changes: 6 additions & 0 deletions libraries/AP_EFI/AP_EFI_Serial_Lutan.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,10 @@
*/
#pragma once

#include "AP_EFI_config.h"

#if HAL_EFI_ENABLED

#include "AP_EFI.h"
#include "AP_EFI_Backend.h"

Expand Down Expand Up @@ -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
6 changes: 6 additions & 0 deletions libraries/AP_EFI/AP_EFI_Serial_MS.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,10 @@
*/
#pragma once

#include "AP_EFI_config.h"

#if HAL_EFI_ENABLED

#include "AP_EFI.h"
#include "AP_EFI_Backend.h"

Expand Down Expand Up @@ -108,3 +112,5 @@ class AP_EFI_Serial_MS: public AP_EFI_Backend {
RT_LAST_OFFSET = FUEL_PRESSURE_LSB
};
};

#endif // HAL_EFI_ENABLED
4 changes: 2 additions & 2 deletions libraries/AP_EFI/AP_EFI_ThrottleLinearisation.cpp
Original file line number Diff line number Diff line change
@@ -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 <AP_Param/AP_Param.h>
Expand Down Expand Up @@ -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

0 comments on commit cfa37c7

Please sign in to comment.