diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 3347fbb95e65a8..98c2f3892c1d35 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -144,7 +144,7 @@ void AP_Periph_FW::init() node_stats.init(); #endif -#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS +#if AP_PERIPH_SERIAL_OPTIONS_ENABLED serial_options.init(); #endif diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index c866147a14f09a..632624eaeb581d 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -384,7 +384,7 @@ class AP_Periph_FW { BattBalance battery_balance; #endif -#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS +#if AP_PERIPH_SERIAL_OPTIONS_ENABLED SerialOptions serial_options; #endif diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 991535c12deba8..8eaf37399f30b5 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -643,7 +643,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GOBJECT(battery_balance, "BAL", BattBalance), #endif -#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS +#if AP_PERIPH_SERIAL_OPTIONS_ENABLED // @Group: UART // @Path: serial_options.cpp GOBJECT(serial_options, "UART", SerialOptions), diff --git a/Tools/AP_Periph/serial_options.cpp b/Tools/AP_Periph/serial_options.cpp index cc480eee5b7f77..83deb1a6f5dbba 100644 --- a/Tools/AP_Periph/serial_options.cpp +++ b/Tools/AP_Periph/serial_options.cpp @@ -18,7 +18,7 @@ #include "AP_Periph.h" -#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS +#if AP_PERIPH_SERIAL_OPTIONS_ENABLED #include "serial_options.h" #include @@ -107,4 +107,4 @@ void SerialOptions::init(void) } } -#endif // HAL_PERIPH_ENABLE_SERIAL_OPTIONS +#endif // AP_PERIPH_SERIAL_OPTIONS_ENABLED diff --git a/Tools/AP_Periph/serial_options.h b/Tools/AP_Periph/serial_options.h index d71bdf43138117..8a93387fe89ee8 100644 --- a/Tools/AP_Periph/serial_options.h +++ b/Tools/AP_Periph/serial_options.h @@ -1,6 +1,6 @@ #pragma once -#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS +#if AP_PERIPH_SERIAL_OPTIONS_ENABLED #ifndef HAL_UART_NUM_SERIAL_PORTS #define HAL_UART_NUM_SERIAL_PORTS AP_HAL::HAL::num_serial @@ -27,4 +27,4 @@ class SerialOptions { }; -#endif // HAL_PERIPH_ENABLE_SERIAL_OPTIONS +#endif // AP_PERIPH_SERIAL_OPTIONS_ENABLED diff --git a/Tools/AP_Periph/serial_options_dev.cpp b/Tools/AP_Periph/serial_options_dev.cpp index 26ba2bb137453c..69ed85b2e38714 100644 --- a/Tools/AP_Periph/serial_options_dev.cpp +++ b/Tools/AP_Periph/serial_options_dev.cpp @@ -18,7 +18,7 @@ #include "AP_Periph.h" -#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS +#if AP_PERIPH_SERIAL_OPTIONS_ENABLED #include "serial_options.h" @@ -44,4 +44,4 @@ const AP_Param::GroupInfo SerialOptionsDev::var_info[] { AP_GROUPEND }; -#endif // HAL_PERIPH_ENABLE_SERIAL_OPTIONS +#endif // AP_PERIPH_SERIAL_OPTIONS_ENABLED diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index e96d39ec9571e9..88d464a1de8ccd 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -966,7 +966,7 @@ def configure_env(self, cfg, env): AP_RPM_STREAM_ENABLED = 1, HAL_PERIPH_ENABLE_RC_OUT = 1, AP_PERIPH_ADSB_ENABLED = 1, - HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1, + AP_PERIPH_SERIAL_OPTIONS_ENABLED = 1, AP_AIRSPEED_ENABLED = 1, AP_BATTERY_ESC_ENABLED = 1, HAL_PWM_COUNT = 32, @@ -991,6 +991,7 @@ def configure_env(self, cfg, env): APJ_BOARD_ID = 101, AP_PERIPH_BATTERY_ENABLED = 0, + AP_PERIPH_SERIAL_OPTIONS_ENABLED = 0, AP_PERIPH_ADSB_ENABLED = 0, AP_PERIPH_GPS_ENABLED = 1, AP_PERIPH_IMU_ENABLED = 0, @@ -1019,6 +1020,7 @@ def configure_env(self, cfg, env): APJ_BOARD_ID = 101, AP_PERIPH_BATTERY_ENABLED = 1, + AP_PERIPH_SERIAL_OPTIONS_ENABLED = 0, AP_PERIPH_BATTERY_BALANCE_ENABLED = 0, AP_PERIPH_ADSB_ENABLED = 0, AP_PERIPH_BARO_ENABLED = 0,