mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 02:28:29 -04:00
autotest: use small INS offsets so INS is recognised as being calibrated
This commit is contained in:
parent
18b6c013dd
commit
113475b158
@ -65,3 +65,10 @@ ACRO_LOCKING 1
|
||||
ELEVON_OUTPUT 0
|
||||
VTAIL_OUTPUT 0
|
||||
SKIP_GYRO_CAL 1
|
||||
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
||||
INS_ACCOFFS_X 0.001
|
||||
INS_ACCOFFS_Y 0.001
|
||||
INS_ACCOFFS_Z 0.001
|
||||
INS_ACCSCAL_X 1.001
|
||||
INS_ACCSCAL_Y 1.001
|
||||
INS_ACCSCAL_Z 1.001
|
||||
|
@ -18,3 +18,10 @@ MODE6 0
|
||||
STEER2SRV_P 1.8
|
||||
SIM_GPS_DELAY 2
|
||||
NAVL1_PERIOD 6
|
||||
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
||||
INS_ACCOFFS_X 0.001
|
||||
INS_ACCOFFS_Y 0.001
|
||||
INS_ACCOFFS_Z 0.001
|
||||
INS_ACCSCAL_X 1.001
|
||||
INS_ACCSCAL_Y 1.001
|
||||
INS_ACCSCAL_Z 1.001
|
||||
|
@ -48,6 +48,13 @@ SIM_WIND_SPD 0
|
||||
SIM_WIND_TURB 0
|
||||
SIM_BARO_RND 0
|
||||
SIM_MAG_RND 0
|
||||
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
||||
INS_ACCOFFS_X 0.001
|
||||
INS_ACCOFFS_Y 0.001
|
||||
INS_ACCOFFS_Z 0.001
|
||||
INS_ACCSCAL_X 1.001
|
||||
INS_ACCSCAL_Y 1.001
|
||||
INS_ACCSCAL_Z 1.001
|
||||
# flightmodes
|
||||
# switch 1 Circle
|
||||
# switch 2 LAND
|
||||
|
@ -46,6 +46,13 @@ SIM_WIND_SPD 0
|
||||
SIM_WIND_TURB 0
|
||||
SIM_BARO_RND 0
|
||||
SIM_MAG_RND 0
|
||||
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
||||
INS_ACCOFFS_X 0.001
|
||||
INS_ACCOFFS_Y 0.001
|
||||
INS_ACCOFFS_Z 0.001
|
||||
INS_ACCSCAL_X 1.001
|
||||
INS_ACCSCAL_Y 1.001
|
||||
INS_ACCSCAL_Z 1.001
|
||||
# flightmodes
|
||||
# switch 1 Circle
|
||||
# switch 2 LAND
|
||||
|
Loading…
Reference in New Issue
Block a user