From 9e1502e54a0792e465e87f0aabb17d2d2c8ad3ab Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 8 Apr 2015 08:24:39 +0900 Subject: [PATCH] SITL: add wait_sim_seconds and get_sim_time --- Tools/autotest/common.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 821a71e3ed..927781fafe 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -55,6 +55,18 @@ def wait_seconds(seconds_to_wait): while tstart + seconds_to_wait > tnow: tnow = time.time() +def wait_sim_seconds(mav, seconds_to_wait): + m = mav.recv_match(type='SYSTEM_TIME', blocking=True) + tstart = m.time_boot_ms / 1000; + tnow = tstart + while tstart + seconds_to_wait > tnow: + m = mav.recv_match(type='SYSTEM_TIME', blocking=True) + tnow = m.time_boot_ms / 1000; + +def get_sim_time(mav): + m = mav.recv_match(type='SYSTEM_TIME', blocking=True) + return m.time_boot_ms / 1000; + def wait_altitude(mav, alt_min, alt_max, timeout=30): climb_rate = 0 previous_alt = 0