From 366616e32c847d9b9bd932d51e6f9227cc059d2e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 9 Apr 2013 12:00:41 +0900 Subject: [PATCH] Copter: reduce default loiter PIDs --- ArduCopter/config.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index ce7bc6ebdb..4d3bd81e45 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -868,7 +868,7 @@ // Loiter position control gains // #ifndef LOITER_P - # define LOITER_P 2.0f + # define LOITER_P 1.0f #endif #ifndef LOITER_I # define LOITER_I 0.0f @@ -881,13 +881,13 @@ // Loiter rate control gains // #ifndef LOITER_RATE_P - # define LOITER_RATE_P 2.0f + # define LOITER_RATE_P 1.0f #endif #ifndef LOITER_RATE_I - # define LOITER_RATE_I 1.0f + # define LOITER_RATE_I 0.5f #endif #ifndef LOITER_RATE_D - # define LOITER_RATE_D 0.50f + # define LOITER_RATE_D 0.25f #endif #ifndef LOITER_RATE_IMAX # define LOITER_RATE_IMAX 30 // degrees