mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Scripting: fixed pitch param reversion in revert_param.lua
This commit is contained in:
parent
1d08662c72
commit
303c33411f
@ -57,7 +57,7 @@ local PID_prefixes = { "_RAT_RLL_", "_RAT_PIT_", "_RAT_YAW_" }
|
||||
local PID_suffixes = { "FF", "P", "I", "D", "D_FF", "PDMX", "NEF", "NTF", "IMAX", "FLTD", "FLTE", "FLTT", "SMAX" }
|
||||
local angle_axes = { "RLL", "PIT", "YAW" }
|
||||
local PSC_types = { "ACCZ", "VELZ", "POSZ", "VELXY", "POSXY" }
|
||||
local OTHER_PARAMS = { "INS_GYRO_FILTER", "INS_ACCEL_FILTER" }
|
||||
local OTHER_PARAMS = { "INS_GYRO_FILTER", "INS_ACCEL_FILTER", "PTCH2SRV_TCONST", "RLL2SRV_TCONST" }
|
||||
|
||||
if PREV_ENABLE:get() == 0 then
|
||||
return
|
||||
@ -92,7 +92,7 @@ end
|
||||
-- add fixed wing tuning
|
||||
for _, suffix in ipairs(PID_suffixes) do
|
||||
add_param("RLL_RATE_" .. suffix)
|
||||
add_param("PIT_RATE_" .. suffix)
|
||||
add_param("PTCH_RATE_" .. suffix)
|
||||
add_param("YAW_RATE_" .. suffix)
|
||||
end
|
||||
|
||||
|
@ -47,9 +47,6 @@ The script covers the following parameters on quadplanes:
|
||||
- Q_A_ANG_RLL_P
|
||||
- Q_A_ANG_PIT_P
|
||||
- Q_A_ANG_YAW_P
|
||||
- RLL_RATE_*
|
||||
- PTCH_RATE_*
|
||||
- YAW_RATE_*
|
||||
- Q_P_ACCZ_*
|
||||
- Q_P_VELZ_*
|
||||
- Q_P_POSZ_*
|
||||
@ -69,3 +66,10 @@ The script covers the following parameters on copters:
|
||||
- PSC_POSZ_*
|
||||
- PSC_VELXY_*
|
||||
- PSC_POSXY_*
|
||||
|
||||
For fixed wing the following parameters are covered:
|
||||
|
||||
- RLL_RATE_*
|
||||
- PTCH_RATE_*
|
||||
- RLL2SRV_TCONST
|
||||
- PTCH2SRV_TCONST
|
||||
|
Loading…
Reference in New Issue
Block a user