diff --git a/Tools/ArdupilotMegaPlanner/ArduCopterConfig.xml b/Tools/ArdupilotMegaPlanner/ArduCopterConfig.xml
index 2558e46e2c8022bcb52c9e741b1213e441e8bd02..fda38f6780653459242fc80c616f181ad72dfae0 100644
--- a/Tools/ArdupilotMegaPlanner/ArduCopterConfig.xml
+++ b/Tools/ArdupilotMegaPlanner/ArduCopterConfig.xml
@@ -101,6 +101,70 @@ Too high = slow wobbles
         <STEP>0.001</STEP>
       </FIELD>
     </FIELDS>
+
+    <SUBHEAD>Yaw Angular Rate Control:</SUBHEAD>
+    <DESC>How much throttle is applied to rotate the copter at the desired speed.
+    </DESC>
+    <FIELDS>
+      <FIELD>
+        <NAME>P</NAME>
+        <PARAMNAME>RATE_YAW_P</PARAMNAME>
+        <RANGEMIN>0.001</RANGEMIN>
+        <RANGEMAX>5</RANGEMAX>
+        <STEP>0.001</STEP>
+      </FIELD>
+      <FIELD>
+        <NAME>I</NAME>
+        <PARAMNAME>RATE_YAW_I</PARAMNAME>
+        <RANGEMIN>0</RANGEMIN>
+        <RANGEMAX>5</RANGEMAX>
+        <STEP>0.001</STEP>
+      </FIELD>
+      <FIELD>
+        <NAME>D</NAME>
+        <PARAMNAME>RATE_YAW_D</PARAMNAME>
+        <RANGEMIN>0</RANGEMIN>
+        <RANGEMAX>5</RANGEMAX>
+        <STEP>0.001</STEP>
+      </FIELD>
+      <FIELD>
+        <NAME>IMAX</NAME>
+        <PARAMNAME>RATE_YAW_IMAX</PARAMNAME>
+        <RANGEMIN>0</RANGEMIN>
+        <RANGEMAX>50</RANGEMAX>
+        <STEP>1</STEP>
+      </FIELD>
+    </FIELDS>
+
+    <SUBHEAD>Yaw Stabilize Control:</SUBHEAD>
+    <DESC>
+      How fast the copter reacts to user or autopilot input.
+      Higher = more aggressive control.
+      Too high = slow wobbles
+    </DESC>
+    <FIELDS>
+      <FIELD>
+        <NAME>P</NAME>
+        <PARAMNAME>STB_YAW_P</PARAMNAME>
+        <RANGEMIN>0.001</RANGEMIN>
+        <RANGEMAX>10</RANGEMAX>
+        <STEP>0.001</STEP>
+      </FIELD>
+      <FIELD>
+        <NAME>I</NAME>
+        <PARAMNAME>STB_YAW_I</PARAMNAME>
+        <RANGEMIN>0</RANGEMIN>
+        <RANGEMAX>5</RANGEMAX>
+        <STEP>0.001</STEP>
+      </FIELD>
+      <FIELD>
+        <NAME>IMAX</NAME>
+        <PARAMNAME>STB_YAW_IMAX</PARAMNAME>
+        <RANGEMIN>0</RANGEMIN>
+        <RANGEMAX>50</RANGEMAX>
+        <STEP>1</STEP>
+      </FIELD>
+    </FIELDS>
   </Item>
   <!-- Loiter -->
   <Item>
@@ -140,7 +204,7 @@ How much angle is applied to make the copter accelerate to the desired speed.
         <PARAMNAME>LOITER_LON_IMAX</PARAMNAME>
         <RANGEMIN>0</RANGEMIN>
         <RANGEMAX>50</RANGEMAX>
-        <STEP>0.1</STEP>
+        <STEP>1</STEP>
       </FIELD>
     </FIELDS>
     <SUBHEAD>Loiter Speed:</SUBHEAD>
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index f9cfca5136a2e27fe8f292e89b886c0b2de78cb2..b318087f83590a47972b034963d31c86a2ccb17a 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -227,7 +227,7 @@
     <Compile Include="Attributes\PrivateAttribute.cs" />
     <Compile Include="CodeGen.cs" />
     <Compile Include="Utilities\CollectionExtensions.cs" />
-    <Compile Include="Utilities\Constants\ParameterMetaDataConstants.cs" />
+    <Compile Include="Utilities\ParameterMetaDataConstants.cs" />
     <Compile Include="Controls\BackstageView\BackstageView.cs">
       <SubType>UserControl</SubType>
     </Compile>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
index fd29bb23998cb7958ce11bbd67cb8c4d318ed806..dc992d7842fd3412e45a1396670a2b1ca8897bad 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
@@ -6,7 +6,6 @@ using System.IO;
 using System.Text;
 using System.Windows.Forms;
 using ArdupilotMega.Utilities;
-using ArdupilotMega.Utilities.Constants;
 using log4net;
 using ArdupilotMega.Controls.BackstageView;
 
diff --git a/Tools/ArdupilotMegaPlanner/Msi/wix.pdb b/Tools/ArdupilotMegaPlanner/Msi/wix.pdb
index e2bd4a8c51e6596bf41da25015857ed84be7ef85..a5d459167772c92af2f5da9b7b52010c246af54a 100644
Binary files a/Tools/ArdupilotMegaPlanner/Msi/wix.pdb and b/Tools/ArdupilotMegaPlanner/Msi/wix.pdb differ
diff --git a/Tools/ArdupilotMegaPlanner/Utilities/Constants/ParameterMetaDataConstants.cs b/Tools/ArdupilotMegaPlanner/Utilities/ParameterMetaDataConstants.cs
similarity index 92%
rename from Tools/ArdupilotMegaPlanner/Utilities/Constants/ParameterMetaDataConstants.cs
rename to Tools/ArdupilotMegaPlanner/Utilities/ParameterMetaDataConstants.cs
index 953649849db75f3ddec0582c461a946d95fbf403..fb29584b08521b229ca8621f0f818c2c149f7732 100644
--- a/Tools/ArdupilotMegaPlanner/Utilities/Constants/ParameterMetaDataConstants.cs
+++ b/Tools/ArdupilotMegaPlanner/Utilities/ParameterMetaDataConstants.cs
@@ -1,4 +1,4 @@
-namespace ArdupilotMega.Utilities.Constants
+namespace ArdupilotMega.Utilities
 {
    public sealed class ParameterMetaDataConstants
    {
@@ -21,4 +21,4 @@
 
       #endregion
    }
-}
+}
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Utilities/ParameterMetaDataParser.cs b/Tools/ArdupilotMegaPlanner/Utilities/ParameterMetaDataParser.cs
index 27d475f55db532341a05ffc7d25158681183c40b..d4498f0f5f391ee52658e704194fe03897cc9ab0 100644
--- a/Tools/ArdupilotMegaPlanner/Utilities/ParameterMetaDataParser.cs
+++ b/Tools/ArdupilotMegaPlanner/Utilities/ParameterMetaDataParser.cs
@@ -7,7 +7,7 @@ using System.Net;
 using System.Text.RegularExpressions;
 using System.Windows.Forms;
 using System.Xml;
-using ArdupilotMega.Utilities.Constants;
+using ArdupilotMega.Utilities;
 using log4net;
 
 namespace ArdupilotMega.Utilities
diff --git a/Tools/ArdupilotMegaPlanner/app.config b/Tools/ArdupilotMegaPlanner/app.config
index 92d311e0c07fd2b3a951454edd5d1893a8685c4c..9bb4229ef3a09b9535adbc50996f8768c806b4cd 100644
--- a/Tools/ArdupilotMegaPlanner/app.config
+++ b/Tools/ArdupilotMegaPlanner/app.config
@@ -9,7 +9,7 @@
     <add key="UpdateLocation"
       value="http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/"/>
     <add key="ParameterLocations"
-      value="http://a432511-wip.googlecode.com/git-history/param-suffix/ArduCopter/Parameters.pde"/>
+      value="http://ardupilot-mega.googlecode.com/git/ArduCopter/Parameters.pde"/>
     <add key="ParameterMetaDataXMLFileName"
       value="ParameterMetaData.xml"/>
   </appSettings>
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArduCopterConfig.xml b/Tools/ArdupilotMegaPlanner/bin/Release/ArduCopterConfig.xml
index 2558e46e2c8022bcb52c9e741b1213e441e8bd02..fda38f6780653459242fc80c616f181ad72dfae0 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/ArduCopterConfig.xml
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/ArduCopterConfig.xml
@@ -101,6 +101,70 @@ Too high = slow wobbles
         <STEP>0.001</STEP>
       </FIELD>
     </FIELDS>
+
+    <SUBHEAD>Yaw Angular Rate Control:</SUBHEAD>
+    <DESC>How much throttle is applied to rotate the copter at the desired speed.
+    </DESC>
+    <FIELDS>
+      <FIELD>
+        <NAME>P</NAME>
+        <PARAMNAME>RATE_YAW_P</PARAMNAME>
+        <RANGEMIN>0.001</RANGEMIN>
+        <RANGEMAX>5</RANGEMAX>
+        <STEP>0.001</STEP>
+      </FIELD>
+      <FIELD>
+        <NAME>I</NAME>
+        <PARAMNAME>RATE_YAW_I</PARAMNAME>
+        <RANGEMIN>0</RANGEMIN>
+        <RANGEMAX>5</RANGEMAX>
+        <STEP>0.001</STEP>
+      </FIELD>
+      <FIELD>
+        <NAME>D</NAME>
+        <PARAMNAME>RATE_YAW_D</PARAMNAME>
+        <RANGEMIN>0</RANGEMIN>
+        <RANGEMAX>5</RANGEMAX>
+        <STEP>0.001</STEP>
+      </FIELD>
+      <FIELD>
+        <NAME>IMAX</NAME>
+        <PARAMNAME>RATE_YAW_IMAX</PARAMNAME>
+        <RANGEMIN>0</RANGEMIN>
+        <RANGEMAX>50</RANGEMAX>
+        <STEP>1</STEP>
+      </FIELD>
+    </FIELDS>
+
+    <SUBHEAD>Yaw Stabilize Control:</SUBHEAD>
+    <DESC>
+      How fast the copter reacts to user or autopilot input.
+      Higher = more aggressive control.
+      Too high = slow wobbles
+    </DESC>
+    <FIELDS>
+      <FIELD>
+        <NAME>P</NAME>
+        <PARAMNAME>STB_YAW_P</PARAMNAME>
+        <RANGEMIN>0.001</RANGEMIN>
+        <RANGEMAX>10</RANGEMAX>
+        <STEP>0.001</STEP>
+      </FIELD>
+      <FIELD>
+        <NAME>I</NAME>
+        <PARAMNAME>STB_YAW_I</PARAMNAME>
+        <RANGEMIN>0</RANGEMIN>
+        <RANGEMAX>5</RANGEMAX>
+        <STEP>0.001</STEP>
+      </FIELD>
+      <FIELD>
+        <NAME>IMAX</NAME>
+        <PARAMNAME>STB_YAW_IMAX</PARAMNAME>
+        <RANGEMIN>0</RANGEMIN>
+        <RANGEMAX>50</RANGEMAX>
+        <STEP>1</STEP>
+      </FIELD>
+    </FIELDS>
   </Item>
   <!-- Loiter -->
   <Item>
@@ -140,7 +204,7 @@ How much angle is applied to make the copter accelerate to the desired speed.
         <PARAMNAME>LOITER_LON_IMAX</PARAMNAME>
         <RANGEMIN>0</RANGEMIN>
         <RANGEMAX>50</RANGEMAX>
-        <STEP>0.1</STEP>
+        <STEP>1</STEP>
       </FIELD>
     </FIELDS>
     <SUBHEAD>Loiter Speed:</SUBHEAD>
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/version.txt b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt
index cf279dbac70c778e06cd683e3db7c8535e628f1c..b68b098b7a9eaee2814f060456ed85826ef27c7f 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/version.txt
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt
@@ -1 +1 @@
-1.1.4498.32482
\ No newline at end of file
+1.1.4499.14296
\ No newline at end of file