From 95c13faac212e6028bf147a9e5c52bf8b5ecec37 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 18 Aug 2023 15:38:03 +1000 Subject: [PATCH] Rover: rely on AP_RALLY_ENABLED for rally support --- Rover/AP_Rally.cpp | 8 ++++++-- Rover/AP_Rally.h | 5 ++++- Rover/Parameters.cpp | 2 +- Rover/Parameters.h | 2 ++ Rover/config.h | 7 ------- Rover/mode_rtl.cpp | 2 +- 6 files changed, 14 insertions(+), 12 deletions(-) diff --git a/Rover/AP_Rally.cpp b/Rover/AP_Rally.cpp index 1a83615964..b0daf506f1 100644 --- a/Rover/AP_Rally.cpp +++ b/Rover/AP_Rally.cpp @@ -13,11 +13,13 @@ along with this program. If not, see . */ -#include +#include "AP_Rally.h" + +#if HAL_RALLY_ENABLED #include "Rover.h" -#include "AP_Rally.h" +#include bool AP_Rally_Rover::is_valid(const Location &rally_point) const { @@ -28,3 +30,5 @@ bool AP_Rally_Rover::is_valid(const Location &rally_point) const #endif return true; } + +#endif // HAL_RALLY_ENABLED diff --git a/Rover/AP_Rally.h b/Rover/AP_Rally.h index 0055dcb1e5..197d6c9279 100644 --- a/Rover/AP_Rally.h +++ b/Rover/AP_Rally.h @@ -15,7 +15,8 @@ #pragma once #include -#include + +#if HAL_RALLY_ENABLED class AP_Rally_Rover : public AP_Rally { @@ -28,3 +29,5 @@ public: private: bool is_valid(const Location &rally_point) const override; }; + +#endif // HAL_RALLY_ENABLED diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index b8951938ae..24783eb2a3 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -548,7 +548,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Path: ../libraries/AP_WheelEncoder/AP_WheelRateControl.cpp AP_SUBGROUPINFO(wheel_rate_control, "WRC", 27, ParametersG2, AP_WheelRateControl), -#if AP_RALLY == ENABLED +#if HAL_RALLY_ENABLED // @Group: RALLY_ // @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp AP_SUBGROUPINFO(rally, "RALLY_", 28, ParametersG2, AP_Rally_Rover), diff --git a/Rover/Parameters.h b/Rover/Parameters.h index c12b6ace33..035d16f4d0 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -381,8 +381,10 @@ public: AP_Gripper gripper; #endif +#if HAL_RALLY_ENABLED // Rally point library AP_Rally_Rover rally; +#endif // Simple mode types AP_Int8 simple_type; diff --git a/Rover/config.h b/Rover/config.h index cc1d55026e..7a280e88f3 100644 --- a/Rover/config.h +++ b/Rover/config.h @@ -31,13 +31,6 @@ #error XXX #endif -////////////////////////////////////////////////////////////////////////////// -// RALLY POINTS -// -#ifndef AP_RALLY - #define AP_RALLY ENABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // NAVL1 // diff --git a/Rover/mode_rtl.cpp b/Rover/mode_rtl.cpp index b9a8ee4964..e896c5151f 100644 --- a/Rover/mode_rtl.cpp +++ b/Rover/mode_rtl.cpp @@ -11,7 +11,7 @@ bool ModeRTL::_enter() g2.wp_nav.init(MAX(0, g2.rtl_speed)); // set target to the closest rally point or home -#if AP_RALLY == ENABLED +#if HAL_RALLY_ENABLED if (!g2.wp_nav.set_desired_location(g2.rally.calc_best_rally_or_home_location(rover.current_loc, ahrs.get_home().alt))) { return false; }