Tools: Test for membership should be `not in`

This commit is contained in:
Pierre Kancir 2023-08-31 23:46:25 +02:00 committed by Peter Barker
parent 31ee88adbb
commit 9d76d1e3df
11 changed files with 15 additions and 15 deletions

View File

@ -756,7 +756,7 @@ class DataflashLog(object):
else: else:
raise Exception("") raise Exception("")
else: else:
if not tokens[0] in self.formats: if tokens[0] not in self.formats:
raise ValueError("Unknown Format {}".format(tokens[0])) raise ValueError("Unknown Format {}".format(tokens[0]))
e = self.formats[tokens[0]](*tokens[1:]) e = self.formats[tokens[0]](*tokens[1:])
self.process(lineNumber, e) self.process(lineNumber, e)

View File

@ -40,7 +40,7 @@ def check_log(logfile, progress=print, ekf2_only=False, ekf3_only=False, verbose
if not hasattr(m,'C'): if not hasattr(m,'C'):
continue continue
mtype = m.get_type() mtype = m.get_type()
if not mtype in counts: if mtype not in counts:
counts[mtype] = 0 counts[mtype] = 0
base_counts[mtype] = 0 base_counts[mtype] = 0
core = m.C core = m.C

View File

@ -614,7 +614,7 @@ Please use a replacement build as follows:
''' % ctx.env.BOARD) ''' % ctx.env.BOARD)
boards = _board_classes.keys() boards = _board_classes.keys()
if not ctx.env.BOARD in boards: if ctx.env.BOARD not in boards:
ctx.fatal("Invalid board '%s': choices are %s" % (ctx.env.BOARD, ', '.join(sorted(boards, key=str.lower)))) ctx.fatal("Invalid board '%s': choices are %s" % (ctx.env.BOARD, ', '.join(sorted(boards, key=str.lower))))
_board = _board_classes[ctx.env.BOARD]() _board = _board_classes[ctx.env.BOARD]()
return _board return _board

View File

@ -31,7 +31,7 @@ def _load_dynamic_env_data(bld):
# relative paths from the make build are relative to BUILDROOT # relative paths from the make build are relative to BUILDROOT
d = os.path.join(bld.env.BUILDROOT, d) d = os.path.join(bld.env.BUILDROOT, d)
d = os.path.normpath(d) d = os.path.normpath(d)
if not d in idirs2: if d not in idirs2:
idirs2.append(d) idirs2.append(d)
_dynamic_env_data['include_dirs'] = idirs2 _dynamic_env_data['include_dirs'] = idirs2
@ -98,7 +98,7 @@ class upload_fw(Task.Task):
except subprocess.CalledProcessError: except subprocess.CalledProcessError:
#if where.exe can't find the file it returns a non-zero result which throws this exception #if where.exe can't find the file it returns a non-zero result which throws this exception
where_python = "" where_python = ""
if not where_python or not "\Python\Python" in where_python or "python.exe" not in where_python: if not where_python or "\Python\Python" not in where_python or "python.exe" not in where_python:
print(self.get_full_wsl2_error_msg("Windows python.exe not found")) print(self.get_full_wsl2_error_msg("Windows python.exe not found"))
return False return False
return True return True

View File

@ -44,7 +44,7 @@ class mavgen(Task.Task):
node.parent.path_from(entry_point.parent), node.parent.path_from(entry_point.parent),
path path
) )
if not path in names: if path not in names:
names.append(path) names.append(path)
return nodes, names return nodes, names

View File

@ -119,7 +119,7 @@ def _set_pkgconfig_crosscompilation_wrapper(cfg):
@conf @conf
def new_validate_cfg(kw): def new_validate_cfg(kw):
if not 'path' in kw: if 'path' not in kw:
if not cfg.env.PKGCONFIG: if not cfg.env.PKGCONFIG:
cfg.find_program('%s-pkg-config' % cfg.env.TOOLCHAIN, var='PKGCONFIG') cfg.find_program('%s-pkg-config' % cfg.env.TOOLCHAIN, var='PKGCONFIG')
kw['path'] = cfg.env.PKGCONFIG kw['path'] = cfg.env.PKGCONFIG

View File

@ -1130,7 +1130,7 @@ class AutoTestPlane(AutoTest):
self.context_collect("HEARTBEAT") self.context_collect("HEARTBEAT")
self.set_parameter("SIM_RC_FAIL", 2) # throttle-to-950 self.set_parameter("SIM_RC_FAIL", 2) # throttle-to-950
self.wait_mode('RTL') # long failsafe self.wait_mode('RTL') # long failsafe
if (not self.get_mode_from_mode_mapping("CIRCLE") in if (self.get_mode_from_mode_mapping("CIRCLE") not in
[x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]): [x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]):
raise NotAchievedException("Did not go via circle mode") raise NotAchievedException("Did not go via circle mode")
self.progress("Ensure we've had our throttle squashed to 950") self.progress("Ensure we've had our throttle squashed to 950")
@ -1168,7 +1168,7 @@ class AutoTestPlane(AutoTest):
self.context_collect("HEARTBEAT") self.context_collect("HEARTBEAT")
self.set_parameter("SIM_RC_FAIL", 1) # no-pulses self.set_parameter("SIM_RC_FAIL", 1) # no-pulses
self.wait_mode('RTL') # long failsafe self.wait_mode('RTL') # long failsafe
if (not self.get_mode_from_mode_mapping("CIRCLE") in if (self.get_mode_from_mode_mapping("CIRCLE") not in
[x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]): [x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]):
raise NotAchievedException("Did not go via circle mode") raise NotAchievedException("Did not go via circle mode")
self.do_timesync_roundtrip() self.do_timesync_roundtrip()

View File

@ -26,7 +26,7 @@ last_fix2 = {}
def handle_fix2(msg): def handle_fix2(msg):
nodeid = msg.transfer.source_node_id nodeid = msg.transfer.source_node_id
tstamp = msg.transfer.ts_real tstamp = msg.transfer.ts_real
if not nodeid in last_fix2: if nodeid not in last_fix2:
last_fix2[nodeid] = tstamp last_fix2[nodeid] = tstamp
return return
dt = tstamp - last_fix2[nodeid] dt = tstamp - last_fix2[nodeid]

View File

@ -43,7 +43,7 @@ def get_board_list():
dirname, dirlist, filenames = next(os.walk('libraries/AP_HAL_ChibiOS/hwdef')) dirname, dirlist, filenames = next(os.walk('libraries/AP_HAL_ChibiOS/hwdef'))
for d in dirlist: for d in dirlist:
hwdef = os.path.join(dirname, d, 'hwdef.dat') hwdef = os.path.join(dirname, d, 'hwdef.dat')
if os.path.exists(hwdef) and not d in omit: if os.path.exists(hwdef) and d not in omit:
board_list.append(d) board_list.append(d)
return board_list return board_list

View File

@ -54,7 +54,7 @@ while True:
flags = (ptype>>4) & 0x0F flags = (ptype>>4) & 0x0F
ptype &= 0x0F ptype &= 0x0F
if not ptype in data_types: if ptype not in data_types:
raise Exception("bad type 0x%x" % ptype) raise Exception("bad type 0x%x" % ptype)
(type_len, type_format) = data_types[ptype] (type_len, type_format) = data_types[ptype]

View File

@ -65,14 +65,14 @@ class Coefficients:
def set_acoeff(self, imu, axis, order, value): def set_acoeff(self, imu, axis, order, value):
if imu not in self.acoef: if imu not in self.acoef:
self.acoef[imu] = {} self.acoef[imu] = {}
if not axis in self.acoef[imu]: if axis not in self.acoef[imu]:
self.acoef[imu][axis] = [0]*4 self.acoef[imu][axis] = [0]*4
self.acoef[imu][axis][POLY_ORDER-order] = value self.acoef[imu][axis][POLY_ORDER-order] = value
def set_gcoeff(self, imu, axis, order, value): def set_gcoeff(self, imu, axis, order, value):
if imu not in self.gcoef: if imu not in self.gcoef:
self.gcoef[imu] = {} self.gcoef[imu] = {}
if not axis in self.gcoef[imu]: if axis not in self.gcoef[imu]:
self.gcoef[imu][axis] = [0]*4 self.gcoef[imu][axis] = [0]*4
self.gcoef[imu][axis][POLY_ORDER-order] = value self.gcoef[imu][axis][POLY_ORDER-order] = value
@ -107,7 +107,7 @@ class Coefficients:
return 0.0 return 0.0
if cal_temp < -80: if cal_temp < -80:
return 0.0 return 0.0
if not axis in coeff: if axis not in coeff:
return 0.0 return 0.0
temperature = constrain(temperature, self.tmin[imu], self.tmax[imu]) temperature = constrain(temperature, self.tmin[imu], self.tmax[imu])
cal_temp = constrain(cal_temp, self.tmin[imu], self.tmax[imu]) cal_temp = constrain(cal_temp, self.tmin[imu], self.tmax[imu])