AP_Scripting: raise max FLTE for yaw to 8

better yaw for many vehicles
This commit is contained in:
Andrew Tridgell 2023-09-10 12:30:55 +10:00
parent b83a895d7b
commit 1794c128a2
2 changed files with 6 additions and 4 deletions

View File

@ -183,7 +183,7 @@ local UPDATE_RATE_HZ = 40
local STAGE_DELAY = 4.0 local STAGE_DELAY = 4.0
local PILOT_INPUT_DELAY = 4.0 local PILOT_INPUT_DELAY = 4.0
local YAW_FLTE_MAX = 2.0 local YAW_FLTE_MAX = 8.0
local FLTD_MUL = 0.5 local FLTD_MUL = 0.5
local FLTT_MUL = 0.5 local FLTT_MUL = 0.5

View File

@ -151,11 +151,13 @@ With default settings the parameters to be tuned will be:
- YAW_D - YAW_D
- YAW_P - YAW_P
The script will also adjust filter settings using the following rules: The script will also adjust filter settings using the following rules
if QUIK_AUTO_FILTER is set to 1 (which is the default):
- the FLTD and FLTT settings will be set to half of the INS_GYRO_FILTER value - the FLTD and FLTT settings will be set to half of the INS_GYRO_FILTER value
- the YAW_FLTE filter will be set to a maximum of 2Hz - the YAW_FLTE filter will be set to a maximum of 8Hz
- if no SMAX is set for a rate controller than the SMAX will be set to 50Hz
Additionally, if no SMAX is set for a rate controller than the SMAX will be set to 50Hz.
Once the tuning is finished you will see a "Tuning: done" message. You Once the tuning is finished you will see a "Tuning: done" message. You
can save the tune by moving the switch to the high position (Tune Save). You can save the tune by moving the switch to the high position (Tune Save). You