autotest: fixed DCM fallback test
give equivalent lag to old test
This commit is contained in:
parent
0ae04ba9dc
commit
2193f18ad7
@ -3305,7 +3305,7 @@ function'''
|
|||||||
self.set_parameters({
|
self.set_parameters({
|
||||||
"EK3_POS_I_GATE": 0,
|
"EK3_POS_I_GATE": 0,
|
||||||
"SIM_GPS_HZ": 1,
|
"SIM_GPS_HZ": 1,
|
||||||
"GPS_DELAY_MS": 300,
|
"SIM_GPS_LAG_MS": 1000,
|
||||||
})
|
})
|
||||||
self.wait_statustext("DCM Active", check_context=True, timeout=60)
|
self.wait_statustext("DCM Active", check_context=True, timeout=60)
|
||||||
self.wait_statustext("EKF3 Active", check_context=True)
|
self.wait_statustext("EKF3 Active", check_context=True)
|
||||||
|
Loading…
Reference in New Issue
Block a user