From 425ab1358a4bbdca4189b341b0b35251137d1bf5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 1 Mar 2021 10:44:36 +1100 Subject: [PATCH] autotest: tidy streamrate handling Stop setting MAVProxy stream rates; these are neither here-nor-there now as MAVProxy will only modify its own connection's streamrates now Stop doing the set-streamrate dance to work around MAVProxy's set_streamrate algorithms. Remove useless and misleading set of streamrate in Plane test; we reset streamrates on the reboot immediately following this set. Considering the streamrate was never eset this was a good thing. --- Tools/autotest/arducopter.py | 3 --- Tools/autotest/arduplane.py | 1 - Tools/autotest/common.py | 17 +---------------- 3 files changed, 1 insertion(+), 20 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 9f9abb9dc1..9a0f4c3ff5 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -1816,7 +1816,6 @@ class AutoTestCopter(AutoTest): def fly_flip(self): ex = None try: - self.mavproxy.send("set streamrate -1\n") self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_ATTITUDE, 100) self.takeoff(20) @@ -1853,8 +1852,6 @@ class AutoTestCopter(AutoTest): self.print_exception_caught(e) ex = e self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_ATTITUDE, 0) - sr = self.sitl_streamrate() - self.mavproxy.send("set streamrate %u\n" % sr) if ex is not None: raise ex diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 13e10b3439..4b6c14e221 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -2173,7 +2173,6 @@ class AutoTestPlane(AutoTest): "INS_TCAL2_TMAX": 42, "SIM_SPEEDUP": 200, }) - self.set_streamrate(1) self.set_parameter("LOG_DISARMED", 1) self.reboot_sitl() diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 9e42509c7f..465fb55338 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -2113,9 +2113,7 @@ class AutoTest(ABC): def initialise_after_reboot_sitl(self): - # after reboot stream-rates may be zero. Prompt MAVProxy to - # send a rate-change message by changing away from our normal - # stream rates and back again: + # after reboot stream-rates may be zero. Request streams. self.drain_mav() self.wait_heartbeat() self.set_streamrate(self.sitl_streamrate()) @@ -2138,12 +2136,7 @@ class AutoTest(ABC): except IOError: pass break - # MAVProxy only checks the streamrates once every 15 seconds. - # Encourage it: - self.set_streamrate(self.sitl_streamrate()+1) self.set_streamrate(self.sitl_streamrate()) - # we also need to wait for MAVProxy to requests streams again - # - in particular, RC_CHANNELS. m = self.mav.recv_match(type='RC_CHANNELS', blocking=True, timeout=15) if m is None: raise NotAchievedException("No RC_CHANNELS message after restarting SITL") @@ -2159,7 +2152,6 @@ class AutoTest(ABC): self.progress("Resetting SITL commandline to default") self.stop_SITL() self.start_SITL(wipe=True) - self.set_streamrate(self.sitl_streamrate()+1) self.set_streamrate(self.sitl_streamrate()) self.apply_defaultfile_parameters() try: @@ -7346,9 +7338,6 @@ Also, ignores heartbeats not from our target system''' self.victim_message_id = mavutil.mavlink.MAVLINK_MSG_ID_VFR_HUD ex = None try: - # tell MAVProxy to stop stuffing around with the rates: - self.mavproxy.send("set streamrate -1\n") - rate = round(self.get_message_rate(self.victim_message, 20)) self.progress("Initial rate: %u" % rate) @@ -7404,10 +7393,6 @@ Also, ignores heartbeats not from our target system''' self.progress("Resetting CAMERA_FEEDBACK rate to zero") self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK, -1) - # tell MAVProxy to start stuffing around with the rates: - sr = self.sitl_streamrate() - self.mavproxy.send("set streamrate %u\n" % sr) - if ex is not None: raise ex