ArduCopter: correct compilation with rally disabled

This commit is contained in:
Peter Barker 2022-09-21 23:13:20 +10:00 committed by Peter Barker
parent 2da23a218a
commit 2d0f31c2ad
5 changed files with 3 additions and 12 deletions

View File

@ -5,7 +5,6 @@
//#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 RANGEFINDER_ENABLED DISABLED // disable rangefinder to save 1k of flash
//#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally)
//#define AC_AVOID_ENABLED DISABLED // disable stop-at-fence library
//#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash

View File

@ -500,7 +500,7 @@ private:
#endif
// Rally library
#if AC_RALLY == ENABLED
#if HAL_RALLY_ENABLED
AP_Rally_Copter rally;
#endif

View File

@ -617,7 +617,7 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECT(avoid, "AVOID_", AC_Avoid),
#endif
#if AC_RALLY == ENABLED
#if HAL_RALLY_ENABLED
// @Group: RALLY_
// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp
GOBJECT(rally, "RALLY_", AP_Rally_Copter),

View File

@ -615,14 +615,6 @@
// Fence, Rally and Terrain and AC_Avoidance defaults
//
#ifndef AC_RALLY
#define AC_RALLY ENABLED
#endif
#if AP_TERRAIN_AVAILABLE && !AC_RALLY
#error Terrain relies on Rally which is disabled
#endif
#ifndef AC_AVOID_ENABLED
#define AC_AVOID_ENABLED ENABLED
#endif

View File

@ -445,7 +445,7 @@ void ModeRTL::build_path()
void ModeRTL::compute_return_target()
{
// set return target to nearest rally point or home position (Note: alt is absolute)
#if AC_RALLY == ENABLED
#if HAL_RALLY_ENABLED
rtl_path.return_target = copter.rally.calc_best_rally_or_home_location(copter.current_loc, ahrs.get_home().alt);
#else
rtl_path.return_target = ahrs.get_home();