From 8046fe2cf30e84735e6566bb6c9e29dceac0ebae Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 15 Apr 2013 21:57:56 +0900 Subject: [PATCH] AC_WPNav: increase max accel to 8m/s/s --- libraries/AC_WPNav/AC_WPNav.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index 75803b3860..3bc0ea4466 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -13,7 +13,7 @@ // loiter maximum velocities and accelerations #define MAX_LOITER_POS_VELOCITY 500 // maximum velocity that our position controller will request. should be 1.5 ~ 2.0 times the pilot input's max velocity. To-Do: make consistent with maximum velocity requested by pilot input to loiter #define MAX_LOITER_POS_ACCEL 250 // defines the velocity vs distant curve. maximum acceleration in cm/s/s that loiter position controller asks for from acceleration controller -#define MAX_LOITER_VEL_ACCEL 400 // max acceleration in cm/s that the loiter velocity controller will ask from the lower accel controller. +#define MAX_LOITER_VEL_ACCEL 800 // max acceleration in cm/s/s that the loiter velocity controller will ask from the lower accel controller. // should be 1.5 times larger than MAX_LOITER_POS_ACCEL. // max acceleration = max lean angle * 980 * pi / 180. i.e. 23deg * 980 * 3.141 / 180 = 393 cm/s/s