mirror of https://github.com/ArduPilot/ardupilot
Rover: rely on AP_RALLY_ENABLED for rally support
This commit is contained in:
parent
1dd5778956
commit
95c13faac2
|
@ -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
|
||||
{
|
||||
|
@ -28,3 +30,5 @@ bool AP_Rally_Rover::is_valid(const Location &rally_point) const
|
|||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // HAL_RALLY_ENABLED
|
||||
|
|
|
@ -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
|
||||
{
|
||||
|
@ -28,3 +29,5 @@ public:
|
|||
private:
|
||||
bool is_valid(const Location &rally_point) const override;
|
||||
};
|
||||
|
||||
#endif // HAL_RALLY_ENABLED
|
||||
|
|
|
@ -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),
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -31,13 +31,6 @@
|
|||
#error XXX
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RALLY POINTS
|
||||
//
|
||||
#ifndef AP_RALLY
|
||||
#define AP_RALLY ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// NAVL1
|
||||
//
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue