mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_Avoid: default behaviour to stop for Rovers
This commit is contained in:
parent
509c7e2a8f
commit
a1bf9d66f0
@ -1,5 +1,11 @@
|
||||
#include "AC_Avoid.h"
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_APMrover2)
|
||||
# define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_STOP
|
||||
#else
|
||||
# define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_SLIDE
|
||||
#endif
|
||||
|
||||
const AP_Param::GroupInfo AC_Avoid::var_info[] = {
|
||||
|
||||
// @Param: ENABLE
|
||||
@ -39,7 +45,7 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = {
|
||||
// @Description: Avoidance behaviour (slide or stop)
|
||||
// @Values: 0:Slide,1:Stop
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("BEHAVE", 5, AC_Avoid, _behavior, 0),
|
||||
AP_GROUPINFO("BEHAVE", 5, AC_Avoid, _behavior, AP_AVOID_BEHAVE_DEFAULT),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user