diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index a9051cb490..35c5d26132 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -201,7 +201,7 @@ void AP_Periph_FW::init() adsb_init(); #endif -#ifdef HAL_PERIPH_ENABLE_EFI +#if AP_PERIPH_EFI_ENABLED if (efi.enabled() && g.efi_port >= 0) { auto *uart = hal.serial(g.efi_port); if (uart != nullptr) { diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index cca40c94c7..5c3461748c 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -192,7 +192,7 @@ public: void prepare_reboot(); bool canfdout() const { return (g.can_fdmode == 1); } -#ifdef HAL_PERIPH_ENABLE_EFI +#if AP_PERIPH_EFI_ENABLED void can_efi_update(); #endif @@ -326,7 +326,7 @@ public: void hwesc_telem_update(); #endif -#ifdef HAL_PERIPH_ENABLE_EFI +#if AP_PERIPH_EFI_ENABLED AP_EFI efi; uint32_t efi_update_ms; #endif @@ -446,7 +446,7 @@ public: static const AP_Param::Info var_info[]; -#ifdef HAL_PERIPH_ENABLE_EFI +#if AP_PERIPH_EFI_ENABLED uint32_t last_efi_update_ms; #endif #if AP_PERIPH_MAG_ENABLED diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 77e9685072..b0ba876069 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -518,7 +518,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GOBJECT(node_stats, "STAT", AP_Stats), #endif -#ifdef HAL_PERIPH_ENABLE_EFI +#if AP_PERIPH_EFI_ENABLED // @Param: EFI_BAUDRATE // @DisplayName: EFI serial baudrate // @Description: EFI serial baudrate. diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 643247dd5d..ad548783a3 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -208,7 +208,7 @@ public: AP_Int32 battery_hide_mask; #endif -#ifdef HAL_PERIPH_ENABLE_EFI +#if AP_PERIPH_EFI_ENABLED AP_Int32 efi_baudrate; AP_Int8 efi_port; #endif diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index a4234131a3..5e0495c085 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -1960,7 +1960,7 @@ void AP_Periph_FW::can_update() #ifdef HAL_PERIPH_ENABLE_RC_OUT rcout_update(); #endif - #ifdef HAL_PERIPH_ENABLE_EFI + #if AP_PERIPH_EFI_ENABLED can_efi_update(); #endif #ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE diff --git a/Tools/AP_Periph/efi.cpp b/Tools/AP_Periph/efi.cpp index 84d0eb3ffb..9722c3405c 100644 --- a/Tools/AP_Periph/efi.cpp +++ b/Tools/AP_Periph/efi.cpp @@ -1,6 +1,6 @@ #include "AP_Periph.h" -#ifdef HAL_PERIPH_ENABLE_EFI +#if AP_PERIPH_EFI_ENABLED /* EFI support @@ -204,4 +204,4 @@ void AP_Periph_FW::can_efi_update(void) } } -#endif // HAL_PERIPH_ENABLE_EFI +#endif // AP_PERIPH_EFI_ENABLED diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index f6acaee2e1..85d2b932a3 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -960,7 +960,7 @@ class sitl_periph_universal(sitl_periph): AP_PERIPH_RANGEFINDER_ENABLED = 1, AP_PERIPH_BATTERY_ENABLED = 1, AP_PERIPH_BATTERY_BALANCE_ENABLED = 0, - HAL_PERIPH_ENABLE_EFI = 1, + AP_PERIPH_EFI_ENABLED = 1, AP_PERIPH_RPM_ENABLED = 1, AP_PERIPH_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_BATTERY_BALANCE_ENABLED = 0, AP_PERIPH_BARO_ENABLED = 0, + AP_PERIPH_EFI_ENABLED = 0, AP_PERIPH_RANGEFINDER_ENABLED = 0, AP_PERIPH_RTC_ENABLED = 0, AP_PERIPH_RCIN_ENABLED = 0, @@ -1023,6 +1024,7 @@ class sitl_periph_battmon(sitl_periph): AP_PERIPH_GPS_ENABLED = 0, AP_PERIPH_IMU_ENABLED = 0, AP_PERIPH_MAG_ENABLED = 0, + AP_PERIPH_EFI_ENABLED = 0, AP_PERIPH_RTC_ENABLED = 0, AP_PERIPH_RCIN_ENABLED = 0, AP_PERIPH_RPM_ENABLED = 0,