Skip to content

Commit

Permalink
AP_Scripting: raise max FLTE for yaw to 8
Browse files Browse the repository at this point in the history
better yaw for many vehicles
  • Loading branch information
tridge committed Sep 10, 2023
1 parent 94201f1 commit 40b41aa
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/applets/VTOL-quicktune.lua
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ local UPDATE_RATE_HZ = 40
local STAGE_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 FLTT_MUL = 0.5

Expand Down
8 changes: 5 additions & 3 deletions libraries/AP_Scripting/applets/VTOL-quicktune.md
Original file line number Diff line number Diff line change
Expand Up @@ -151,11 +151,13 @@ With default settings the parameters to be tuned will be:
- YAW_D
- 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 YAW_FLTE filter will be set to a maximum of 2Hz
- if no SMAX is set for a rate controller than the SMAX will be set to 50Hz
- the YAW_FLTE filter will be set to a maximum of 8Hz

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
can save the tune by moving the switch to the high position (Tune Save). You
Expand Down

0 comments on commit 40b41aa

Please sign in to comment.