Rover: use AP_FOLLOW_ENABLED

This commit is contained in:
Shiv Tyagi 2023-08-11 17:58:32 +05:30 committed by Andrew Tridgell
parent ecdc036eb6
commit 4f40b31367
9 changed files with 28 additions and 0 deletions

View File

@ -398,8 +398,10 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
void GCS_MAVLINK_Rover::packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) void GCS_MAVLINK_Rover::packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg)
{ {
#if AP_FOLLOW_ENABLED
// pass message to follow library // pass message to follow library
rover.g2.follow.handle_msg(msg); rover.g2.follow.handle_msg(msg);
#endif
GCS_MAVLINK::packetReceived(status, msg); GCS_MAVLINK::packetReceived(status, msg);
} }

View File

@ -517,9 +517,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Standard // @User: Standard
AP_GROUPINFO("CRASH_ANGLE", 22, ParametersG2, crash_angle, 0), AP_GROUPINFO("CRASH_ANGLE", 22, ParametersG2, crash_angle, 0),
#if AP_FOLLOW_ENABLED
// @Group: FOLL // @Group: FOLL
// @Path: ../libraries/AP_Follow/AP_Follow.cpp // @Path: ../libraries/AP_Follow/AP_Follow.cpp
AP_SUBGROUPINFO(follow, "FOLL", 23, ParametersG2, AP_Follow), AP_SUBGROUPINFO(follow, "FOLL", 23, ParametersG2, AP_Follow),
#endif
// @Param: FRAME_TYPE // @Param: FRAME_TYPE
// @DisplayName: Frame Type // @DisplayName: Frame Type
@ -752,7 +754,9 @@ ParametersG2::ParametersG2(void)
proximity(), proximity(),
#endif #endif
avoid(), avoid(),
#if AP_FOLLOW_ENABLED
follow(), follow(),
#endif
windvane(), windvane(),
pos_control(attitude_control), pos_control(attitude_control),
wp_nav(attitude_control, pos_control), wp_nav(attitude_control, pos_control),

View File

@ -360,8 +360,10 @@ public:
// pitch/roll angle for crash check // pitch/roll angle for crash check
AP_Int8 crash_angle; AP_Int8 crash_angle;
#if AP_FOLLOW_ENABLED
// follow mode library // follow mode library
AP_Follow follow; AP_Follow follow;
#endif
// frame type for vehicle (used for vectored motor vehicles and custom motor configs) // frame type for vehicle (used for vectored motor vehicles and custom motor configs)
AP_Int8 frame_type; AP_Int8 frame_type;

View File

@ -214,10 +214,12 @@ bool RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit
do_aux_function_change_mode(rover.mode_loiter, ch_flag); do_aux_function_change_mode(rover.mode_loiter, ch_flag);
break; break;
#if MODE_FOLLOW_ENABLED == ENABLED
// Set mode to Follow // Set mode to Follow
case AUX_FUNC::FOLLOW: case AUX_FUNC::FOLLOW:
do_aux_function_change_mode(rover.mode_follow, ch_flag); do_aux_function_change_mode(rover.mode_follow, ch_flag);
break; break;
#endif
// set mode to Simple // set mode to Simple
case AUX_FUNC::SIMPLE: case AUX_FUNC::SIMPLE:

View File

@ -43,6 +43,7 @@
#include <AR_WPNav/AR_WPNav_OA.h> #include <AR_WPNav/AR_WPNav_OA.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h> #include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AC_PrecLand/AC_PrecLand_config.h> #include <AC_PrecLand/AC_PrecLand_config.h>
#include <AP_Follow/AP_Follow_config.h>
// Configuration // Configuration
#include "defines.h" #include "defines.h"
@ -91,7 +92,9 @@ public:
friend class ModeManual; friend class ModeManual;
friend class ModeRTL; friend class ModeRTL;
friend class ModeSmartRTL; friend class ModeSmartRTL;
#if MODE_FOLLOW_ENABLED == ENABLED
friend class ModeFollow; friend class ModeFollow;
#endif
friend class ModeSimple; friend class ModeSimple;
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED == ENABLED
friend class ModeDock; friend class ModeDock;
@ -236,7 +239,9 @@ private:
ModeSteering mode_steering; ModeSteering mode_steering;
ModeRTL mode_rtl; ModeRTL mode_rtl;
ModeSmartRTL mode_smartrtl; ModeSmartRTL mode_smartrtl;
#if MODE_FOLLOW_ENABLED == ENABLED
ModeFollow mode_follow; ModeFollow mode_follow;
#endif
ModeSimple mode_simple; ModeSimple mode_simple;
#if MODE_DOCK_ENABLED == ENABLED #if MODE_DOCK_ENABLED == ENABLED
ModeDock mode_dock; ModeDock mode_dock;

View File

@ -67,6 +67,12 @@
# define MODE_DOCK_ENABLED AC_PRECLAND_ENABLED # define MODE_DOCK_ENABLED AC_PRECLAND_ENABLED
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// Follow mode - allows vehicle to follow target
#ifndef MODE_FOLLOW_ENABLED
# define MODE_FOLLOW_ENABLED AP_FOLLOW_ENABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Developer Items // Developer Items

View File

@ -531,9 +531,11 @@ Mode *Rover::mode_from_mode_num(const enum Mode::Number num)
case Mode::Number::LOITER: case Mode::Number::LOITER:
ret = &mode_loiter; ret = &mode_loiter;
break; break;
#if MODE_FOLLOW_ENABLED == ENABLED
case Mode::Number::FOLLOW: case Mode::Number::FOLLOW:
ret = &mode_follow; ret = &mode_follow;
break; break;
#endif
case Mode::Number::SIMPLE: case Mode::Number::SIMPLE:
ret = &mode_simple; ret = &mode_simple;
break; break;

View File

@ -789,6 +789,7 @@ protected:
bool _enter() override { return false; }; bool _enter() override { return false; };
}; };
#if MODE_FOLLOW_ENABLED == ENABLED
class ModeFollow : public Mode class ModeFollow : public Mode
{ {
public: public:
@ -823,6 +824,7 @@ protected:
float _desired_speed; // desired speed in m/s float _desired_speed; // desired speed in m/s
}; };
#endif
class ModeSimple : public Mode class ModeSimple : public Mode
{ {

View File

@ -1,5 +1,6 @@
#include "Rover.h" #include "Rover.h"
#if MODE_FOLLOW_ENABLED
// initialize follow mode // initialize follow mode
bool ModeFollow::_enter() bool ModeFollow::_enter()
{ {
@ -94,3 +95,5 @@ bool ModeFollow::set_desired_speed(float speed)
_desired_speed = speed; _desired_speed = speed;
return true; return true;
} }
#endif // MODE_FOLLOW_ENABLED