mirror of https://github.com/ArduPilot/ardupilot
autotest: ignore type=0 heartbeat packets on SITL start
Until ArduCopter allocates its motors backend we emit a generic type, for which there is no mode map in pymavlink. So don't consider the reboot complete until we see a valid heartbeat.
This commit is contained in:
parent
ec15614e11
commit
dbee2e5d71
|
@ -2133,7 +2133,10 @@ class AutoTest(ABC):
|
|||
if time.time() - tstart > 30:
|
||||
raise NotAchievedException("Failed to customise")
|
||||
try:
|
||||
self.wait_heartbeat(drain_mav=True)
|
||||
m = self.wait_heartbeat(drain_mav=True)
|
||||
if m.type == 0:
|
||||
self.progress("Bad heartbeat: %s" % str(m))
|
||||
continue
|
||||
except IOError:
|
||||
pass
|
||||
break
|
||||
|
|
Loading…
Reference in New Issue