mirror of https://github.com/ArduPilot/ardupilot
Disco: adjust default Disco parameters
This commit is contained in:
parent
52caf8419e
commit
19d580d60f
|
@ -18,17 +18,17 @@ FLTMODE6 0
|
||||||
FLTMODE_CH 5
|
FLTMODE_CH 5
|
||||||
FS_GCS_ENABL 0
|
FS_GCS_ENABL 0
|
||||||
INS_ACCEL_FILTER 10
|
INS_ACCEL_FILTER 10
|
||||||
INS_GYRO_FILTER 10
|
INS_GYRO_FILTER 5
|
||||||
LAND_FLARE_ALT 3
|
LAND_FLARE_ALT 3
|
||||||
LAND_FLARE_SEC 2
|
LAND_FLARE_SEC 2
|
||||||
LIM_PITCH_MAX 3000
|
LIM_PITCH_MAX 3000
|
||||||
LIM_PITCH_MIN -2500
|
LIM_PITCH_MIN -2500
|
||||||
LIM_ROLL_CD 5500
|
LIM_ROLL_CD 5500
|
||||||
NAVL1_PERIOD 16
|
NAVL1_PERIOD 16
|
||||||
PTCH2SRV_D 0.146462
|
PTCH2SRV_D 0.07
|
||||||
PTCH2SRV_I 0.4
|
PTCH2SRV_I 0.4
|
||||||
PTCH2SRV_IMAX 3000
|
PTCH2SRV_IMAX 3000
|
||||||
PTCH2SRV_P 1.952827
|
PTCH2SRV_P 1.8
|
||||||
PTCH2SRV_RLL 1.0
|
PTCH2SRV_RLL 1.0
|
||||||
PTCH2SRV_RMAX_DN 75
|
PTCH2SRV_RMAX_DN 75
|
||||||
PTCH2SRV_RMAX_UP 75
|
PTCH2SRV_RMAX_UP 75
|
||||||
|
|
Loading…
Reference in New Issue