From 069bd17928b3c6eb3722cea89a64f0ee62fed048 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 16 Jun 2013 15:31:36 +0900 Subject: [PATCH] Copter: reduce default AltHold P to 1.0 (was 2.0) This helps reduce jumpiness due to althold feed forward --- ArduCopter/ReleaseNotes.txt | 1 + ArduCopter/config.h | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index 8fc2932261..31b2a9a2c6 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -5,6 +5,7 @@ Improvements over 3.0.0-rc5 1) bug fix to Circle mode's start position (was moving to last loiter target) 2) WP_ACCEL parameter added to allow user to adjust acceleration during missions 3) loiter acceleration set to half of LOIT_SPEED parameter value (was hard-coded) +4) reduce AltHold P to 1.0 (was 2.0) ------------------------------------------------------------------ ArduCopter 3.0.0-rc5 04-Jun-2013 Improvements over 3.0.0-rc4 diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 1a5dc7bcfe..42ac765954 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -918,7 +918,7 @@ #endif #ifndef ALT_HOLD_P - # define ALT_HOLD_P 2.0f + # define ALT_HOLD_P 1.0f #endif #ifndef ALT_HOLD_I # define ALT_HOLD_I 0.0f