From 3eae09596660ee0fdebabdac3c492476762d316c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Apr 2023 17:39:19 +1000 Subject: [PATCH] ArduCopter: use AP_BEACON_ENABLED instead of BEACON_ENABLED --- ArduCopter/APM_Config.h | 1 - ArduCopter/Copter.cpp | 4 ++-- ArduCopter/Copter.h | 4 ++-- ArduCopter/Parameters.cpp | 4 ++-- ArduCopter/Parameters.h | 2 +- ArduCopter/config.h | 7 ------- ArduCopter/system.cpp | 2 +- 7 files changed, 8 insertions(+), 16 deletions(-) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index d9c8f7afdc..bdd901706b 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -9,7 +9,6 @@ //#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles //#define PARACHUTE DISABLED // disable parachute release to save 1k of flash //#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands -//#define BEACON_ENABLED DISABLED // disable beacon support //#define STATS_ENABLED DISABLED // disable statistics support //#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support //#define MODE_AUTO_ENABLED DISABLED // disable auto mode support diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index bb80d616ad..1241b5f9b2 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -165,7 +165,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if HAL_PROXIMITY_ENABLED SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50, 36), #endif -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED SCHED_TASK_CLASS(AP_Beacon, &copter.g2.beacon, update, 400, 50, 39), #endif SCHED_TASK(update_altitude, 10, 100, 42), @@ -550,7 +550,7 @@ void Copter::ten_hz_logging_loop() #if HAL_PROXIMITY_ENABLED g2.proximity.log(); // Write proximity sensor distances #endif -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED g2.beacon.log(); #endif } diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 425e419cfc..bde520ce01 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -100,8 +100,8 @@ #include "AP_Rally.h" // Rally point library #include "AP_Arming.h" -// libraries which are dependent on #defines in defines.h and/or config.h -#if BEACON_ENABLED == ENABLED +#include +#if AP_BEACON_ENABLED #include #endif diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 71ef92699f..579a1baa44 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -776,7 +776,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0), -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED // @Group: BCN // @Path: ../libraries/AP_Beacon/AP_Beacon.cpp AP_SUBGROUPINFO(beacon, "BCN", 14, ParametersG2, AP_Beacon), @@ -1225,7 +1225,7 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = { */ ParametersG2::ParametersG2(void) : temp_calibration() // this doesn't actually need constructing, but removing it here is problematic syntax-wise -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED , beacon() #endif #if HAL_PROXIMITY_ENABLED diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 22fcee3432..15f719224c 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -525,7 +525,7 @@ public: // temperature calibration handling AP_TempCalibration temp_calibration; -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED // beacon (non-GPS positioning) library AP_Beacon beacon; #endif diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 9900d7e39b..a260b6cba4 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -288,13 +288,6 @@ # define MODE_AUTOROTATE_ENABLED DISABLED #endif -////////////////////////////////////////////////////////////////////////////// - -// Beacon support - support for local positioning systems -#ifndef BEACON_ENABLED -# define BEACON_ENABLED !HAL_MINIMIZE_FEATURES -#endif - ////////////////////////////////////////////////////////////////////////////// // RADIO CONFIGURATION ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 499c552a58..4e1527e2fc 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -159,7 +159,7 @@ void Copter::init_ardupilot() g2.proximity.init(); #endif -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED // init beacons used for non-gps position estimation g2.beacon.init(); #endif