Skip to content

Commit

Permalink
Rover: rely on AP_RALLY_ENABLED for rally support
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and tridge committed Aug 21, 2023
1 parent 1dd5778 commit 95c13fa
Show file tree
Hide file tree
Showing 6 changed files with 14 additions and 12 deletions.
8 changes: 6 additions & 2 deletions Rover/AP_Rally.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,13 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

#include <AP_Common/Location.h>
#include "AP_Rally.h"

#if HAL_RALLY_ENABLED

#include "Rover.h"

#include "AP_Rally.h"
#include <AP_Common/Location.h>

bool AP_Rally_Rover::is_valid(const Location &rally_point) const
{
Expand All @@ -28,3 +30,5 @@ bool AP_Rally_Rover::is_valid(const Location &rally_point) const
#endif
return true;
}

#endif // HAL_RALLY_ENABLED
5 changes: 4 additions & 1 deletion Rover/AP_Rally.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,8 @@
#pragma once

#include <AP_Rally/AP_Rally.h>
#include <AP_AHRS/AP_AHRS.h>

#if HAL_RALLY_ENABLED

class AP_Rally_Rover : public AP_Rally
{
Expand All @@ -28,3 +29,5 @@ class AP_Rally_Rover : public AP_Rally
private:
bool is_valid(const Location &rally_point) const override;
};

#endif // HAL_RALLY_ENABLED
2 changes: 1 addition & 1 deletion Rover/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
2 changes: 2 additions & 0 deletions Rover/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -381,8 +381,10 @@ class ParametersG2 {
AP_Gripper gripper;
#endif

#if HAL_RALLY_ENABLED
// Rally point library
AP_Rally_Rover rally;
#endif

// Simple mode types
AP_Int8 simple_type;
Expand Down
7 changes: 0 additions & 7 deletions Rover/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,6 @@
#error XXX
#endif

//////////////////////////////////////////////////////////////////////////////
// RALLY POINTS
//
#ifndef AP_RALLY
#define AP_RALLY ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
// NAVL1
//
Expand Down
2 changes: 1 addition & 1 deletion Rover/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down

0 comments on commit 95c13fa

Please sign in to comment.