diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 73f68f2cde..87acfa7309 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -92,7 +92,7 @@ void AP_Periph_FW::init() stm32_watchdog_pat(); -#ifdef HAL_NO_GCS +#if !HAL_GCS_ENABLED hal.serial(0)->begin(AP_SERIALMANAGER_CONSOLE_BAUD, 32, 32); #endif hal.serial(3)->begin(115200, 128, 256); @@ -103,13 +103,13 @@ void AP_Periph_FW::init() can_start(); -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED stm32_watchdog_pat(); gcs().init(); #endif serial_manager.init(); -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED gcs().setup_console(); gcs().send_text(MAV_SEVERITY_INFO, "AP_Periph GCS Initialised!"); #endif @@ -347,7 +347,7 @@ void AP_Periph_FW::update() rcout_init_1Hz(); #endif -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED gcs().send_message(MSG_HEARTBEAT); gcs().send_message(MSG_SYS_STATUS); #endif @@ -384,7 +384,7 @@ void AP_Periph_FW::update() #ifdef HAL_PERIPH_ENABLE_NOTIFY notify.update(); #endif -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED gcs().update_receive(); gcs().update_send(); #endif diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 0b685b998a..4bc39d3444 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -23,7 +23,7 @@ #include #endif -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED #include "GCS_MAVLink.h" #endif @@ -219,7 +219,7 @@ public: AP_Logger logger; #endif -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED GCS_Periph _gcs; #endif // setup the var_info table diff --git a/Tools/AP_Periph/GCS_MAVLink.cpp b/Tools/AP_Periph/GCS_MAVLink.cpp index ae911f25be..70bd4e5f0a 100644 --- a/Tools/AP_Periph/GCS_MAVLink.cpp +++ b/Tools/AP_Periph/GCS_MAVLink.cpp @@ -16,7 +16,7 @@ #include "GCS_MAVLink.h" #include "AP_Periph.h" -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED static const ap_message STREAM_RAW_SENSORS_msgs[] = { MSG_RAW_IMU @@ -75,4 +75,4 @@ MAV_RESULT GCS_MAVLINK_Periph::handle_preflight_reboot(const mavlink_command_lon #endif } -#endif // #ifndef HAL_NO_GCS +#endif // #if HAL_GCS_ENABLED diff --git a/Tools/AP_Periph/GCS_MAVLink.h b/Tools/AP_Periph/GCS_MAVLink.h index 8b3305e67c..4196d70010 100644 --- a/Tools/AP_Periph/GCS_MAVLink.h +++ b/Tools/AP_Periph/GCS_MAVLink.h @@ -15,7 +15,7 @@ #pragma once #include -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED /* * GCS backend used for many examples and tools @@ -89,4 +89,4 @@ private: MAV_TYPE frame_type() const override { return MAV_TYPE_GENERIC; } uint32_t custom_mode() const override { return 3; } // magic number }; -#endif // HAL_NO_GCS +#endif // HAL_GCS_ENABLED diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index a8674eafcc..3e3b078bcd 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -334,7 +334,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GSCALAR(log_bitmask, "LOG_BITMASK", 4), #endif -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED // @Param: SYSID_THISMAV // @DisplayName: MAVLink system ID of this vehicle // @Description: Allows setting an individual system id for this vehicle to distinguish it from others on the same network diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 65bff7d9d6..6af734ae65 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -114,7 +114,7 @@ public: AP_Int32 log_bitmask; #endif -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED AP_Int16 sysid_this_mav; #endif diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 83a4d2950f..7304b9fbd7 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -70,7 +70,7 @@ class Board: # allow GCS disable for AP_DAL example if cfg.options.no_gcs: - env.CXXFLAGS += ['-DHAL_NO_GCS=1'] + env.CXXFLAGS += ['-DHAL_GCS_ENABLED=0'] # setup for supporting onvif cam control if cfg.options.enable_onvif: @@ -626,7 +626,7 @@ class sitl_periph_gps(sitl): HAL_CAN_DEFAULT_NODE_ID = 0, HAL_RAM_RESERVE_START = 0, APJ_BOARD_ID = 100, - HAL_NO_GCS = 1, + HAL_GCS_ENABLED = 0, HAL_LOGGING_ENABLED = 0, HAL_LOGGING_MAVLINK_ENABLED = 0, HAL_MISSION_ENABLED = 0,