From 77b7852ff09a6dbf0bb308ef4abb39ef7d5fa661 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 Jun 2016 11:04:03 +1000 Subject: [PATCH] Plane: adjust recommend ranges for quadplane Q_VFWD_GAIN and Q_WVANE_GAIN --- ArduPlane/quadplane.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 3a23caac8a..a6db4ca765 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -235,7 +235,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: VFWD_GAIN // @DisplayName: Forward velocity hold gain - // @Description: Controls use of forward motor in vtol modes. If this is zero then the forward motor will not be used for position control in VTOL modes. A value of 0.1 is a good place to start if you want to use the forward motor for position control. No forward motor will be used in QSTABILIZE or QHOVER modes. Use QLOITER for position hold with the forward motor. + // @Description: Controls use of forward motor in vtol modes. If this is zero then the forward motor will not be used for position control in VTOL modes. A value of 0.05 is a good place to start if you want to use the forward motor for position control. No forward motor will be used in QSTABILIZE or QHOVER modes. Use QLOITER for position hold with the forward motor. // @Range: 0 0.5 // @Increment: 0.01 // @User: Standard @@ -243,7 +243,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: WVANE_GAIN // @DisplayName: Weathervaning gain - // @Description: This controls the tendency to yaw to face into the wind. A value of 0.4 is good for reasonably quick wind direction correction. The weathervaning works by turning into the direction of roll. + // @Description: This controls the tendency to yaw to face into the wind. A value of 0.1 is to start with and will give a slow turn into the wind. Use a value of 0.4 for more rapid response. The weathervaning works by turning into the direction of roll. // @Range: 0 1 // @Increment: 0.01 // @User: Standard