mirror of https://github.com/ArduPilot/ardupilot
AC_Avoidance: reduce maximum acceleration to 1m/s/s
This makes the vehicle slow very gently as it approaches the edge of the fence
This commit is contained in:
parent
a7422153cb
commit
a427768087
|
@ -8,7 +8,7 @@
|
|||
#include <AC_AttitudeControl/AC_AttitudeControl.h> // Attitude controller library for sqrt controller
|
||||
#include <AC_Fence/AC_Fence.h> // Failsafe fence library
|
||||
|
||||
#define AC_AVOID_ACCEL_CMSS_MAX 250.0f // maximum acceleration/deceleration in cm/s/s used to avoid hitting fence
|
||||
#define AC_AVOID_ACCEL_CMSS_MAX 100.0f // maximum acceleration/deceleration in cm/s/s used to avoid hitting fence
|
||||
|
||||
// bit masks for enabled fence types.
|
||||
#define AC_AVOID_DISABLED 0 // avoidance disabled
|
||||
|
|
Loading…
Reference in New Issue