ArduCopter: use AP_BEACON_ENABLED instead of BEACON_ENABLED

This commit is contained in:
Peter Barker 2023-04-09 17:39:19 +10:00 committed by Peter Barker
parent aab771d380
commit 3eae095966
7 changed files with 8 additions and 16 deletions

View File

@ -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

View File

@ -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
}

View File

@ -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 <AP_Beacon/AP_Beacon_config.h>
#if AP_BEACON_ENABLED
#include <AP_Beacon/AP_Beacon.h>
#endif

View File

@ -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

View File

@ -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

View File

@ -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
//////////////////////////////////////////////////////////////////////////////

View File

@ -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