diff --git a/Tools/ArdupilotMegaPlanner/ArduCopterConfig.xml b/Tools/ArdupilotMegaPlanner/ArduCopterConfig.xml
index 2558e46e2c..fda38f6780 100644
--- a/Tools/ArdupilotMegaPlanner/ArduCopterConfig.xml
+++ b/Tools/ArdupilotMegaPlanner/ArduCopterConfig.xml
@@ -101,6 +101,70 @@ Too high = slow wobbles
0.001
+
+ Yaw Angular Rate Control:
+ How much throttle is applied to rotate the copter at the desired speed.
+
+
+
+ P
+ RATE_YAW_P
+ 0.001
+ 5
+ 0.001
+
+
+ I
+ RATE_YAW_I
+ 0
+ 5
+ 0.001
+
+
+ D
+ RATE_YAW_D
+ 0
+ 5
+ 0.001
+
+
+ IMAX
+ RATE_YAW_IMAX
+ 0
+ 50
+ 1
+
+
+
+ Yaw Stabilize Control:
+
+ How fast the copter reacts to user or autopilot input.
+ Higher = more aggressive control.
+ Too high = slow wobbles
+
+
+
+ P
+ STB_YAW_P
+ 0.001
+ 10
+ 0.001
+
+
+ I
+ STB_YAW_I
+ 0
+ 5
+ 0.001
+
+
+ IMAX
+ STB_YAW_IMAX
+ 0
+ 50
+ 1
+
+
-
@@ -140,7 +204,7 @@ How much angle is applied to make the copter accelerate to the desired speed.
LOITER_LON_IMAX
0
50
- 0.1
+ 1
Loiter Speed:
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index f9cfca5136..b318087f83 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -227,7 +227,7 @@
-
+
UserControl
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
index fd29bb2399..dc992d7842 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 e2bd4a8c51..a5d4591677 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 953649849d..fb29584b08 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 27d475f55d..d4498f0f5f 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 92d311e0c0..9bb4229ef3 100644
--- a/Tools/ArdupilotMegaPlanner/app.config
+++ b/Tools/ArdupilotMegaPlanner/app.config
@@ -9,7 +9,7 @@
+ value="http://ardupilot-mega.googlecode.com/git/ArduCopter/Parameters.pde"/>
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArduCopterConfig.xml b/Tools/ArdupilotMegaPlanner/bin/Release/ArduCopterConfig.xml
index 2558e46e2c..fda38f6780 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/ArduCopterConfig.xml
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/ArduCopterConfig.xml
@@ -101,6 +101,70 @@ Too high = slow wobbles
0.001
+
+ Yaw Angular Rate Control:
+ How much throttle is applied to rotate the copter at the desired speed.
+
+
+
+ P
+ RATE_YAW_P
+ 0.001
+ 5
+ 0.001
+
+
+ I
+ RATE_YAW_I
+ 0
+ 5
+ 0.001
+
+
+ D
+ RATE_YAW_D
+ 0
+ 5
+ 0.001
+
+
+ IMAX
+ RATE_YAW_IMAX
+ 0
+ 50
+ 1
+
+
+
+ Yaw Stabilize Control:
+
+ How fast the copter reacts to user or autopilot input.
+ Higher = more aggressive control.
+ Too high = slow wobbles
+
+
+
+ P
+ STB_YAW_P
+ 0.001
+ 10
+ 0.001
+
+
+ I
+ STB_YAW_I
+ 0
+ 5
+ 0.001
+
+
+ IMAX
+ STB_YAW_IMAX
+ 0
+ 50
+ 1
+
+
-
@@ -140,7 +204,7 @@ How much angle is applied to make the copter accelerate to the desired speed.
LOITER_LON_IMAX
0
50
- 0.1
+ 1
Loiter Speed:
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/version.txt b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt
index cf279dbac7..b68b098b7a 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