Ruff: enable most of bugbear (#29320)

* added mutable default args

* most of the Bs

* add comment about lrucache
old-commit-hash: 62c1e65924
beeps
Justin Newberry 2 years ago committed by GitHub
parent a9611d13be
commit d487c0501f
  1. 2
      docs/conf.py
  2. 4
      pyproject.toml
  3. 2
      scripts/code_stats.py
  4. 21
      selfdrive/athena/athenad.py
  5. 2
      selfdrive/car/ecu_addrs.py
  6. 2
      selfdrive/car/tests/test_fingerprints.py
  7. 8
      selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py
  8. 4
      selfdrive/controls/lib/lateral_planner.py
  9. 4
      selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
  10. 2
      selfdrive/debug/internal/fuzz_fw_fingerprint.py
  11. 2
      selfdrive/manager/process.py
  12. 2
      selfdrive/modeld/tests/timing/benchmark.py
  13. 4
      selfdrive/monitoring/driver_monitor.py
  14. 8
      selfdrive/test/test_onroad.py
  15. 2
      selfdrive/thermald/thermald.py
  16. 4
      system/camerad/test/test_exposure.py
  17. 20
      system/hardware/tici/hardware.py
  18. 2
      system/sensord/rawgps/rawgpsd.py
  19. 5
      system/sensord/rawgps/structs.py
  20. 10
      system/ubloxd/tests/ublox.py
  21. 2
      tools/gpstest/rpc_server.py
  22. 2
      tools/gpstest/test_gps.py
  23. 10
      tools/lib/framereader.py
  24. 2
      tools/lib/logreader.py

@ -100,7 +100,7 @@ breathe_projects_source = {}
# only document files that have accompanying .cc files next to them
print("searching for c_docs...")
for root, dirs, files in os.walk(BASEDIR):
for root, _, files in os.walk(BASEDIR):
found = False
breath_src = {}
breathe_srcs_list = []

@ -197,8 +197,8 @@ build-backend = "poetry.core.masonry.api"
# https://beta.ruff.rs/docs/configuration/#using-pyprojecttoml
[tool.ruff]
select = ["E", "F", "W", "PIE", "C4", "ISC", "RUF100", "A"]
ignore = ["W292", "E741", "E402", "C408", "ISC003"]
select = ["E", "F", "W", "PIE", "C4", "ISC", "RUF100", "A", "B"]
ignore = ["W292", "E741", "E402", "C408", "ISC003", "B027", "B024", "B905"]
line-length = 160
target-version="py311"
exclude = [

@ -8,7 +8,7 @@ fouts = {x.decode('utf-8') for x in subprocess.check_output(['git', 'ls-files'])
pyf = []
for d in ["cereal", "common", "scripts", "selfdrive", "tools"]:
for root, dirs, files in os.walk(d):
for root, _, files in os.walk(d):
for f in files:
if f.endswith(".py"):
pyf.append(os.path.join(root, f))

@ -213,6 +213,16 @@ def retry_upload(tid: int, end_event: threading.Event, increase_count: bool = Tr
break
def cb(sm, item, tid, sz: int, cur: int) -> None:
# Abort transfer if connection changed to metered after starting upload
sm.update(0)
metered = sm['deviceState'].networkMetered
if metered and (not item.allow_cellular):
raise AbortTransferException
cur_upload_items[tid] = replace(item, progress=cur / sz if sz else 1)
def upload_handler(end_event: threading.Event) -> None:
sm = messaging.SubMaster(['deviceState'])
tid = threading.get_ident()
@ -242,15 +252,6 @@ def upload_handler(end_event: threading.Event) -> None:
continue
try:
def cb(sz: int, cur: int) -> None:
# Abort transfer if connection changed to metered after starting upload
sm.update(0)
metered = sm['deviceState'].networkMetered
if metered and (not item.allow_cellular):
raise AbortTransferException
cur_upload_items[tid] = replace(item, progress=cur / sz if sz else 1)
fn = item.path
try:
sz = os.path.getsize(fn)
@ -258,7 +259,7 @@ def upload_handler(end_event: threading.Event) -> None:
sz = -1
cloudlog.event("athena.upload_handler.upload_start", fn=fn, sz=sz, network_type=network_type, metered=metered, retry_count=item.retry_count)
response = _do_upload(item, cb)
response = _do_upload(item, partial(cb, sm, item, tid))
if response.status_code not in (200, 201, 401, 403, 412):
cloudlog.event("athena.upload_handler.retry", status_code=response.status_code, fn=fn, sz=sz, network_type=network_type, metered=metered)

@ -90,7 +90,7 @@ if __name__ == "__main__":
print()
print("Found ECUs on addresses:")
for addr, subaddr, bus in ecu_addrs:
for addr, subaddr, _ in ecu_addrs:
msg = f" 0x{hex(addr)}"
if subaddr is not None:
msg += f" (sub-address: {hex(subaddr)})"

@ -70,7 +70,7 @@ if __name__ == "__main__":
for brand in fingerprints:
for car in fingerprints[brand]:
fingerprints_flat += fingerprints[brand][car]
for i in range(len(fingerprints[brand][car])):
for _ in range(len(fingerprints[brand][car])):
car_names.append(car)
brand_names.append(brand)

@ -129,11 +129,15 @@ def gen_lat_ocp():
class LateralMpc():
def __init__(self, x0=np.zeros(X_DIM)):
def __init__(self, x0=None):
if x0 is None:
x0 = np.zeros(X_DIM)
self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N)
self.reset(x0)
def reset(self, x0=np.zeros(X_DIM)):
def reset(self, x0=None):
if x0 is None:
x0 = np.zeros(X_DIM)
self.x_sol = np.zeros((N+1, X_DIM))
self.u_sol = np.zeros((N, 1))
self.yref = np.zeros((N+1, COST_DIM))

@ -50,7 +50,9 @@ class LateralPlanner:
self.lat_mpc = LateralMpc()
self.reset_mpc(np.zeros(4))
def reset_mpc(self, x0=np.zeros(4)):
def reset_mpc(self, x0=None):
if x0 is None:
x0 = np.zeros(4)
self.x0 = x0
self.lat_mpc.reset(x0=self.x0)

@ -83,7 +83,9 @@ def get_stopped_equivalence_factor(v_lead):
def get_safe_obstacle_distance(v_ego, t_follow):
return (v_ego**2) / (2 * COMFORT_BRAKE) + t_follow * v_ego + STOP_DISTANCE
def desired_follow_distance(v_ego, v_lead, t_follow=get_T_FOLLOW()):
def desired_follow_distance(v_ego, v_lead, t_follow=None):
if t_follow is None:
t_follow = get_T_FOLLOW()
return get_safe_obstacle_distance(v_ego, t_follow) - get_stopped_equivalence_factor(v_lead)

@ -27,7 +27,7 @@ if __name__ == "__main__":
for _ in tqdm(range(1000)):
for candidate, fws in FWS.items():
fw_dict = {}
for (tp, addr, subaddr), fw_list in fws.items():
for (_, addr, subaddr), fw_list in fws.items():
fw_dict[(addr, subaddr)] = [random.choice(fw_list)]
matches = match_fw_to_car_fuzzy(fw_dict, log=False, exclude=candidate)

@ -39,7 +39,7 @@ def launcher(proc: str, name: str) -> None:
sentry.set_tag("daemon", name)
# exec the process
getattr(mod, 'main')()
mod.main()
except KeyboardInterrupt:
cloudlog.warning(f"child {proc} got SIGINT")
except Exception:

@ -35,6 +35,6 @@ if __name__ == "__main__":
print("\n\n")
print(f"ran modeld {N} times for {TIME}s each")
for n, t in enumerate(execution_times):
for _, t in enumerate(execution_times):
print(f"\tavg: {sum(t)/len(t):0.2f}ms, min: {min(t):0.2f}ms, max: {max(t):0.2f}ms")
print("\n\n")

@ -119,7 +119,9 @@ class DriverBlink():
self.right_blink = 0.
class DriverStatus():
def __init__(self, rhd_saved=False, settings=DRIVER_MONITOR_SETTINGS()):
def __init__(self, rhd_saved=False, settings=None):
if settings is None:
settings = DRIVER_MONITOR_SETTINGS()
# init policy settings
self.settings = settings

@ -282,7 +282,7 @@ class TestOnroad(unittest.TestCase):
result += "-------------- Debayer Timing ------------------\n"
result += "------------------------------------------------\n"
ts = [getattr(getattr(m, m.which()), "processingTime") for m in self.lr if 'CameraState' in m.which()]
ts = [getattr(m, m.which()).processingTime for m in self.lr if 'CameraState' in m.which()]
self.assertLess(min(ts), 0.025, f"high execution time: {min(ts)}")
result += f"execution time: min {min(ts):.5f}s\n"
result += f"execution time: max {max(ts):.5f}s\n"
@ -297,7 +297,7 @@ class TestOnroad(unittest.TestCase):
result += "----------------- SoF Timing ------------------\n"
result += "------------------------------------------------\n"
for name in ['roadCameraState', 'wideRoadCameraState', 'driverCameraState']:
ts = [getattr(getattr(m, m.which()), "timestampSof") for m in self.lr if name in m.which()]
ts = [getattr(m, m.which()).timestampSof for m in self.lr if name in m.which()]
d_ms = np.diff(ts) / 1e6
d50 = np.abs(d_ms-50)
self.assertLess(max(d50), 1.0, f"high sof delta vs 50ms: {max(d50)}")
@ -315,7 +315,7 @@ class TestOnroad(unittest.TestCase):
cfgs = [("lateralPlan", 0.05, 0.05), ("longitudinalPlan", 0.05, 0.05)]
for (s, instant_max, avg_max) in cfgs:
ts = [getattr(getattr(m, s), "solverExecutionTime") for m in self.service_msgs[s]]
ts = [getattr(m, s).solverExecutionTime for m in self.service_msgs[s]]
self.assertLess(max(ts), instant_max, f"high '{s}' execution time: {max(ts)}")
self.assertLess(np.mean(ts), avg_max, f"high avg '{s}' execution time: {np.mean(ts)}")
result += f"'{s}' execution time: min {min(ts):.5f}s\n"
@ -335,7 +335,7 @@ class TestOnroad(unittest.TestCase):
("driverStateV2", 0.050, 0.026),
]
for (s, instant_max, avg_max) in cfgs:
ts = [getattr(getattr(m, s), "modelExecutionTime") for m in self.service_msgs[s]]
ts = [getattr(m, s).modelExecutionTime for m in self.service_msgs[s]]
self.assertLess(max(ts), instant_max, f"high '{s}' execution time: {max(ts)}")
self.assertLess(np.mean(ts), avg_max, f"high avg '{s}' execution time: {np.mean(ts)}")
result += f"'{s}' execution time: min {min(ts):.5f}s\n"

@ -61,7 +61,7 @@ def populate_tz_by_type():
if not n.startswith("thermal_zone"):
continue
with open(os.path.join("/sys/devices/virtual/thermal", n, "type")) as f:
tz_by_type[f.read().strip()] = int(n.lstrip("thermal_zone"))
tz_by_type[f.read().strip()] = int(n.removeprefix("thermal_zone"))
def read_tz(x):
if x is None:

@ -18,7 +18,9 @@ class TestCamerad(unittest.TestCase):
ret = np.clip(im[:,:,2] * 0.114 + im[:,:,1] * 0.587 + im[:,:,0] * 0.299, 0, 255).astype(np.uint8)
return ret
def _is_exposure_okay(self, i, med_mean=np.array([[0.2,0.4],[0.2,0.6]])):
def _is_exposure_okay(self, i, med_mean=None):
if med_mean is None:
med_mean = np.array([[0.2,0.4],[0.2,0.6]])
h, w = i.shape[:2]
i = i[h//10:9*h//10,w//10:9*w//10]
med_ex, mean_ex = med_mean

@ -83,6 +83,17 @@ def affine_irq(val, action):
for i in irqs:
sudo_write(str(val), f"/proc/irq/{i}/smp_affinity_list")
@lru_cache
def get_device_type():
# lru_cache and cache can cause memory leaks when used in classes
with open("/sys/firmware/devicetree/base/model") as f:
model = f.read().strip('\x00')
model = model.split('comma ')[-1]
# TODO: remove this with AGNOS 7+
if model.startswith('Qualcomm'):
model = 'tici'
return model
class Tici(HardwareBase):
@cached_property
def bus(self):
@ -105,15 +116,8 @@ class Tici(HardwareBase):
with open("/VERSION") as f:
return f.read().strip()
@lru_cache
def get_device_type(self):
with open("/sys/firmware/devicetree/base/model") as f:
model = f.read().strip('\x00')
model = model.split('comma ')[-1]
# TODO: remove this with AGNOS 7+
if model.startswith('Qualcomm'):
model = 'tici'
return model
return get_device_type()
def get_sound_card_online(self):
if os.path.isfile('/proc/asound/card0/state'):

@ -446,7 +446,7 @@ def main() -> NoReturn:
report.source = 1 # glonass
measurement_status_fields = (measurementStatusFields.items(), measurementStatusGlonassFields.items())
else:
assert False
raise RuntimeError(f"invalid log_type: {log_type}")
for k,v in dat.items():
if k == "version":

@ -317,8 +317,7 @@ def parse_struct(ss):
elif typ in ["uint64", "uint64_t"]:
st += "Q"
else:
print("unknown type", typ)
assert False
raise RuntimeError(f"unknown type {typ}")
if '[' in nam:
cnt = int(nam.split("[")[1].split("]")[0])
st += st[-1]*(cnt-1)
@ -333,7 +332,7 @@ def dict_unpacker(ss, camelcase = False):
if camelcase:
nams = [name_to_camelcase(x) for x in nams]
sz = calcsize(st)
return lambda x: dict(zip(nams, unpack_from(st, x))), sz
return lambda x: dict(zip(nams, unpack_from(st, x), strict=True)), sz
def relist(dat):
list_keys = set()

@ -185,8 +185,8 @@ class UBloxAttrDict(dict):
def __getattr__(self, name):
try:
return self.__getitem__(name)
except KeyError:
raise AttributeError(name)
except KeyError as e:
raise RuntimeError(f"ublock invalid attr: {name}") from e
def __setattr__(self, name, value):
if name in self.__dict__:
@ -270,7 +270,7 @@ class UBloxDescriptor:
return
size2 = struct.calcsize(self.format2)
for c in range(count):
for _ in range(count):
r = UBloxAttrDict()
if size2 > len(buf):
raise UBloxError("INVALID_SIZE=%u, " % len(buf))
@ -573,10 +573,10 @@ class UBloxMessage:
'''allow access to message fields'''
try:
return self._fields[name]
except KeyError:
except KeyError as e:
if name == 'recs':
return self._recs
raise AttributeError(name)
raise AttributeError(name) from e
def __setattr__(self, name, value):
'''allow access to message fields'''

@ -128,7 +128,7 @@ class RemoteCheckerService(rpyc.Service):
if pos_geo is None or len(pos_geo) == 0:
continue
match = all(abs(g-s) < DELTA for g,s in zip(pos_geo[:2], [slat, slon]))
match = all(abs(g-s) < DELTA for g,s in zip(pos_geo[:2], [slat, slon], strict=True))
match &= abs(pos_geo[2] - salt) < ALT_DELTA
if match:
match_cnt += 1

@ -30,7 +30,7 @@ def create_backup(pigeon):
pigeon.send(b"\xB5\x62\x09\x14\x04\x00\x00\x00\x00\x00\x21\xEC")
try:
if not pigeon.wait_for_ack(ack=pd.UBLOX_SOS_ACK, nack=pd.UBLOX_SOS_NACK):
assert False, "Could not store almanac"
raise RuntimeError("Could not store almanac")
except TimeoutError:
pass

@ -70,8 +70,8 @@ def ffprobe(fn, fmt=None):
try:
ffprobe_output = subprocess.check_output(cmd)
except subprocess.CalledProcessError:
raise DataUnreadableError(fn)
except subprocess.CalledProcessError as e:
raise DataUnreadableError(fn) from e
return json.loads(ffprobe_output)
@ -86,8 +86,8 @@ def vidindex(fn, typ):
tempfile.NamedTemporaryFile() as index_f:
try:
subprocess.check_call([vidindex, typ, fn, prefix_f.name, index_f.name])
except subprocess.CalledProcessError:
raise DataUnreadableError(f"vidindex failed on file {fn}")
except subprocess.CalledProcessError as e:
raise DataUnreadableError(f"vidindex failed on file {fn}") from e
with open(index_f.name, "rb") as f:
index = f.read()
with open(prefix_f.name, "rb") as f:
@ -418,7 +418,7 @@ class VideoStreamDecompressor:
elif self.pix_fmt == "yuv444p":
ret = np.frombuffer(dat, dtype=np.uint8).reshape((3, self.h, self.w))
else:
assert False
raise RuntimeError(f"unknown pix_fmt: {self.pix_fmt}")
yield ret
result_code = self.proc.wait()

@ -98,7 +98,7 @@ class LogReader:
for e in ents:
_ents.append(e)
except capnp.KjException:
warnings.warn("Corrupted events detected", RuntimeWarning)
warnings.warn("Corrupted events detected", RuntimeWarning, stacklevel=1)
self._ents = list(sorted(_ents, key=lambda x: x.logMonoTime) if sort_by_time else _ents)
self._ts = [x.logMonoTime for x in self._ents]

Loading…
Cancel
Save