From 995ff30cd698112fb6d1748c5b7c77dc9a7d67f6 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 11 Jan 2022 16:48:52 +0900 Subject: [PATCH] AC_Avoid: enable slide behaviour for rover --- libraries/AC_Avoidance/AC_Avoid.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 59c05576a5..b77d6e3934 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -67,12 +67,12 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = { // @User: Standard AP_GROUPINFO("MARGIN", 4, AC_Avoid, _margin, 2.0f), - // @Param{Copter}: BEHAVE + // @Param{Copter, Rover}: BEHAVE // @DisplayName: Avoidance behaviour // @Description: Avoidance behaviour (slide or stop) // @Values: 0:Slide,1:Stop // @User: Standard - AP_GROUPINFO_FRAME("BEHAVE", 5, AC_Avoid, _behavior, AP_AVOID_BEHAVE_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER), + AP_GROUPINFO_FRAME("BEHAVE", 5, AC_Avoid, _behavior, AP_AVOID_BEHAVE_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_ROVER), // @Param: BACKUP_SPD // @DisplayName: Avoidance maximum backup speed