Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 6 additions & 6 deletions common/git.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,27 +4,27 @@


@cache
def get_commit(cwd: str = None, branch: str = "HEAD") -> str:
def get_commit(cwd: str | None = None, branch: str = "HEAD") -> str:
return run_cmd_default(["git", "rev-parse", branch], cwd=cwd)


@cache
def get_commit_date(cwd: str = None, commit: str = "HEAD") -> str:
def get_commit_date(cwd: str | None = None, commit: str = "HEAD") -> str:
return run_cmd_default(["git", "show", "--no-patch", "--format='%ct %ci'", commit], cwd=cwd)


@cache
def get_short_branch(cwd: str = None) -> str:
def get_short_branch(cwd: str | None = None) -> str:
return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "HEAD"], cwd=cwd)


@cache
def get_branch(cwd: str = None) -> str:
def get_branch(cwd: str | None = None) -> str:
return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "--symbolic-full-name", "@{u}"], cwd=cwd)


@cache
def get_origin(cwd: str = None) -> str:
def get_origin(cwd: str | None = None) -> str:
try:
local_branch = run_cmd(["git", "name-rev", "--name-only", "HEAD"], cwd=cwd)
tracking_remote = run_cmd(["git", "config", "branch." + local_branch + ".remote"], cwd=cwd)
Expand All @@ -34,7 +34,7 @@ def get_origin(cwd: str = None) -> str:


@cache
def get_normalized_origin(cwd: str = None) -> str:
def get_normalized_origin(cwd: str | None = None) -> str:
return get_origin(cwd) \
.replace("git@", "", 1) \
.replace(".git", "", 1) \
Expand Down
19 changes: 9 additions & 10 deletions common/pid.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,15 @@
from numbers import Number

class PIDController:
def __init__(self, k_p, k_i, k_d=0., pos_limit=1e308, neg_limit=-1e308, rate=100):
self._k_p = k_p
self._k_i = k_i
self._k_d = k_d
if isinstance(self._k_p, Number):
self._k_p = [[0], [self._k_p]]
if isinstance(self._k_i, Number):
self._k_i = [[0], [self._k_i]]
if isinstance(self._k_d, Number):
self._k_d = [[0], [self._k_d]]
_k_p: list[list[float]]
_k_i: list[list[float]]
_k_d: list[list[float]]

def __init__(self, k_p: float | list[list[float]], k_i: float | list[list[float]],
k_d: float | list[list[float]] = 0., pos_limit=1e308, neg_limit=-1e308, rate=100):
self._k_p: list[list[float]] = [[0.0], [float(k_p)]] if isinstance(k_p, Number) else k_p
self._k_i: list[list[float]] = [[0.0], [float(k_i)]] if isinstance(k_i, Number) else k_i
self._k_d: list[list[float]] = [[0.0], [float(k_d)]] if isinstance(k_d, Number) else k_d

self.set_limits(pos_limit, neg_limit)

Expand Down
2 changes: 1 addition & 1 deletion common/prefix.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
from openpilot.system.hardware.hw import DEFAULT_DOWNLOAD_CACHE_ROOT

class OpenpilotPrefix:
def __init__(self, prefix: str = None, create_dirs_on_enter: bool = True, clean_dirs_on_exit: bool = True, shared_download_cache: bool = False):
def __init__(self, prefix: str | None = None, create_dirs_on_enter: bool = True, clean_dirs_on_exit: bool = True, shared_download_cache: bool = False):
self.prefix = prefix if prefix else str(uuid.uuid4().hex[0:15])
self.msgq_path = os.path.join(Paths.shm_path(), self.prefix)
self.create_dirs_on_enter = create_dirs_on_enter
Expand Down
3 changes: 2 additions & 1 deletion common/swaglog.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@ def get_file_handler():
return handler

class SwaglogRotatingFileHandler(BaseRotatingHandler):
last_rollover: float

def __init__(self, base_filename, interval=60, max_bytes=1024*256, backup_count=2500, encoding=None):
super().__init__(base_filename, mode="a", encoding=encoding, delay=True)
self.base_filename = base_filename
Expand All @@ -27,7 +29,6 @@ def __init__(self, base_filename, interval=60, max_bytes=1024*256, backup_count=
self.log_files = self.get_existing_logfiles()
log_indexes = [f.split(".")[-1] for f in self.log_files]
self.last_file_idx = max([int(i) for i in log_indexes if i.isdigit()] or [-1])
self.last_rollover = None
self.doRollover()

def _open(self):
Expand Down
33 changes: 15 additions & 18 deletions pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ docs = [
testing = [
"coverage",
"hypothesis ==6.47.*",
"mypy",
"ty",
"pytest",
"pytest-cpp",
"pytest-subtests",
Expand Down Expand Up @@ -180,8 +180,10 @@ ignore-words-list = "bu,ro,te,ue,alo,hda,ois,nam,nams,ned,som,parm,setts,inout,w
builtin = "clear,rare,informal,code,names,en-GB_to_en-US"
skip = "./third_party/*, ./tinygrad/*, ./tinygrad_repo/*, ./msgq/*, ./panda/*, ./opendbc/*, ./opendbc_repo/*, ./rednose/*, ./rednose_repo/*, ./teleoprtc/*, ./teleoprtc_repo/*, *.po, uv.lock, *.onnx, ./cereal/gen/*, */c_generated_code/*, docs/assets/*, tools/plotjuggler/layouts/*, selfdrive/assets/offroad/mici_fcc.html"

[tool.mypy]
python_version = "3.11"
[tool.ty.environment]
python-version = "3.11"

[tool.ty.src]
exclude = [
"cereal/",
"msgq/",
Expand All @@ -198,23 +200,18 @@ exclude = [
"third_party/",
]

# third-party packages
ignore_missing_imports=true

# helpful warnings
warn_redundant_casts=true
warn_unreachable=true
warn_unused_ignores=true

# restrict dynamic typing
warn_return_any=true
[tool.ty.rules]
# third-party packages (maps to mypy's ignore_missing_imports)
unresolved-import = "ignore"

# allow implicit optionals for default args
implicit_optional = true
# helpful warnings (maps to mypy's warn_* options)
redundant-cast = "warn"
unused-ignore-comment = "warn"

local_partial_types=true
explicit_package_bases=true
disable_error_code = "annotation-unchecked"
# TODO: fix and remove these
possibly-missing-attribute = "ignore" # 260 warnings
invalid-argument-type = "ignore" # 111 errors
unresolved-attribute = "ignore" # 96 errors

# https://beta.ruff.rs/docs/configuration/#using-pyprojecttoml
[tool.ruff]
Expand Down
12 changes: 6 additions & 6 deletions scripts/lint/lint.sh
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ function run_tests() {
run "check_nomerge_comments" $DIR/check_nomerge_comments.sh $ALL_FILES

if [[ -z "$FAST" ]]; then
run "mypy" mypy $PYTHON_FILES
run "ty" ty check
run "codespell" codespell $ALL_FILES
fi

Expand All @@ -69,7 +69,7 @@ function help() {
echo ""
echo -e "${BOLD}${UNDERLINE}Tests:${NC}"
echo -e " ${BOLD}ruff${NC}"
echo -e " ${BOLD}mypy${NC}"
echo -e " ${BOLD}ty${NC}"
echo -e " ${BOLD}codespell${NC}"
echo -e " ${BOLD}check_added_large_files${NC}"
echo -e " ${BOLD}check_shebang_scripts_are_executable${NC}"
Expand All @@ -81,11 +81,11 @@ function help() {
echo " Specify tests to skip separated by spaces"
echo ""
echo -e "${BOLD}${UNDERLINE}Examples:${NC}"
echo " op lint mypy ruff"
echo " Only run the mypy and ruff tests"
echo " op lint ty ruff"
echo " Only run the ty and ruff tests"
echo ""
echo " op lint --skip mypy ruff"
echo " Skip the mypy and ruff tests"
echo " op lint --skip ty ruff"
echo " Skip the ty and ruff tests"
echo ""
echo " op lint"
echo " Run all the tests"
Expand Down
2 changes: 1 addition & 1 deletion selfdrive/car/car_specific.py
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ def update(self, CS: car.CarState, CS_prev: car.CarState, CC: car.CarControl):
events.add(EventName.speedTooLow)

# TODO: this needs to be implemented generically in carState struct
# if CC.eps_timer_soft_disable_alert: # type: ignore[attr-defined]
# if CC.eps_timer_soft_disable_alert:
# events.add(EventName.steerTimeLimit)

elif self.CP.brand == 'hyundai':
Expand Down
1 change: 1 addition & 0 deletions selfdrive/car/card.py
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,7 @@ def __init__(self, CI=None, RI=None) -> None:
# continue onto next fingerprinting step in pandad
self.params.put_bool("FirmwareQueryDone", True)
else:
assert RI is not None
self.CI, self.CP = CI, CI.CP
self.RI = RI

Expand Down
2 changes: 1 addition & 1 deletion selfdrive/car/tests/test_models.py
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ def test_panda_safety_rx_checks(self):

# Don't check relay malfunction on disabled routes (relay closed),
# or before fingerprinting is done (elm327 and noOutput)
if self.openpilot_enabled and t / 1e4 > self.car_safety_mode_frame:
if self.openpilot_enabled and self.car_safety_mode_frame is not None and t / 1e4 > self.car_safety_mode_frame:
self.assertFalse(self.safety.get_relay_malfunction())
else:
self.safety.set_relay_malfunction(False)
Expand Down
6 changes: 3 additions & 3 deletions selfdrive/debug/car/hyundai_enable_radar_points.py
Original file line number Diff line number Diff line change
Expand Up @@ -101,19 +101,19 @@ class ConfigValues(NamedTuple):
uds_client = UdsClient(panda, 0x7D0, bus=args.bus)

print("\n[START DIAGNOSTIC SESSION]")
session_type : SESSION_TYPE = 0x07 # type: ignore
session_type = SESSION_TYPE(0x07)
uds_client.diagnostic_session_control(session_type)

print("[HARDWARE/SOFTWARE VERSION]")
fw_version_data_id : DATA_IDENTIFIER_TYPE = 0xf100 # type: ignore
fw_version_data_id = DATA_IDENTIFIER_TYPE(0xf100)
fw_version = uds_client.read_data_by_identifier(fw_version_data_id)
print(fw_version)
if fw_version not in SUPPORTED_FW_VERSIONS.keys():
print("radar not supported! (aborted)")
sys.exit(1)

print("[GET CONFIGURATION]")
config_data_id : DATA_IDENTIFIER_TYPE = 0x0142 # type: ignore
config_data_id = DATA_IDENTIFIER_TYPE(0x0142)
current_config = uds_client.read_data_by_identifier(config_data_id)
config_values = SUPPORTED_FW_VERSIONS[fw_version]
new_config = config_values.default_config if args.default else config_values.tracks_enabled
Expand Down
11 changes: 6 additions & 5 deletions selfdrive/debug/car/vw_mqb_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class ACCESS_TYPE_LEVEL_1(IntEnum):
sw_ver = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER).decode("utf-8")
component = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.SYSTEM_NAME_OR_ENGINE_TYPE).decode("utf-8")
odx_file = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.ODX_FILE).decode("utf-8").rstrip('\x00')
current_coding = uds_client.read_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING) # type: ignore
current_coding = uds_client.read_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING)
coding_text = current_coding.hex()

print("\nEPS diagnostic data\n")
Expand All @@ -72,6 +72,7 @@ class ACCESS_TYPE_LEVEL_1(IntEnum):
print("Timeout fetching data from EPS")
quit()

assert current_coding is not None
coding_variant, current_coding_array, coding_byte, coding_bit = None, None, 0, 0
coding_length = len(current_coding)

Expand Down Expand Up @@ -126,9 +127,9 @@ class ACCESS_TYPE_LEVEL_1(IntEnum):
new_coding = current_coding[0:coding_byte] + new_byte.to_bytes(1, "little") + current_coding[coding_byte+1:]

try:
seed = uds_client.security_access(ACCESS_TYPE_LEVEL_1.REQUEST_SEED) # type: ignore
seed = uds_client.security_access(ACCESS_TYPE_LEVEL_1.REQUEST_SEED)
key = struct.unpack("!I", seed)[0] + 28183 # yeah, it's like that
uds_client.security_access(ACCESS_TYPE_LEVEL_1.SEND_KEY, struct.pack("!I", key)) # type: ignore
uds_client.security_access(ACCESS_TYPE_LEVEL_1.SEND_KEY, struct.pack("!I", key))
except (NegativeResponseError, MessageTimeoutError):
print("Security access failed!")
print("Open the hood and retry (disables the \"diagnostic firewall\" on newer vehicles)")
Expand All @@ -148,15 +149,15 @@ class ACCESS_TYPE_LEVEL_1(IntEnum):
uds_client.write_data_by_identifier(DATA_IDENTIFIER_TYPE.PROGRAMMING_DATE, prog_date)
tester_num = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.CALIBRATION_REPAIR_SHOP_CODE_OR_CALIBRATION_EQUIPMENT_SERIAL_NUMBER)
uds_client.write_data_by_identifier(DATA_IDENTIFIER_TYPE.REPAIR_SHOP_CODE_OR_TESTER_SERIAL_NUMBER, tester_num)
uds_client.write_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING, new_coding) # type: ignore
uds_client.write_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING, new_coding)
except (NegativeResponseError, MessageTimeoutError):
print("Writing new configuration failed!")
print("Make sure the comma processes are stopped: tmux kill-session -t comma")
quit()

try:
# Read back result just to make 100% sure everything worked
current_coding_text = uds_client.read_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING).hex() # type: ignore
current_coding_text = uds_client.read_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING).hex()
print(f" New coding: {current_coding_text}")
except (NegativeResponseError, MessageTimeoutError):
print("Reading back updated coding failed!")
Expand Down
1 change: 0 additions & 1 deletion selfdrive/debug/cpu_usage_stat.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#!/usr/bin/env python3
# type: ignore
'''
System tools like top/htop can only show current cpu usage values, so I write this script to do statistics jobs.
Features:
Expand Down
6 changes: 2 additions & 4 deletions selfdrive/debug/cycle_alerts.py
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,7 @@ def cycle_alerts(duration=200, is_metric=False):
alert = AM.process_alerts(frame, [])
print(alert)
for _ in range(duration):
dat = messaging.new_message()
dat.init('selfdriveState')
dat = messaging.new_message('selfdriveState')
dat.selfdriveState.enabled = False

if alert:
Expand All @@ -112,8 +111,7 @@ def cycle_alerts(duration=200, is_metric=False):
dat.selfdriveState.alertSound = alert.audible_alert
pm.send('selfdriveState', dat)

dat = messaging.new_message()
dat.init('deviceState')
dat = messaging.new_message('deviceState')
dat.deviceState.started = True
pm.send('deviceState', dat)

Expand Down
2 changes: 1 addition & 1 deletion selfdrive/debug/fingerprint_from_route.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
def get_fingerprint(lr):
# TODO: make this a nice tool for car ports. should also work with qlogs for FW

fw = None
fw = []
vin = None
msgs = {}
for msg in lr:
Expand Down
1 change: 0 additions & 1 deletion selfdrive/debug/fuzz_fw_fingerprint.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#!/usr/bin/env python3
# type: ignore
import random
from collections import defaultdict

Expand Down
6 changes: 4 additions & 2 deletions selfdrive/debug/live_cpu_and_temp.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,11 @@ def proc_name(proc):

print(f"CPU {100.0 * np.mean(cores):.2f}% - RAM: {last_mem:.2f}% - Temp {last_temp:.2f}C")

cur_proclog_t: int = sm.logMonoTime['procLog']
if args.cpu and prev_proclog is not None and prev_proclog_t is not None:
assert prev_proclog_t is not None
procs: dict[str, float] = defaultdict(float)
dt = (sm.logMonoTime['procLog'] - prev_proclog_t) / 1e9
dt = (cur_proclog_t - prev_proclog_t) / 1e9
for proc in m.procs:
try:
name = proc_name(proc)
Expand All @@ -103,4 +105,4 @@ def proc_name(proc):
print()

prev_proclog = m
prev_proclog_t = sm.logMonoTime['procLog']
prev_proclog_t = cur_proclog_t
1 change: 0 additions & 1 deletion selfdrive/debug/measure_torque_time_to_max.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#!/usr/bin/env python3
# type: ignore

import os
import argparse
Expand Down
1 change: 0 additions & 1 deletion selfdrive/debug/test_fw_query_on_routes.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#!/usr/bin/env python3
# type: ignore

from collections import defaultdict
import argparse
Expand Down
4 changes: 2 additions & 2 deletions selfdrive/locationd/calibrationd.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@


def is_calibration_valid(rpy: np.ndarray) -> bool:
return (PITCH_LIMITS[0] < rpy[1] < PITCH_LIMITS[1]) and (YAW_LIMITS[0] < rpy[2] < YAW_LIMITS[1]) # type: ignore
return (PITCH_LIMITS[0] < rpy[1] < PITCH_LIMITS[1]) and (YAW_LIMITS[0] < rpy[2] < YAW_LIMITS[1])


def sanity_clip(rpy: np.ndarray) -> np.ndarray:
Expand Down Expand Up @@ -92,7 +92,7 @@ def reset(self, rpy_init: np.ndarray = RPY_INIT,
valid_blocks: int = 0,
wide_from_device_euler_init: np.ndarray = WIDE_FROM_DEVICE_EULER_INIT,
height_init: np.ndarray = HEIGHT_INIT,
smooth_from: np.ndarray = None) -> None:
smooth_from: np.ndarray | None = None) -> None:
if not np.isfinite(rpy_init).all():
self.rpy = RPY_INIT.copy()
else:
Expand Down
2 changes: 1 addition & 1 deletion selfdrive/locationd/helpers.py
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ def is_calculable(self) -> bool:
def add_point(self, x: float, y: float) -> None:
raise NotImplementedError

def get_points(self, num_points: int = None) -> Any:
def get_points(self, num_points: int | None = None) -> Any:
points = np.vstack([x.arr for x in self.buckets.values()])
if num_points is None:
return points
Expand Down
4 changes: 2 additions & 2 deletions selfdrive/locationd/paramsd.py
Original file line number Diff line number Diff line change
Expand Up @@ -127,8 +127,8 @@ def handle_log(self, t: float, which: str, msg: capnp._DynamicStructReader):

if not self.active:
# Reset time when stopped so uncertainty doesn't grow
self.kf.filter.set_filter_time(t) # type: ignore
self.kf.filter.reset_rewind() # type: ignore
self.kf.filter.set_filter_time(t)
self.kf.filter.reset_rewind()

def get_msg(self, valid: bool, debug: bool = False) -> capnp._DynamicStructBuilder:
x = self.kf.x
Expand Down
Loading
Loading