From 74df1c0b2256214550b6b51fda44fa14368a78d3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 9 Feb 2022 12:07:14 +0900 Subject: [PATCH] AR_PosControl: reduce default I term to zero --- libraries/APM_Control/AR_PosControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/APM_Control/AR_PosControl.cpp b/libraries/APM_Control/AR_PosControl.cpp index ac868d4777..4317915439 100644 --- a/libraries/APM_Control/AR_PosControl.cpp +++ b/libraries/APM_Control/AR_PosControl.cpp @@ -27,7 +27,7 @@ extern const AP_HAL::HAL& hal; #define AR_POSCON_TIMEOUT_MS 100 // timeout after 0.1 sec #define AR_POSCON_POS_P 0.2f // default position P gain #define AR_POSCON_VEL_P 1.0f // default velocity P gain -#define AR_POSCON_VEL_I 0.2f // default velocity I gain +#define AR_POSCON_VEL_I 0.0f // default velocity I gain #define AR_POSCON_VEL_D 0.0f // default velocity D gain #define AR_POSCON_VEL_FF 0.0f // default velocity FF gain #define AR_POSCON_VEL_IMAX 1.0f // default velocity IMAX