ArduCopter: avoid use of MINIMIZE_FEATURES define in Copter directory

This commit is contained in:
Peter Barker 2023-08-03 08:34:05 +10:00 committed by Andrew Tridgell
parent 009172685e
commit 201e276f00
3 changed files with 27 additions and 25 deletions

View File

@ -146,8 +146,8 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Nav-Guided - allows external nav computer to control vehicle // Nav-Guided - allows external nav computer to control vehicle
#ifndef NAV_GUIDED #ifndef AC_NAV_GUIDED
# define NAV_GUIDED !HAL_MINIMIZE_FEATURES # define AC_NAV_GUIDED ENABLED
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
@ -189,7 +189,7 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Follow - follow another vehicle or GCS // Follow - follow another vehicle or GCS
#ifndef MODE_FOLLOW_ENABLED #ifndef MODE_FOLLOW_ENABLED
# define MODE_FOLLOW_ENABLED !HAL_MINIMIZE_FEATURES # define MODE_FOLLOW_ENABLED ENABLED
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
@ -201,7 +201,7 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// GuidedNoGPS mode - control vehicle's angles from GCS // GuidedNoGPS mode - control vehicle's angles from GCS
#ifndef MODE_GUIDED_NOGPS_ENABLED #ifndef MODE_GUIDED_NOGPS_ENABLED
# define MODE_GUIDED_NOGPS_ENABLED !HAL_MINIMIZE_FEATURES # define MODE_GUIDED_NOGPS_ENABLED ENABLED
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
@ -237,7 +237,7 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// System ID - conduct system identification tests on vehicle // System ID - conduct system identification tests on vehicle
#ifndef MODE_SYSTEMID_ENABLED #ifndef MODE_SYSTEMID_ENABLED
# define MODE_SYSTEMID_ENABLED !HAL_MINIMIZE_FEATURES # define MODE_SYSTEMID_ENABLED ENABLED
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
@ -249,19 +249,19 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// ZigZag - allow vehicle to fly in a zigzag manner with predefined point A B // ZigZag - allow vehicle to fly in a zigzag manner with predefined point A B
#ifndef MODE_ZIGZAG_ENABLED #ifndef MODE_ZIGZAG_ENABLED
# define MODE_ZIGZAG_ENABLED !HAL_MINIMIZE_FEATURES # define MODE_ZIGZAG_ENABLED ENABLED
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Turtle - allow vehicle to be flipped over after a crash // Turtle - allow vehicle to be flipped over after a crash
#ifndef MODE_TURTLE_ENABLED #ifndef MODE_TURTLE_ENABLED
# define MODE_TURTLE_ENABLED !HAL_MINIMIZE_FEATURES && !defined(DISABLE_DSHOT) && FRAME_CONFIG != HELI_FRAME # define MODE_TURTLE_ENABLED !defined(DISABLE_DSHOT) && FRAME_CONFIG != HELI_FRAME
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Flowhold - use optical flow to hover in place // Flowhold - use optical flow to hover in place
#ifndef MODE_FLOWHOLD_ENABLED #ifndef MODE_FLOWHOLD_ENABLED
# define MODE_FLOWHOLD_ENABLED !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED # define MODE_FLOWHOLD_ENABLED AP_OPTICALFLOW_ENABLED
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
@ -269,17 +269,18 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Weathervane - allow vehicle to yaw into wind // Weathervane - allow vehicle to yaw into wind
#ifndef WEATHERVANE_ENABLED #ifndef WEATHERVANE_ENABLED
# define WEATHERVANE_ENABLED !HAL_MINIMIZE_FEATURES # define WEATHERVANE_ENABLED ENABLED
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Autorotate - autonomous auto-rotation - helicopters only // Autorotate - autonomous auto-rotation - helicopters only
#ifndef MODE_AUTOROTATE_ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
#ifndef MODE_AUTOROTATE_ENABLED #ifndef MODE_AUTOROTATE_ENABLED
# define MODE_AUTOROTATE_ENABLED !HAL_MINIMIZE_FEATURES # define MODE_AUTOROTATE_ENABLED ENABLED
#endif #endif
#else #else
# define MODE_AUTOROTATE_ENABLED DISABLED # define MODE_AUTOROTATE_ENABLED DISABLED
@ -287,6 +288,7 @@
#else #else
# define MODE_AUTOROTATE_ENABLED DISABLED # define MODE_AUTOROTATE_ENABLED DISABLED
#endif #endif
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION // RADIO CONFIGURATION
@ -561,7 +563,7 @@
#endif #endif
#ifndef AC_OAPATHPLANNER_ENABLED #ifndef AC_OAPATHPLANNER_ENABLED
#define AC_OAPATHPLANNER_ENABLED !HAL_MINIMIZE_FEATURES #define AC_OAPATHPLANNER_ENABLED ENABLED
#endif #endif
#if MODE_FOLLOW_ENABLED && !AC_AVOID_ENABLED #if MODE_FOLLOW_ENABLED && !AC_AVOID_ENABLED

View File

@ -566,7 +566,7 @@ private:
void do_loiter_to_alt(const AP_Mission::Mission_Command& cmd); void do_loiter_to_alt(const AP_Mission::Mission_Command& cmd);
void do_spline_wp(const AP_Mission::Mission_Command& cmd); void do_spline_wp(const AP_Mission::Mission_Command& cmd);
void get_spline_from_cmd(const AP_Mission::Mission_Command& cmd, const Location& default_loc, Location& dest_loc, Location& next_dest_loc, bool& next_dest_loc_is_spline); void get_spline_from_cmd(const AP_Mission::Mission_Command& cmd, const Location& default_loc, Location& dest_loc, Location& next_dest_loc, bool& next_dest_loc_is_spline);
#if NAV_GUIDED == ENABLED #if AC_NAV_GUIDED == ENABLED
void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd); void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
void do_guided_limits(const AP_Mission::Mission_Command& cmd); void do_guided_limits(const AP_Mission::Mission_Command& cmd);
#endif #endif
@ -604,7 +604,7 @@ private:
bool verify_nav_wp(const AP_Mission::Mission_Command& cmd); bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
bool verify_circle(const AP_Mission::Mission_Command& cmd); bool verify_circle(const AP_Mission::Mission_Command& cmd);
bool verify_spline_wp(const AP_Mission::Mission_Command& cmd); bool verify_spline_wp(const AP_Mission::Mission_Command& cmd);
#if NAV_GUIDED == ENABLED #if AC_NAV_GUIDED == ENABLED
bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd); bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
#endif #endif
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);

View File

@ -136,7 +136,7 @@ void ModeAuto::run()
case SubMode::NAVGUIDED: case SubMode::NAVGUIDED:
case SubMode::NAV_SCRIPT_TIME: case SubMode::NAV_SCRIPT_TIME:
#if NAV_GUIDED == ENABLED || AP_SCRIPTING_ENABLED #if AC_NAV_GUIDED == ENABLED || AP_SCRIPTING_ENABLED
nav_guided_run(); nav_guided_run();
#endif #endif
break; break;
@ -502,7 +502,7 @@ void ModeAuto::circle_start()
set_submode(SubMode::CIRCLE); set_submode(SubMode::CIRCLE);
} }
#if NAV_GUIDED == ENABLED #if AC_NAV_GUIDED == ENABLED
// auto_nav_guided_start - hand over control to external navigation controller in AUTO mode // auto_nav_guided_start - hand over control to external navigation controller in AUTO mode
void ModeAuto::nav_guided_start() void ModeAuto::nav_guided_start()
{ {
@ -519,7 +519,7 @@ void ModeAuto::nav_guided_start()
// set submode // set submode
set_submode(SubMode::NAVGUIDED); set_submode(SubMode::NAVGUIDED);
} }
#endif //NAV_GUIDED #endif //AC_NAV_GUIDED
bool ModeAuto::is_landing() const bool ModeAuto::is_landing() const
{ {
@ -647,7 +647,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
do_spline_wp(cmd); do_spline_wp(cmd);
break; break;
#if NAV_GUIDED == ENABLED #if AC_NAV_GUIDED == ENABLED
case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer
do_nav_guided_enable(cmd); do_nav_guided_enable(cmd);
break; break;
@ -719,7 +719,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
#endif //AP_FENCE_ENABLED #endif //AP_FENCE_ENABLED
break; break;
#if NAV_GUIDED == ENABLED #if AC_NAV_GUIDED == ENABLED
case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits
do_guided_limits(cmd); do_guided_limits(cmd);
break; break;
@ -892,7 +892,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
cmd_complete = verify_spline_wp(cmd); cmd_complete = verify_spline_wp(cmd);
break; break;
#if NAV_GUIDED == ENABLED #if AC_NAV_GUIDED == ENABLED
case MAV_CMD_NAV_GUIDED_ENABLE: case MAV_CMD_NAV_GUIDED_ENABLE:
cmd_complete = verify_nav_guided_enable(cmd); cmd_complete = verify_nav_guided_enable(cmd);
break; break;
@ -1033,7 +1033,7 @@ void ModeAuto::circle_run()
attitude_control->input_thrust_vector_heading(pos_control->get_thrust_vector(), auto_yaw.get_heading()); attitude_control->input_thrust_vector_heading(pos_control->get_thrust_vector(), auto_yaw.get_heading());
} }
#if NAV_GUIDED == ENABLED || AP_SCRIPTING_ENABLED #if AC_NAV_GUIDED == ENABLED || AP_SCRIPTING_ENABLED
// auto_nav_guided_run - allows control by external navigation controller // auto_nav_guided_run - allows control by external navigation controller
// called by auto_run at 100hz or more // called by auto_run at 100hz or more
void ModeAuto::nav_guided_run() void ModeAuto::nav_guided_run()
@ -1041,7 +1041,7 @@ void ModeAuto::nav_guided_run()
// call regular guided flight mode run function // call regular guided flight mode run function
copter.mode_guided.run(); copter.mode_guided.run();
} }
#endif // NAV_GUIDED || AP_SCRIPTING_ENABLED #endif // AC_NAV_GUIDED || AP_SCRIPTING_ENABLED
// auto_loiter_run - loiter in AUTO flight mode // auto_loiter_run - loiter in AUTO flight mode
// called by auto_run at 100hz or more // called by auto_run at 100hz or more
@ -1751,7 +1751,7 @@ void ModeAuto::get_spline_from_cmd(const AP_Mission::Mission_Command& cmd, const
} }
} }
#if NAV_GUIDED == ENABLED #if AC_NAV_GUIDED == ENABLED
// do_nav_guided_enable - initiate accepting commands from external nav computer // do_nav_guided_enable - initiate accepting commands from external nav computer
void ModeAuto::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd) void ModeAuto::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
{ {
@ -1770,7 +1770,7 @@ void ModeAuto::do_guided_limits(const AP_Mission::Mission_Command& cmd)
cmd.content.guided_limits.alt_max * 100.0f, // convert meters to cm cmd.content.guided_limits.alt_max * 100.0f, // convert meters to cm
cmd.content.guided_limits.horiz_max * 100.0f); // convert meters to cm cmd.content.guided_limits.horiz_max * 100.0f); // convert meters to cm
} }
#endif // NAV_GUIDED #endif // AC_NAV_GUIDED
// do_nav_delay - Delay the next navigation command // do_nav_delay - Delay the next navigation command
void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd) void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd)
@ -2188,7 +2188,7 @@ bool ModeAuto::verify_spline_wp(const AP_Mission::Mission_Command& cmd)
return false; return false;
} }
#if NAV_GUIDED == ENABLED #if AC_NAV_GUIDED == ENABLED
// verify_nav_guided - check if we have breached any limits // verify_nav_guided - check if we have breached any limits
bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd) bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
{ {
@ -2200,7 +2200,7 @@ bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
// check time and position limits // check time and position limits
return copter.mode_guided.limit_check(); return copter.mode_guided.limit_check();
} }
#endif // NAV_GUIDED #endif // AC_NAV_GUIDED
// verify_nav_delay - check if we have waited long enough // verify_nav_delay - check if we have waited long enough
bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd) bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd)