Skip to content

Commit

Permalink
Copter: remove ENABLE/ENABLED/DISABLE/DISABLED defines
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Sep 6, 2024
1 parent 0e33a0f commit 7847603
Show file tree
Hide file tree
Showing 55 changed files with 320 additions and 328 deletions.
50 changes: 25 additions & 25 deletions ArduCopter/APM_Config.h
Original file line number Diff line number Diff line change
@@ -1,33 +1,33 @@
// User specific config file. Any items listed in config.h can be overridden here.

// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards)
//#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
//#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support
//#define MODE_CIRCLE_ENABLED DISABLED // disable circle mode support
//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
//#define MODE_FLIP_ENABLED DISABLED // disable flip mode support
//#define MODE_FOLLOW_ENABLED DISABLED // disable follow mode support
//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support
//#define MODE_GUIDED_NOGPS_ENABLED DISABLED // disable guided/nogps mode support
//#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support
//#define MODE_POSHOLD_ENABLED DISABLED // disable poshold mode support
//#define MODE_RTL_ENABLED DISABLED // disable rtl mode support
//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
//#define MODE_SPORT_ENABLED DISABLED // disable sport mode support
//#define MODE_SYSTEMID_ENABLED DISABLED // disable system ID mode support
//#define MODE_THROW_ENABLED DISABLED // disable throw mode support
//#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support
//#define OSD_ENABLED DISABLED // disable on-screen-display support
//#define LOGGING_ENABLED 0 // disable logging to save 11K of flash space
//#define MOUNT 0 // disable the camera gimbal to save 8K of flash space
//#define AUTOTUNE_ENABLED 0 // disable the auto tune functionality to save 7k of flash
//#define NAV_GUIDED 0 // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define MODE_ACRO_ENABLED 0 // disable acrobatic mode support
//#define MODE_AUTO_ENABLED 0 // disable auto mode support
//#define MODE_BRAKE_ENABLED 0 // disable brake mode support
//#define MODE_CIRCLE_ENABLED 0 // disable circle mode support
//#define MODE_DRIFT_ENABLED 0 // disable drift mode support
//#define MODE_FLIP_ENABLED 0 // disable flip mode support
//#define MODE_FOLLOW_ENABLED 0 // disable follow mode support
//#define MODE_GUIDED_ENABLED 0 // disable guided mode support
//#define MODE_GUIDED_NOGPS_ENABLED 0 // disable guided/nogps mode support
//#define MODE_LOITER_ENABLED 0 // disable loiter mode support
//#define MODE_POSHOLD_ENABLED 0 // disable poshold mode support
//#define MODE_RTL_ENABLED 0 // disable rtl mode support
//#define MODE_SMARTRTL_ENABLED 0 // disable smartrtl mode support
//#define MODE_SPORT_ENABLED 0 // disable sport mode support
//#define MODE_SYSTEMID_ENABLED 0 // disable system ID mode support
//#define MODE_THROW_ENABLED 0 // disable throw mode support
//#define MODE_ZIGZAG_ENABLED 0 // disable zigzag mode support
//#define OSD_ENABLED 0 // disable on-screen-display support

// features below are disabled by default on all boards
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
//#define ADVANCED_FAILSAFE ENABLED // enabled advanced failsafe which allows running a portion of the mission in failsafe events
//#define ADVANCED_FAILSAFE 1 // enabled advanced failsafe which allows running a portion of the mission in failsafe events

// other settings
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)
Expand All @@ -42,5 +42,5 @@
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz
//#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz
//#define USERHOOK_AUXSWITCH ENABLED // for code to handle user aux switches
//#define USER_PARAMS_ENABLED ENABLED // to enable user parameters
//#define USERHOOK_AUXSWITCH 1 // for code to handle user aux switches
//#define USER_PARAMS_ENABLED 1 // to enable user parameters
10 changes: 5 additions & 5 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -210,7 +210,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
}

// acro balance parameter check
#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
if ((copter.g.acro_balance_roll > copter.attitude_control->get_angle_roll_p().kP()) || (copter.g.acro_balance_pitch > copter.attitude_control->get_angle_pitch_p().kP())) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check ACRO_BAL_ROLL/PITCH");
return false;
Expand Down Expand Up @@ -251,7 +251,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
#endif // HELI_FRAME

// checks when using range finder for RTL
#if MODE_RTL_ENABLED == ENABLED
#if MODE_RTL_ENABLED
if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::TERRAIN) {
// get terrain source from wpnav
const char *failure_template = "RTL_ALT_TYPE is above-terrain but %s";
Expand Down Expand Up @@ -728,7 +728,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
copter.update_super_simple_bearing(false);

// Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point
#if MODE_SMARTRTL_ENABLED == ENABLED
#if MODE_SMARTRTL_ENABLED
copter.g2.smart_rtl.set_home(copter.position_ok());
#endif

Expand Down Expand Up @@ -815,7 +815,7 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
// send disarm command to motors
copter.motors->armed(false);

#if MODE_AUTO_ENABLED == ENABLED
#if MODE_AUTO_ENABLED
// reset the mission
copter.mode_auto.mission.reset();
#endif
Expand All @@ -828,7 +828,7 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che

copter.ap.in_arming_delay = false;

#if AUTOTUNE_ENABLED == ENABLED
#if AUTOTUNE_ENABLED
// Possibly save auto tuned parameters
copter.mode_autotune.autotune.disarmed(copter.flightmode == &copter.mode_autotune);
#endif
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control)
return 0.0f;
}

#if TOY_MODE_ENABLED == ENABLED
#if TOY_MODE_ENABLED
if (g2.toy_mode.enabled()) {
// allow throttle to be reduced after throttle arming and for
// slower descent close to the ground
Expand Down
24 changes: 12 additions & 12 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
FAST_TASK_CLASS(AP_InertialSensor, &copter.ins, update),
// run low level rate controllers that only require IMU data
FAST_TASK(run_rate_controller),
#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED
#if AC_CUSTOMCONTROL_MULTI_ENABLED
FAST_TASK(run_custom_controller),
#endif
#if FRAME_CONFIG == HELI_FRAME
Expand Down Expand Up @@ -159,7 +159,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(update_batt_compass, 10, 120, 15),
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&copter.g2.rc_channels, read_aux_all, 10, 50, 18),
SCHED_TASK(arm_motors_check, 10, 50, 21),
#if TOY_MODE_ENABLED == ENABLED
#if TOY_MODE_ENABLED
SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50, 24),
#endif
SCHED_TASK(auto_disarm_check, 10, 50, 27),
Expand All @@ -176,7 +176,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(update_altitude, 10, 100, 42),
SCHED_TASK(run_nav_updates, 50, 100, 45),
SCHED_TASK(update_throttle_hover,100, 90, 48),
#if MODE_SMARTRTL_ENABLED == ENABLED
#if MODE_SMARTRTL_ENABLED
SCHED_TASK_CLASS(ModeSmartRTL, &copter.mode_smartrtl, save_position, 3, 100, 51),
#endif
#if HAL_SPRAYER_ENABLED
Expand Down Expand Up @@ -232,7 +232,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if HAL_ADSB_ENABLED
SCHED_TASK(avoidance_adsb_update, 10, 100, 138),
#endif
#if ADVANCED_FAILSAFE == ENABLED
#if ADVANCED_FAILSAFE
SCHED_TASK(afs_fs_check, 10, 100, 141),
#endif
#if AP_TERRAIN_AVAILABLE
Expand Down Expand Up @@ -274,7 +274,7 @@ constexpr int8_t Copter::_failsafe_priorities[7];


#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
#if MODE_GUIDED_ENABLED
// set target location (for use by external control and scripting)
bool Copter::set_target_location(const Location& target_loc)
{
Expand All @@ -285,11 +285,11 @@ bool Copter::set_target_location(const Location& target_loc)

return mode_guided.set_destination(target_loc);
}
#endif //MODE_GUIDED_ENABLED == ENABLED
#endif //MODE_GUIDED_ENABLED
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED

#if AP_SCRIPTING_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
#if MODE_GUIDED_ENABLED
// start takeoff to given altitude (for use by scripting)
bool Copter::start_takeoff(float alt)
{
Expand Down Expand Up @@ -391,7 +391,7 @@ bool Copter::set_target_angle_and_climbrate(float roll_deg, float pitch_deg, flo
}
#endif

#if MODE_CIRCLE_ENABLED == ENABLED
#if MODE_CIRCLE_ENABLED
// circle mode controls
bool Copter::get_circle_radius(float &radius_m)
{
Expand All @@ -412,7 +412,7 @@ bool Copter::set_desired_speed(float speed)
return flightmode->set_speed_xy(speed * 100.0f);
}

#if MODE_AUTO_ENABLED == ENABLED
#if MODE_AUTO_ENABLED
// returns true if mode supports NAV_SCRIPT_TIME mission commands
bool Copter::nav_scripting_enable(uint8_t mode)
{
Expand Down Expand Up @@ -488,7 +488,7 @@ bool Copter::is_taking_off() const

bool Copter::current_mode_requires_mission() const
{
#if MODE_AUTO_ENABLED == ENABLED
#if MODE_AUTO_ENABLED
return flightmode == &mode_auto;
#else
return false;
Expand Down Expand Up @@ -631,7 +631,7 @@ void Copter::twentyfive_hz_logging()
AP::ins().Write_IMU();
}

#if MODE_AUTOROTATE_ENABLED == ENABLED
#if MODE_AUTOROTATE_ENABLED
if (should_log(MASK_LOG_ATTITUDE_MED) || should_log(MASK_LOG_ATTITUDE_FAST)) {
//update autorotation log
g2.arot.Log_Write_Autorotation();
Expand Down Expand Up @@ -702,7 +702,7 @@ void Copter::one_hz_loop()
// slowly update the PID notches with the average loop rate
attitude_control->set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
pos_control->get_accel_z_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED
#if AC_CUSTOMCONTROL_MULTI_ENABLED
custom_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
#endif
}
Expand Down
Loading

0 comments on commit 7847603

Please sign in to comment.