diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index b4d9b35ffc..d3a94bc63c 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -990,6 +990,33 @@ class AutoTestCopter(AutoTest): self.progress("CIRCLE OK for %u seconds" % holdtime) + # fly_autotune - autotune the virtual vehicle + def fly_autotune(self): + + # hold position in loiter + self.mavproxy.send('mode autotune\n') + self.wait_mode('AUTOTUNE') + + tstart = self.get_sim_time() + sim_time_expected = 5000 + deadline = tstart + sim_time_expected + while self.get_sim_time_cached() < deadline: + now = self.get_sim_time_cached() + m = self.mav.recv_match(type='STATUSTEXT', + blocking=True, + timeout=1) + if m is None: + continue + self.progress("STATUSTEXT (%u<%u): %s" % (now, deadline, m.text)) + if "AutoTune: Success" in m.text: + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + # near enough for now: + return + + self.progress("AUTOTUNE failed (%u seconds)" % + (self.get_sim_time() - tstart)) + raise NotAchievedException() + # fly_auto_test - fly mission which tests a significant number of commands def fly_auto_test(self): # Fly mission #1 @@ -1396,6 +1423,9 @@ class AutoTestCopter(AutoTest): self.run_test("Takeoff to test fly Square", lambda: self.takeoff(10)) + # AutoTune mode + self.run_test("Fly AUTOTUNE mode", self.fly_autotune) + # Fly a square in Stabilize mode self.run_test("Fly a square and save WPs with CH7", self.fly_square) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 86cb316eae..79db695eb7 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -263,6 +263,13 @@ class AutoTest(ABC): m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True) return m.time_boot_ms * 1.0e-3 + def get_sim_time_cached(self): + """Get SITL time.""" + x = self.mav.messages.get("SYSTEM_TIME", None) + if x is None: + return self.get_sim_time() + return x.time_boot_ms * 1.0e-3 + def sim_location(self): """Return current simulator location.""" m = self.mav.recv_match(type='SIMSTATE', blocking=True) @@ -348,7 +355,7 @@ class AutoTest(ABC): def set_rc(self, chan, pwm, timeout=20): """Setup a simulated RC control to a PWM value""" tstart = self.get_sim_time() - while self.get_sim_time() < tstart + timeout: + while self.get_sim_time_cached() < tstart + timeout: self.mavproxy.send('rc %u %u\n' % (chan, pwm)) m = self.mav.recv_match(type='RC_CHANNELS', blocking=True) chan_pwm = getattr(m, "chan" + str(chan) + "_raw")