From 227b6780b27ea04d14d3b7b6b7cda0773b40b747 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 5 Aug 2024 10:54:28 +1000 Subject: [PATCH] Rover: remove ENABLE/DISABLE defines --- Rover/Parameters.cpp | 8 ++++---- Rover/Parameters.h | 4 ++-- Rover/RC_Channel.cpp | 2 +- Rover/Rover.cpp | 2 +- Rover/Rover.h | 14 +++++++------- Rover/afs_rover.cpp | 2 +- Rover/afs_rover.h | 2 +- Rover/config.h | 4 ++-- Rover/defines.h | 8 -------- Rover/failsafe.cpp | 6 +++--- Rover/mode.cpp | 4 ++-- Rover/mode.h | 6 +++--- Rover/mode_dock.cpp | 2 +- Rover/system.cpp | 4 ++-- 14 files changed, 30 insertions(+), 38 deletions(-) diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 0c740105e5..0eb2480343 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -418,7 +418,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h AP_SUBGROUPINFO(rc_channels, "RC", 4, ParametersG2, RC_Channels_Rover), -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED // @Group: AFS_ // @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe), @@ -667,7 +667,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("MANUAL_OPTIONS", 53, ParametersG2, manual_options, 0), -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED // @Group: DOCK // @Path: mode_dock.cpp AP_SUBGROUPPTR(mode_dock_ptr, "DOCK", 54, ParametersG2, ModeDock), @@ -729,7 +729,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { ParametersG2::ParametersG2(void) : -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED afs(), #endif #if AP_BEACON_ENABLED @@ -739,7 +739,7 @@ ParametersG2::ParametersG2(void) wheel_rate_control(wheel_encoder), attitude_control(), smart_rtl(), -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED mode_dock_ptr(&rover.mode_dock), #endif #if HAL_PROXIMITY_ENABLED diff --git a/Rover/Parameters.h b/Rover/Parameters.h index e2d8d9849c..8a19324bfa 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -301,7 +301,7 @@ public: // control over servo output ranges SRV_Channels servo_channels; -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED // advanced failsafe library AP_AdvancedFailsafe_Rover afs; #endif @@ -340,7 +340,7 @@ public: AP_Proximity proximity; #endif -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED // we need a pointer to the mode for the G2 table class ModeDock *mode_dock_ptr; #endif diff --git a/Rover/RC_Channel.cpp b/Rover/RC_Channel.cpp index 4e17ec7769..75cd088a75 100644 --- a/Rover/RC_Channel.cpp +++ b/Rover/RC_Channel.cpp @@ -215,7 +215,7 @@ bool RC_Channel_Rover::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch do_aux_function_change_mode(rover.mode_loiter, ch_flag); break; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED // Set mode to Follow case AUX_FUNC::FOLLOW: do_aux_function_change_mode(rover.mode_follow, ch_flag); diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index 7392ae6223..a8fc94074d 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -134,7 +134,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { #endif SCHED_TASK(crash_check, 10, 200, 123), SCHED_TASK(cruise_learn_update, 50, 200, 126), -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED SCHED_TASK(afs_fs_check, 10, 200, 129), #endif }; diff --git a/Rover/Rover.h b/Rover/Rover.h index 2537f80e8f..93c7c5c64c 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -60,7 +60,7 @@ // Local modules #include "AP_Arming.h" #include "sailboat.h" -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED #include "afs_rover.h" #endif #include "Parameters.h" @@ -81,7 +81,7 @@ public: friend class ParametersG2; friend class AP_Rally_Rover; friend class AP_Arming_Rover; -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED friend class AP_AdvancedFailsafe_Rover; #endif #if AP_EXTERNAL_CONTROL_ENABLED @@ -99,11 +99,11 @@ public: friend class ModeManual; friend class ModeRTL; friend class ModeSmartRTL; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED friend class ModeFollow; #endif friend class ModeSimple; -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED friend class ModeDock; #endif @@ -253,11 +253,11 @@ private: ModeSteering mode_steering; ModeRTL mode_rtl; ModeSmartRTL mode_smartrtl; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED ModeFollow mode_follow; #endif ModeSimple mode_simple; -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED ModeDock mode_dock; #endif @@ -322,7 +322,7 @@ private: // failsafe.cpp void failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool on); void handle_battery_failsafe(const char* type_str, const int8_t action); -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED void afs_fs_check(void); #endif diff --git a/Rover/afs_rover.cpp b/Rover/afs_rover.cpp index 4265a20887..60625ed8de 100644 --- a/Rover/afs_rover.cpp +++ b/Rover/afs_rover.cpp @@ -4,7 +4,7 @@ #include "Rover.h" -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED /* Setup radio_out values for all channels to termination values diff --git a/Rover/afs_rover.h b/Rover/afs_rover.h index aa3473ddc3..f8b291eeda 100644 --- a/Rover/afs_rover.h +++ b/Rover/afs_rover.h @@ -18,7 +18,7 @@ advanced failsafe support for rover */ -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED #include /* diff --git a/Rover/config.h b/Rover/config.h index f1f07a71f0..7685a875b8 100644 --- a/Rover/config.h +++ b/Rover/config.h @@ -72,6 +72,6 @@ #define RESET_SWITCH_CHAN_PWM 1750 #endif -#ifndef ADVANCED_FAILSAFE - #define ADVANCED_FAILSAFE DISABLED +#ifndef AP_ROVER_ADVANCED_FAILSAFE_ENABLED + #define AP_ROVER_ADVANCED_FAILSAFE_ENABLED 0 #endif diff --git a/Rover/defines.h b/Rover/defines.h index 5fd45c2a2c..150afba023 100644 --- a/Rover/defines.h +++ b/Rover/defines.h @@ -3,14 +3,6 @@ // Internal defines, don't edit and expect things to work // ------------------------------------------------------- -// Just so that it's completely clear... -#define ENABLED 1 -#define DISABLED 0 - -// this avoids a very common config error -#define ENABLE ENABLED -#define DISABLE DISABLED - #define SERVO_MAX 4500.0 // This value represents 45 degrees and is just an arbitrary representation of servo max travel. // types of failsafe events diff --git a/Rover/failsafe.cpp b/Rover/failsafe.cpp index 76aec3c27a..3aabdfbacf 100644 --- a/Rover/failsafe.cpp +++ b/Rover/failsafe.cpp @@ -133,18 +133,18 @@ void Rover::handle_battery_failsafe(const char* type_str, const int8_t action) } break; case FailsafeAction::Terminate: -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED char battery_type_str[17]; snprintf(battery_type_str, 17, "%s battery", type_str); g2.afs.gcs_terminate(true, battery_type_str); #else arming.disarm(AP_Arming::Method::BATTERYFAILSAFE); -#endif // ADVANCED_FAILSAFE == ENABLED +#endif // AP_ROVER_ADVANCED_FAILSAFE_ENABLED break; } } -#if ADVANCED_FAILSAFE == ENABLED +#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED /* check for AFS failsafe check */ diff --git a/Rover/mode.cpp b/Rover/mode.cpp index b5800acb34..2b626ca4bb 100644 --- a/Rover/mode.cpp +++ b/Rover/mode.cpp @@ -531,7 +531,7 @@ Mode *Rover::mode_from_mode_num(const enum Mode::Number num) case Mode::Number::LOITER: ret = &mode_loiter; break; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED case Mode::Number::FOLLOW: ret = &mode_follow; break; @@ -557,7 +557,7 @@ Mode *Rover::mode_from_mode_num(const enum Mode::Number num) case Mode::Number::INITIALISING: ret = &mode_initializing; break; -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED case Mode::Number::DOCK: ret = (Mode *)g2.mode_dock_ptr; break; diff --git a/Rover/mode.h b/Rover/mode.h index f7eb932095..c338d8cea2 100644 --- a/Rover/mode.h +++ b/Rover/mode.h @@ -19,7 +19,7 @@ public: LOITER = 5, FOLLOW = 6, SIMPLE = 7, -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED DOCK = 8, #endif CIRCLE = 9, @@ -808,7 +808,7 @@ protected: bool _enter() override { return false; }; }; -#if MODE_FOLLOW_ENABLED == ENABLED +#if MODE_FOLLOW_ENABLED class ModeFollow : public Mode { public: @@ -868,7 +868,7 @@ private: float _desired_heading_cd; // latest desired heading (in centi-degrees) from pilot }; -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED class ModeDock : public Mode { public: diff --git a/Rover/mode_dock.cpp b/Rover/mode_dock.cpp index 89f8d89af7..09d727fce0 100644 --- a/Rover/mode_dock.cpp +++ b/Rover/mode_dock.cpp @@ -1,6 +1,6 @@ #include "Rover.h" -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED const AP_Param::GroupInfo ModeDock::var_info[] = { // @Param: _SPEED diff --git a/Rover/system.cpp b/Rover/system.cpp index 02b93ab644..51d9bd079d 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -30,7 +30,7 @@ void Rover::init_ardupilot() // setup telem slots with serial ports gcs().setup_uarts(); -#if OSD_ENABLED == ENABLED +#if OSD_ENABLED osd.init(); #endif @@ -201,7 +201,7 @@ bool Rover::gcs_mode_enabled(const Mode::Number mode_num) const (uint8_t)Mode::Number::RTL, (uint8_t)Mode::Number::SMART_RTL, (uint8_t)Mode::Number::GUIDED, -#if MODE_DOCK_ENABLED == ENABLED +#if MODE_DOCK_ENABLED (uint8_t)Mode::Number::DOCK #endif };