Frame_params: Solo notch filter params
Adds the dynamic harmonic notch filter and static notch filter to the Solo's default parameters. PID tuning parameters for the green cube Solo adjusted to take advantage of the better control.
This commit is contained in:
parent
de5945bea5
commit
b96a5d87b2
@ -70,6 +70,15 @@ GPS_NAVFILTER,6
|
||||
GPS_TYPE,1
|
||||
INS_ACC_BODYFIX,3
|
||||
INS_FAST_SAMPLE,3
|
||||
INS_HNTCH_ATT,40
|
||||
INS_HNTCH_ENABLE,1
|
||||
INS_HNTCH_REF,0.26
|
||||
INS_HNTCH_FREQ,200
|
||||
INS_HNTCH_BW,100
|
||||
INS_NOTCH_ATT,40
|
||||
INS_NOTCH_ENABLE,1
|
||||
INS_NOTCH_FREQ,98
|
||||
INS_NOTCH_BW,49
|
||||
INS_TRIM_OPTION,2
|
||||
LAND_ALT_LOW,600
|
||||
LAND_SPEED,45
|
||||
|
@ -15,14 +15,14 @@ ATC_ANG_PIT_P,10
|
||||
ATC_ANG_RLL_P,9
|
||||
ATC_ANG_YAW_P,6
|
||||
ATC_INPUT_TC,0.15
|
||||
ATC_RAT_PIT_D,0.006
|
||||
ATC_RAT_PIT_I,0.09
|
||||
ATC_RAT_PIT_D,0.0075
|
||||
ATC_RAT_PIT_I,0.270
|
||||
ATC_RAT_PIT_IMAX,0.444
|
||||
ATC_RAT_PIT_P,0.167
|
||||
ATC_RAT_PIT_P,0.270
|
||||
ATC_RAT_RLL_D,0.005
|
||||
ATC_RAT_RLL_I,0.12
|
||||
ATC_RAT_RLL_I,0.200
|
||||
ATC_RAT_RLL_IMAX,0.444
|
||||
ATC_RAT_RLL_P,0.086
|
||||
ATC_RAT_RLL_P,0.200
|
||||
ATC_RAT_YAW_FILT,5
|
||||
ATC_RAT_YAW_FLTE,5
|
||||
ATC_RAT_YAW_I,0.05
|
||||
@ -69,6 +69,15 @@ GPS_NAVFILTER,6
|
||||
GPS_TYPE,1
|
||||
INS_ACC_BODYFIX,3
|
||||
INS_FAST_SAMPLE,3
|
||||
INS_HNTCH_ATT,40
|
||||
INS_HNTCH_ENABLE,1
|
||||
INS_HNTCH_REF,0.26
|
||||
INS_HNTCH_FREQ,200
|
||||
INS_HNTCH_BW,100
|
||||
INS_NOTCH_ATT,40
|
||||
INS_NOTCH_ENABLE,1
|
||||
INS_NOTCH_FREQ,98
|
||||
INS_NOTCH_BW,49
|
||||
INS_TRIM_OPTION,2
|
||||
LAND_ALT_LOW,600
|
||||
LAND_SPEED,45
|
||||
|
10
Tools/Frame_params/test params stock solo.param
Normal file
10
Tools/Frame_params/test params stock solo.param
Normal file
@ -0,0 +1,10 @@
|
||||
# New stock cube notch params for chris to try
|
||||
INS_HNTCH_ATT,40
|
||||
INS_HNTCH_ENABLE,1
|
||||
INS_HNTCH_REF,0.26
|
||||
INS_HNTCH_FREQ,200
|
||||
INS_HNTCH_BW,100
|
||||
INS_NOTCH_ATT,40
|
||||
INS_NOTCH_ENABLE,1
|
||||
INS_NOTCH_FREQ,98
|
||||
INS_NOTCH_BW,49
|
16
Tools/Frame_params/test params.param
Normal file
16
Tools/Frame_params/test params.param
Normal file
@ -0,0 +1,16 @@
|
||||
# New Green Cube tuning and notch params for chris to try
|
||||
ATC_RAT_PIT_D,0.008
|
||||
ATC_RAT_PIT_I,0.280
|
||||
ATC_RAT_PIT_P,0.280
|
||||
ATC_RAT_RLL_D,0.005
|
||||
ATC_RAT_RLL_I,0.108
|
||||
ATC_RAT_RLL_P,0.108
|
||||
INS_HNTCH_ATT,40
|
||||
INS_HNTCH_ENABLE,1
|
||||
INS_HNTCH_REF,0.26
|
||||
INS_HNTCH_FREQ,200
|
||||
INS_HNTCH_BW,100
|
||||
INS_NOTCH_ATT,40
|
||||
INS_NOTCH_ENABLE,1
|
||||
INS_NOTCH_FREQ,98
|
||||
INS_NOTCH_BW,49
|
Loading…
Reference in New Issue
Block a user