mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
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.
This commit is contained in:
parent
f028747399
commit
425ab1358a
@ -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
|
||||
|
||||
|
@ -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()
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user