From e0fc2dd50e77b77f1e480e9feccc76f5283174ff Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 5 Aug 2014 09:11:57 +0900 Subject: [PATCH] AC_PosControl: remove 20cm on takeoff --- libraries/AC_AttitudeControl/AC_PosControl.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 9d84daf3ab..14ce41faf1 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -21,7 +21,7 @@ #define POSCONTROL_STOPPING_DIST_Z_MAX 200.0f // max stopping distance vertically // should be 1.5 times larger than POSCONTROL_ACCELERATION. // max acceleration = max lean angle * 980 * pi / 180. i.e. 23deg * 980 * 3.141 / 180 = 393 cm/s/s -#define POSCONTROL_TAKEOFF_JUMP_CM 20.0f // during take-off altitude target is set to current altitude + this value +#define POSCONTROL_TAKEOFF_JUMP_CM 0.0f // during take-off altitude target is set to current altitude + this value #define POSCONTROL_SPEED 500.0f // default horizontal speed in cm/s #define POSCONTROL_SPEED_DOWN -150.0f // default descent rate in cm/s