From b21c00fcf9ac706c488f81afd1b4ac91bcc4ad2c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 19 Feb 2015 16:19:33 +1100 Subject: [PATCH] AP_L1_Control: changed default L1 tuning to 20 this is more appropriate for most aircraft --- libraries/AP_L1_Control/AP_L1_Control.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index 6a1e579cef..d770e09f26 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -9,11 +9,11 @@ extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_L1_Control::var_info[] PROGMEM = { // @Param: PERIOD // @DisplayName: L1 control period - // @Description: Period in seconds of L1 tracking loop. This parameter is the primary control for agressiveness of turns in auto mode. This needs to be larger for less responsive airframes. The default of 30 is very conservative, and for most RC aircraft will lead to slow and lazy turns. For smaller more agile aircraft a value closer to 20 is appropriate, or even as low as 10 for some very agile aircraft. When tuning, change this value in small increments, as a value that is much too small (say 5 or 10 below the right value) can lead to very radical turns, and a risk of stalling. + // @Description: Period in seconds of L1 tracking loop. This parameter is the primary control for agressiveness of turns in auto mode. This needs to be larger for less responsive airframes. The default of 20 is quite conservative, but for most RC aircraft will lead to reasonable flight. For smaller more agile aircraft a value closer to 15 is appropriate, or even as low as 10 for some very agile aircraft. When tuning, change this value in small increments, as a value that is much too small (say 5 or 10 below the right value) can lead to very radical turns, and a risk of stalling. // @Units: seconds // @Range: 1-60 // @Increment: 1 - AP_GROUPINFO("PERIOD", 0, AP_L1_Control, _L1_period, 25), + AP_GROUPINFO("PERIOD", 0, AP_L1_Control, _L1_period, 20), // @Param: DAMPING // @DisplayName: L1 control damping ratio