AC_WPNav: increase max accel to 8m/s/s

This commit is contained in:
Randy Mackay 2013-04-15 21:57:56 +09:00
parent 8fe3e689f4
commit 8046fe2cf3

View File

@ -13,7 +13,7 @@
// loiter maximum velocities and accelerations // 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_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_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. // 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 // max acceleration = max lean angle * 980 * pi / 180. i.e. 23deg * 980 * 3.141 / 180 = 393 cm/s/s