Browse Source

autotest: correct loiter-requires-position test for new SIM_GPS simulation

sitl_gps was sending out ubx packets even if the device was supposed to
be absent, allowing the EKF to get a lag and thus allocate its buffers.

The new sim doesn't do that, so we do need to direct the EKF to not use
the GPS.
gps-1.3.1
Peter Barker 3 years ago committed by Peter Barker
parent
commit
fda0d16475
  1. 8
      Tools/autotest/arducopter.py

8
Tools/autotest/arducopter.py

@ -5286,6 +5286,14 @@ class AutoTestCopter(AutoTest): @@ -5286,6 +5286,14 @@ class AutoTestCopter(AutoTest):
self.context_push()
self.set_parameter("GPS_TYPE", 2)
self.set_parameter("SIM_GPS_DISABLE", 1)
# if there is no GPS at all then we must direct EK3 to not use
# it at all. Otherwise it will never initialise, as it wants
# to calculate the lag and size its delay buffers accordingly.
self.set_parameters({
"EK3_SRC1_POSXY": 0,
"EK3_SRC1_VELZ": 0,
"EK3_SRC1_VELXY": 0,
})
self.reboot_sitl()
# check for expected EKF flags

Loading…
Cancel
Save