diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt
index 8fc29322613b905e5cd8f11b32985afaae985e4c..31b2a9a2c6991227598ff7a89c26889fa3c106c3 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 1a5dc7bcfe13c9c8d316fc85a7be9319e4cedf37..42ac76595491410e7817a860b224f026f2f5601a 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