Tools: use new AP_PERIPH_EFI_ENABLED define

This commit is contained in:
Shiv Tyagi 2025-02-19 23:56:48 +05:30 committed by Peter Barker
parent 49755d6212
commit 82a0347657
7 changed files with 12 additions and 10 deletions

View File

@ -201,7 +201,7 @@ void AP_Periph_FW::init()
adsb_init(); adsb_init();
#endif #endif
#ifdef HAL_PERIPH_ENABLE_EFI #if AP_PERIPH_EFI_ENABLED
if (efi.enabled() && g.efi_port >= 0) { if (efi.enabled() && g.efi_port >= 0) {
auto *uart = hal.serial(g.efi_port); auto *uart = hal.serial(g.efi_port);
if (uart != nullptr) { if (uart != nullptr) {

View File

@ -192,7 +192,7 @@ public:
void prepare_reboot(); void prepare_reboot();
bool canfdout() const { return (g.can_fdmode == 1); } bool canfdout() const { return (g.can_fdmode == 1); }
#ifdef HAL_PERIPH_ENABLE_EFI #if AP_PERIPH_EFI_ENABLED
void can_efi_update(); void can_efi_update();
#endif #endif
@ -326,7 +326,7 @@ public:
void hwesc_telem_update(); void hwesc_telem_update();
#endif #endif
#ifdef HAL_PERIPH_ENABLE_EFI #if AP_PERIPH_EFI_ENABLED
AP_EFI efi; AP_EFI efi;
uint32_t efi_update_ms; uint32_t efi_update_ms;
#endif #endif
@ -446,7 +446,7 @@ public:
static const AP_Param::Info var_info[]; static const AP_Param::Info var_info[];
#ifdef HAL_PERIPH_ENABLE_EFI #if AP_PERIPH_EFI_ENABLED
uint32_t last_efi_update_ms; uint32_t last_efi_update_ms;
#endif #endif
#if AP_PERIPH_MAG_ENABLED #if AP_PERIPH_MAG_ENABLED

View File

@ -518,7 +518,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(node_stats, "STAT", AP_Stats), GOBJECT(node_stats, "STAT", AP_Stats),
#endif #endif
#ifdef HAL_PERIPH_ENABLE_EFI #if AP_PERIPH_EFI_ENABLED
// @Param: EFI_BAUDRATE // @Param: EFI_BAUDRATE
// @DisplayName: EFI serial baudrate // @DisplayName: EFI serial baudrate
// @Description: EFI serial baudrate. // @Description: EFI serial baudrate.

View File

@ -208,7 +208,7 @@ public:
AP_Int32 battery_hide_mask; AP_Int32 battery_hide_mask;
#endif #endif
#ifdef HAL_PERIPH_ENABLE_EFI #if AP_PERIPH_EFI_ENABLED
AP_Int32 efi_baudrate; AP_Int32 efi_baudrate;
AP_Int8 efi_port; AP_Int8 efi_port;
#endif #endif

View File

@ -1960,7 +1960,7 @@ void AP_Periph_FW::can_update()
#ifdef HAL_PERIPH_ENABLE_RC_OUT #ifdef HAL_PERIPH_ENABLE_RC_OUT
rcout_update(); rcout_update();
#endif #endif
#ifdef HAL_PERIPH_ENABLE_EFI #if AP_PERIPH_EFI_ENABLED
can_efi_update(); can_efi_update();
#endif #endif
#ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE #ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE

View File

@ -1,6 +1,6 @@
#include "AP_Periph.h" #include "AP_Periph.h"
#ifdef HAL_PERIPH_ENABLE_EFI #if AP_PERIPH_EFI_ENABLED
/* /*
EFI support EFI support
@ -204,4 +204,4 @@ void AP_Periph_FW::can_efi_update(void)
} }
} }
#endif // HAL_PERIPH_ENABLE_EFI #endif // AP_PERIPH_EFI_ENABLED

View File

@ -960,7 +960,7 @@ class sitl_periph_universal(sitl_periph):
AP_PERIPH_RANGEFINDER_ENABLED = 1, AP_PERIPH_RANGEFINDER_ENABLED = 1,
AP_PERIPH_BATTERY_ENABLED = 1, AP_PERIPH_BATTERY_ENABLED = 1,
AP_PERIPH_BATTERY_BALANCE_ENABLED = 0, AP_PERIPH_BATTERY_BALANCE_ENABLED = 0,
HAL_PERIPH_ENABLE_EFI = 1, AP_PERIPH_EFI_ENABLED = 1,
AP_PERIPH_RPM_ENABLED = 1, AP_PERIPH_RPM_ENABLED = 1,
AP_PERIPH_RPM_STREAM_ENABLED = 1, AP_PERIPH_RPM_STREAM_ENABLED = 1,
AP_RPM_STREAM_ENABLED = 1, AP_RPM_STREAM_ENABLED = 1,
@ -996,6 +996,7 @@ class sitl_periph_gps(sitl_periph):
AP_PERIPH_MAG_ENABLED = 0, AP_PERIPH_MAG_ENABLED = 0,
AP_PERIPH_BATTERY_BALANCE_ENABLED = 0, AP_PERIPH_BATTERY_BALANCE_ENABLED = 0,
AP_PERIPH_BARO_ENABLED = 0, AP_PERIPH_BARO_ENABLED = 0,
AP_PERIPH_EFI_ENABLED = 0,
AP_PERIPH_RANGEFINDER_ENABLED = 0, AP_PERIPH_RANGEFINDER_ENABLED = 0,
AP_PERIPH_RTC_ENABLED = 0, AP_PERIPH_RTC_ENABLED = 0,
AP_PERIPH_RCIN_ENABLED = 0, AP_PERIPH_RCIN_ENABLED = 0,
@ -1023,6 +1024,7 @@ class sitl_periph_battmon(sitl_periph):
AP_PERIPH_GPS_ENABLED = 0, AP_PERIPH_GPS_ENABLED = 0,
AP_PERIPH_IMU_ENABLED = 0, AP_PERIPH_IMU_ENABLED = 0,
AP_PERIPH_MAG_ENABLED = 0, AP_PERIPH_MAG_ENABLED = 0,
AP_PERIPH_EFI_ENABLED = 0,
AP_PERIPH_RTC_ENABLED = 0, AP_PERIPH_RTC_ENABLED = 0,
AP_PERIPH_RCIN_ENABLED = 0, AP_PERIPH_RCIN_ENABLED = 0,
AP_PERIPH_RPM_ENABLED = 0, AP_PERIPH_RPM_ENABLED = 0,