autotest: comment out unused context_start_custom_binary method

Broken under Python2.

Also fix some flake8 problems under flake8 under Python2
This commit is contained in:
Peter Barker 2022-07-21 09:58:09 +10:00 committed by Peter Barker
parent ea44da1e8d
commit 3e89e32d8a
1 changed files with 21 additions and 19 deletions

View File

@ -5041,23 +5041,24 @@ class AutoTest(ABC):
self.start_SITL(wipe=False) self.start_SITL(wipe=False)
self.set_streamrate(self.sitl_streamrate()) self.set_streamrate(self.sitl_streamrate())
def context_start_custom_binary(self, extra_defines={}): # the following method is broken under Python2; can't **build_opts
# grab copy of current binary: # def context_start_custom_binary(self, extra_defines={}):
context = self.context_get() # # grab copy of current binary:
if getattr(context, "old_binary", None) is not None: # context = self.context_get()
raise ValueError("Not nestable at the moment") # if getattr(context, "old_binary", None) is not None:
with open(self.binary, "rb") as f: # raise ValueError("Not nestable at the moment")
self.old_binary = f.read() # with open(self.binary, "rb") as f:
f.close() # self.old_binary = f.read()
build_opts = copy.copy(self.build_opts) # f.close()
build_opts["extra_defines"] = extra_defines # build_opts = copy.copy(self.build_opts)
util.build_SITL( # build_opts["extra_defines"] = extra_defines
'bin/arducopter', # FIXME! # util.build_SITL(
**build_opts, # 'bin/arducopter', # FIXME!
) # **build_opts,
self.stop_SITL() # )
self.start_SITL(wipe=False) # self.stop_SITL()
self.set_streamrate(self.sitl_streamrate()) # self.start_SITL(wipe=False)
# self.set_streamrate(self.sitl_streamrate())
class Context(object): class Context(object):
def __init__(self, testsuite): def __init__(self, testsuite):
@ -11088,7 +11089,8 @@ switch value'''
m = None m = None
text = text.rstrip("\0") text = text.rstrip("\0")
self.progress("Received frsky text (%s)" % (text,)) self.progress("Received frsky text (%s)" % (text,))
self.progress("context texts: %s" % str([x.text for x in self.context_collection('STATUSTEXT')])) self.progress("context texts: %s" %
str([st.text for st in self.context_collection('STATUSTEXT')]))
m = self.statustext_in_collections(text) m = self.statustext_in_collections(text)
if m is not None: if m is not None:
want_sev = m.severity want_sev = m.severity
@ -11101,7 +11103,7 @@ switch value'''
received_statustexts = self.context_collection('STATUSTEXT') received_statustexts = self.context_collection('STATUSTEXT')
if len(received_statustexts) != last_len_received_statustexts: if len(received_statustexts) != last_len_received_statustexts:
last_len_received_statustexts = len(received_statustexts) last_len_received_statustexts = len(received_statustexts)
self.progress("received statustexts: %s" % str([x.text for x in received_statustexts])) self.progress("received statustexts: %s" % str([st.text for st in received_statustexts]))
self.progress("received frsky texts: %s" % str(received_frsky_texts)) self.progress("received frsky texts: %s" % str(received_frsky_texts))
for (want_sev, received_text) in received_frsky_texts: for (want_sev, received_text) in received_frsky_texts:
for m in received_statustexts: for m in received_statustexts: