Rover: remove ENABLE/DISABLE defines

This commit is contained in:
Peter Barker 2024-08-05 10:54:28 +10:00 committed by Randy Mackay
parent 516c2a853f
commit 227b6780b2
14 changed files with 30 additions and 38 deletions

View File

@ -418,7 +418,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h // @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
AP_SUBGROUPINFO(rc_channels, "RC", 4, ParametersG2, RC_Channels_Rover), AP_SUBGROUPINFO(rc_channels, "RC", 4, ParametersG2, RC_Channels_Rover),
#if ADVANCED_FAILSAFE == ENABLED #if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
// @Group: AFS_ // @Group: AFS_
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp // @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe), AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe),
@ -667,7 +667,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced // @User: Advanced
AP_GROUPINFO("MANUAL_OPTIONS", 53, ParametersG2, manual_options, 0), AP_GROUPINFO("MANUAL_OPTIONS", 53, ParametersG2, manual_options, 0),
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED
// @Group: DOCK // @Group: DOCK
// @Path: mode_dock.cpp // @Path: mode_dock.cpp
AP_SUBGROUPPTR(mode_dock_ptr, "DOCK", 54, ParametersG2, ModeDock), AP_SUBGROUPPTR(mode_dock_ptr, "DOCK", 54, ParametersG2, ModeDock),
@ -729,7 +729,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
ParametersG2::ParametersG2(void) ParametersG2::ParametersG2(void)
: :
#if ADVANCED_FAILSAFE == ENABLED #if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
afs(), afs(),
#endif #endif
#if AP_BEACON_ENABLED #if AP_BEACON_ENABLED
@ -739,7 +739,7 @@ ParametersG2::ParametersG2(void)
wheel_rate_control(wheel_encoder), wheel_rate_control(wheel_encoder),
attitude_control(), attitude_control(),
smart_rtl(), smart_rtl(),
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED
mode_dock_ptr(&rover.mode_dock), mode_dock_ptr(&rover.mode_dock),
#endif #endif
#if HAL_PROXIMITY_ENABLED #if HAL_PROXIMITY_ENABLED

View File

@ -301,7 +301,7 @@ public:
// control over servo output ranges // control over servo output ranges
SRV_Channels servo_channels; SRV_Channels servo_channels;
#if ADVANCED_FAILSAFE == ENABLED #if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
// advanced failsafe library // advanced failsafe library
AP_AdvancedFailsafe_Rover afs; AP_AdvancedFailsafe_Rover afs;
#endif #endif
@ -340,7 +340,7 @@ public:
AP_Proximity proximity; AP_Proximity proximity;
#endif #endif
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED
// we need a pointer to the mode for the G2 table // we need a pointer to the mode for the G2 table
class ModeDock *mode_dock_ptr; class ModeDock *mode_dock_ptr;
#endif #endif

View File

@ -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); do_aux_function_change_mode(rover.mode_loiter, ch_flag);
break; break;
#if MODE_FOLLOW_ENABLED == ENABLED #if MODE_FOLLOW_ENABLED
// Set mode to Follow // Set mode to Follow
case AUX_FUNC::FOLLOW: case AUX_FUNC::FOLLOW:
do_aux_function_change_mode(rover.mode_follow, ch_flag); do_aux_function_change_mode(rover.mode_follow, ch_flag);

View File

@ -134,7 +134,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
#endif #endif
SCHED_TASK(crash_check, 10, 200, 123), SCHED_TASK(crash_check, 10, 200, 123),
SCHED_TASK(cruise_learn_update, 50, 200, 126), 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), SCHED_TASK(afs_fs_check, 10, 200, 129),
#endif #endif
}; };

View File

@ -60,7 +60,7 @@
// Local modules // Local modules
#include "AP_Arming.h" #include "AP_Arming.h"
#include "sailboat.h" #include "sailboat.h"
#if ADVANCED_FAILSAFE == ENABLED #if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
#include "afs_rover.h" #include "afs_rover.h"
#endif #endif
#include "Parameters.h" #include "Parameters.h"
@ -81,7 +81,7 @@ public:
friend class ParametersG2; friend class ParametersG2;
friend class AP_Rally_Rover; friend class AP_Rally_Rover;
friend class AP_Arming_Rover; friend class AP_Arming_Rover;
#if ADVANCED_FAILSAFE == ENABLED #if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
friend class AP_AdvancedFailsafe_Rover; friend class AP_AdvancedFailsafe_Rover;
#endif #endif
#if AP_EXTERNAL_CONTROL_ENABLED #if AP_EXTERNAL_CONTROL_ENABLED
@ -99,11 +99,11 @@ public:
friend class ModeManual; friend class ModeManual;
friend class ModeRTL; friend class ModeRTL;
friend class ModeSmartRTL; friend class ModeSmartRTL;
#if MODE_FOLLOW_ENABLED == ENABLED #if MODE_FOLLOW_ENABLED
friend class ModeFollow; friend class ModeFollow;
#endif #endif
friend class ModeSimple; friend class ModeSimple;
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED
friend class ModeDock; friend class ModeDock;
#endif #endif
@ -253,11 +253,11 @@ private:
ModeSteering mode_steering; ModeSteering mode_steering;
ModeRTL mode_rtl; ModeRTL mode_rtl;
ModeSmartRTL mode_smartrtl; ModeSmartRTL mode_smartrtl;
#if MODE_FOLLOW_ENABLED == ENABLED #if MODE_FOLLOW_ENABLED
ModeFollow mode_follow; ModeFollow mode_follow;
#endif #endif
ModeSimple mode_simple; ModeSimple mode_simple;
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED
ModeDock mode_dock; ModeDock mode_dock;
#endif #endif
@ -322,7 +322,7 @@ private:
// failsafe.cpp // failsafe.cpp
void failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool on); 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); 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); void afs_fs_check(void);
#endif #endif

View File

@ -4,7 +4,7 @@
#include "Rover.h" #include "Rover.h"
#if ADVANCED_FAILSAFE == ENABLED #if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
/* /*
Setup radio_out values for all channels to termination values Setup radio_out values for all channels to termination values

View File

@ -18,7 +18,7 @@
advanced failsafe support for rover advanced failsafe support for rover
*/ */
#if ADVANCED_FAILSAFE == ENABLED #if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h> #include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
/* /*

View File

@ -72,6 +72,6 @@
#define RESET_SWITCH_CHAN_PWM 1750 #define RESET_SWITCH_CHAN_PWM 1750
#endif #endif
#ifndef ADVANCED_FAILSAFE #ifndef AP_ROVER_ADVANCED_FAILSAFE_ENABLED
#define ADVANCED_FAILSAFE DISABLED #define AP_ROVER_ADVANCED_FAILSAFE_ENABLED 0
#endif #endif

View File

@ -3,14 +3,6 @@
// Internal defines, don't edit and expect things to work // 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. #define SERVO_MAX 4500.0 // This value represents 45 degrees and is just an arbitrary representation of servo max travel.
// types of failsafe events // types of failsafe events

View File

@ -133,18 +133,18 @@ void Rover::handle_battery_failsafe(const char* type_str, const int8_t action)
} }
break; break;
case FailsafeAction::Terminate: case FailsafeAction::Terminate:
#if ADVANCED_FAILSAFE == ENABLED #if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
char battery_type_str[17]; char battery_type_str[17];
snprintf(battery_type_str, 17, "%s battery", type_str); snprintf(battery_type_str, 17, "%s battery", type_str);
g2.afs.gcs_terminate(true, battery_type_str); g2.afs.gcs_terminate(true, battery_type_str);
#else #else
arming.disarm(AP_Arming::Method::BATTERYFAILSAFE); arming.disarm(AP_Arming::Method::BATTERYFAILSAFE);
#endif // ADVANCED_FAILSAFE == ENABLED #endif // AP_ROVER_ADVANCED_FAILSAFE_ENABLED
break; break;
} }
} }
#if ADVANCED_FAILSAFE == ENABLED #if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
/* /*
check for AFS failsafe check check for AFS failsafe check
*/ */

View File

@ -531,7 +531,7 @@ Mode *Rover::mode_from_mode_num(const enum Mode::Number num)
case Mode::Number::LOITER: case Mode::Number::LOITER:
ret = &mode_loiter; ret = &mode_loiter;
break; break;
#if MODE_FOLLOW_ENABLED == ENABLED #if MODE_FOLLOW_ENABLED
case Mode::Number::FOLLOW: case Mode::Number::FOLLOW:
ret = &mode_follow; ret = &mode_follow;
break; break;
@ -557,7 +557,7 @@ Mode *Rover::mode_from_mode_num(const enum Mode::Number num)
case Mode::Number::INITIALISING: case Mode::Number::INITIALISING:
ret = &mode_initializing; ret = &mode_initializing;
break; break;
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED
case Mode::Number::DOCK: case Mode::Number::DOCK:
ret = (Mode *)g2.mode_dock_ptr; ret = (Mode *)g2.mode_dock_ptr;
break; break;

View File

@ -19,7 +19,7 @@ public:
LOITER = 5, LOITER = 5,
FOLLOW = 6, FOLLOW = 6,
SIMPLE = 7, SIMPLE = 7,
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED
DOCK = 8, DOCK = 8,
#endif #endif
CIRCLE = 9, CIRCLE = 9,
@ -808,7 +808,7 @@ protected:
bool _enter() override { return false; }; bool _enter() override { return false; };
}; };
#if MODE_FOLLOW_ENABLED == ENABLED #if MODE_FOLLOW_ENABLED
class ModeFollow : public Mode class ModeFollow : public Mode
{ {
public: public:
@ -868,7 +868,7 @@ private:
float _desired_heading_cd; // latest desired heading (in centi-degrees) from pilot 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 class ModeDock : public Mode
{ {
public: public:

View File

@ -1,6 +1,6 @@
#include "Rover.h" #include "Rover.h"
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED
const AP_Param::GroupInfo ModeDock::var_info[] = { const AP_Param::GroupInfo ModeDock::var_info[] = {
// @Param: _SPEED // @Param: _SPEED

View File

@ -30,7 +30,7 @@ void Rover::init_ardupilot()
// setup telem slots with serial ports // setup telem slots with serial ports
gcs().setup_uarts(); gcs().setup_uarts();
#if OSD_ENABLED == ENABLED #if OSD_ENABLED
osd.init(); osd.init();
#endif #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::RTL,
(uint8_t)Mode::Number::SMART_RTL, (uint8_t)Mode::Number::SMART_RTL,
(uint8_t)Mode::Number::GUIDED, (uint8_t)Mode::Number::GUIDED,
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED
(uint8_t)Mode::Number::DOCK (uint8_t)Mode::Number::DOCK
#endif #endif
}; };