mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
autotest: make polling home position quiet by default
This commit is contained in:
parent
5318538182
commit
e7aefc7fe4
@ -5160,7 +5160,7 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
mavutil.dump_message_verbose(f, m)
|
mavutil.dump_message_verbose(f, m)
|
||||||
return f.getvalue()
|
return f.getvalue()
|
||||||
|
|
||||||
def poll_home_position(self, quiet=False, timeout=30):
|
def poll_home_position(self, quiet=True, timeout=30):
|
||||||
old = self.mav.messages.get("HOME_POSITION", None)
|
old = self.mav.messages.get("HOME_POSITION", None)
|
||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
while True:
|
while True:
|
||||||
@ -5188,6 +5188,7 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
break
|
break
|
||||||
if m._timestamp != old._timestamp:
|
if m._timestamp != old._timestamp:
|
||||||
break
|
break
|
||||||
|
self.progress("Polled home position (%s)" % str(m))
|
||||||
return m
|
return m
|
||||||
|
|
||||||
def distance_to_home(self, use_cached_home=False):
|
def distance_to_home(self, use_cached_home=False):
|
||||||
|
Loading…
Reference in New Issue
Block a user