mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_L1_Control: update NAV_L1_PERIOD docs
This commit is contained in:
parent
3813bcb7ce
commit
1fc8116069
@ -9,7 +9,7 @@ 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 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. 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 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.
|
||||
// @Units: seconds
|
||||
// @Range: 1-60
|
||||
// @Increment: 1
|
||||
|
Loading…
Reference in New Issue
Block a user