mirror of https://github.com/commaai/openpilot.git
Add More Types for mypy (#23268)
* mypy passes * a few more * a few in manager * more types, will lint * more * simple types * events type * Update selfdrive/thermald/thermald.py * Apply suggestions from code review Co-authored-by: Adeeb Shihadeh <adeebshihadeh@gmail.com>
This commit is contained in:
parent
5387806400
commit
dc96d4bee7
|
@ -39,7 +39,7 @@ def set_realtime_priority(level: int) -> None:
|
|||
|
||||
def set_core_affinity(core: int) -> None:
|
||||
if not PC:
|
||||
os.sched_setaffinity(0, [core,])
|
||||
os.sched_setaffinity(0, [core,]) # type: ignore[attr-defined]
|
||||
|
||||
|
||||
def config_realtime_process(core: int, priority: int) -> None:
|
||||
|
|
|
@ -24,7 +24,7 @@ class Spinner():
|
|||
except BrokenPipeError:
|
||||
pass
|
||||
|
||||
def update_progress(self, cur: int, total: int):
|
||||
def update_progress(self, cur: float, total: float):
|
||||
self.update(str(round(100 * cur / total)))
|
||||
|
||||
def close(self):
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
from enum import IntEnum
|
||||
from typing import Dict, Union, Callable
|
||||
from typing import Dict, Union, Callable, List, Optional
|
||||
|
||||
from cereal import log, car
|
||||
import cereal.messaging as messaging
|
||||
|
@ -42,33 +42,33 @@ EVENT_NAME = {v: k for k, v in EventName.schema.enumerants.items()}
|
|||
|
||||
class Events:
|
||||
def __init__(self):
|
||||
self.events = []
|
||||
self.static_events = []
|
||||
self.events: List[int] = []
|
||||
self.static_events: List[int] = []
|
||||
self.events_prev = dict.fromkeys(EVENTS.keys(), 0)
|
||||
|
||||
@property
|
||||
def names(self):
|
||||
def names(self) -> List[int]:
|
||||
return self.events
|
||||
|
||||
def __len__(self):
|
||||
def __len__(self) -> int:
|
||||
return len(self.events)
|
||||
|
||||
def add(self, event_name, static=False):
|
||||
def add(self, event_name: int, static: bool=False) -> None:
|
||||
if static:
|
||||
self.static_events.append(event_name)
|
||||
self.events.append(event_name)
|
||||
|
||||
def clear(self):
|
||||
def clear(self) -> None:
|
||||
self.events_prev = {k: (v + 1 if k in self.events else 0) for k, v in self.events_prev.items()}
|
||||
self.events = self.static_events.copy()
|
||||
|
||||
def any(self, event_type):
|
||||
def any(self, event_type: str) -> bool:
|
||||
for e in self.events:
|
||||
if event_type in EVENTS.get(e, {}).keys():
|
||||
return True
|
||||
return False
|
||||
|
||||
def create_alerts(self, event_types, callback_args=None):
|
||||
def create_alerts(self, event_types: List[str], callback_args=None):
|
||||
if callback_args is None:
|
||||
callback_args = []
|
||||
|
||||
|
@ -129,7 +129,7 @@ class Alert:
|
|||
self.creation_delay = creation_delay
|
||||
|
||||
self.alert_type = ""
|
||||
self.event_type = None
|
||||
self.event_type: Optional[str] = None
|
||||
|
||||
def __str__(self) -> str:
|
||||
return f"{self.alert_text_1}/{self.alert_text_2} {self.priority} {self.visual_alert} {self.audible_alert}"
|
||||
|
@ -139,14 +139,14 @@ class Alert:
|
|||
|
||||
|
||||
class NoEntryAlert(Alert):
|
||||
def __init__(self, alert_text_2, visual_alert=VisualAlert.none):
|
||||
def __init__(self, alert_text_2: str, visual_alert: car.CarControl.HUDControl.VisualAlert=VisualAlert.none):
|
||||
super().__init__("openpilot Unavailable", alert_text_2, AlertStatus.normal,
|
||||
AlertSize.mid, Priority.LOW, visual_alert,
|
||||
AudibleAlert.refuse, 3.)
|
||||
|
||||
|
||||
class SoftDisableAlert(Alert):
|
||||
def __init__(self, alert_text_2):
|
||||
def __init__(self, alert_text_2: str):
|
||||
super().__init__("TAKE CONTROL IMMEDIATELY", alert_text_2,
|
||||
AlertStatus.userPrompt, AlertSize.full,
|
||||
Priority.MID, VisualAlert.steerRequired,
|
||||
|
@ -155,13 +155,13 @@ class SoftDisableAlert(Alert):
|
|||
|
||||
# less harsh version of SoftDisable, where the condition is user-triggered
|
||||
class UserSoftDisableAlert(SoftDisableAlert):
|
||||
def __init__(self, alert_text_2):
|
||||
def __init__(self, alert_text_2: str):
|
||||
super().__init__(alert_text_2),
|
||||
self.alert_text_1 = "openpilot will disengage"
|
||||
|
||||
|
||||
class ImmediateDisableAlert(Alert):
|
||||
def __init__(self, alert_text_2):
|
||||
def __init__(self, alert_text_2: str):
|
||||
super().__init__("TAKE CONTROL IMMEDIATELY", alert_text_2,
|
||||
AlertStatus.critical, AlertSize.full,
|
||||
Priority.HIGHEST, VisualAlert.steerRequired,
|
||||
|
|
|
@ -1,11 +1,12 @@
|
|||
from abc import abstractmethod, ABC
|
||||
from collections import namedtuple
|
||||
from typing import Dict
|
||||
|
||||
ThermalConfig = namedtuple('ThermalConfig', ['cpu', 'gpu', 'mem', 'bat', 'ambient', 'pmic'])
|
||||
|
||||
class HardwareBase(ABC):
|
||||
@staticmethod
|
||||
def get_cmdline():
|
||||
def get_cmdline() -> Dict[str, str]:
|
||||
with open('/proc/cmdline') as f:
|
||||
cmdline = f.read()
|
||||
return {kv[0]: kv[1] for kv in [s.split('=') for s in cmdline.split(' ')] if len(kv) == 2}
|
||||
|
|
|
@ -8,6 +8,7 @@ and the image input into the neural network is not corrected for roll.
|
|||
|
||||
import os
|
||||
import copy
|
||||
from typing import NoReturn
|
||||
import numpy as np
|
||||
import cereal.messaging as messaging
|
||||
from cereal import log
|
||||
|
@ -183,11 +184,11 @@ class Calibrator():
|
|||
msg.liveCalibration.rpyCalibSpread = [float(x) for x in self.calib_spread]
|
||||
return msg
|
||||
|
||||
def send_data(self, pm):
|
||||
def send_data(self, pm) -> None:
|
||||
pm.send('liveCalibration', self.get_msg())
|
||||
|
||||
|
||||
def calibrationd_thread(sm=None, pm=None):
|
||||
def calibrationd_thread(sm=None, pm=None) -> NoReturn:
|
||||
if sm is None:
|
||||
sm = messaging.SubMaster(['cameraOdometry', 'carState'], poll=['cameraOdometry'])
|
||||
|
||||
|
@ -215,7 +216,7 @@ def calibrationd_thread(sm=None, pm=None):
|
|||
calibrator.send_data(pm)
|
||||
|
||||
|
||||
def main(sm=None, pm=None):
|
||||
def main(sm=None, pm=None) -> NoReturn:
|
||||
calibrationd_thread(sm, pm)
|
||||
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@ MAX_BUILD_PROGRESS = 100
|
|||
PREBUILT = os.path.exists(os.path.join(BASEDIR, 'prebuilt'))
|
||||
|
||||
|
||||
def build(spinner, dirty=False):
|
||||
def build(spinner: Spinner, dirty: bool = False) -> None:
|
||||
env = os.environ.copy()
|
||||
env['SCONS_PROGRESS'] = "1"
|
||||
nproc = os.cpu_count()
|
||||
|
@ -30,6 +30,7 @@ def build(spinner, dirty=False):
|
|||
|
||||
for retry in [True, False]:
|
||||
scons = subprocess.Popen(["scons", j_flag, "--cache-populate"], cwd=BASEDIR, env=env, stderr=subprocess.PIPE)
|
||||
assert scons.stderr is not None
|
||||
|
||||
compile_output = []
|
||||
|
||||
|
|
|
@ -5,7 +5,7 @@ import errno
|
|||
import signal
|
||||
|
||||
|
||||
def unblock_stdout():
|
||||
def unblock_stdout() -> None:
|
||||
# get a non-blocking stdout
|
||||
child_pid, child_pty = os.forkpty()
|
||||
if child_pid != 0: # parent
|
||||
|
|
|
@ -5,6 +5,7 @@ import signal
|
|||
import subprocess
|
||||
import sys
|
||||
import traceback
|
||||
from typing import List, Tuple, Union
|
||||
|
||||
import cereal.messaging as messaging
|
||||
import selfdrive.crash as crash
|
||||
|
@ -25,7 +26,7 @@ from selfdrive.version import is_dirty, get_commit, get_version, get_origin, get
|
|||
sys.path.append(os.path.join(BASEDIR, "pyextra"))
|
||||
|
||||
|
||||
def manager_init():
|
||||
def manager_init() -> None:
|
||||
# update system time from panda
|
||||
set_time(cloudlog)
|
||||
|
||||
|
@ -35,7 +36,7 @@ def manager_init():
|
|||
params = Params()
|
||||
params.clear_all(ParamKeyType.CLEAR_ON_MANAGER_START)
|
||||
|
||||
default_params = [
|
||||
default_params: List[Tuple[str, Union[str, bytes]]] = [
|
||||
("CompletedTrainingVersion", "0"),
|
||||
("HasAcceptedTerms", "0"),
|
||||
("OpenpilotEnabledToggle", "1"),
|
||||
|
@ -56,7 +57,7 @@ def manager_init():
|
|||
|
||||
# is this dashcam?
|
||||
if os.getenv("PASSIVE") is not None:
|
||||
params.put_bool("Passive", bool(int(os.getenv("PASSIVE"))))
|
||||
params.put_bool("Passive", bool(int(os.getenv("PASSIVE", "0"))))
|
||||
|
||||
if params.get("Passive") is None:
|
||||
raise Exception("Passive must be set to continue")
|
||||
|
@ -99,12 +100,12 @@ def manager_init():
|
|||
device=HARDWARE.get_device_type())
|
||||
|
||||
|
||||
def manager_prepare():
|
||||
def manager_prepare() -> None:
|
||||
for p in managed_processes.values():
|
||||
p.prepare()
|
||||
|
||||
|
||||
def manager_cleanup():
|
||||
def manager_cleanup() -> None:
|
||||
# send signals to kill all procs
|
||||
for p in managed_processes.values():
|
||||
p.stop(block=False)
|
||||
|
@ -116,7 +117,7 @@ def manager_cleanup():
|
|||
cloudlog.info("everything is dead")
|
||||
|
||||
|
||||
def manager_thread():
|
||||
def manager_thread() -> None:
|
||||
cloudlog.bind(daemon="manager")
|
||||
cloudlog.info("manager start")
|
||||
cloudlog.info({"environ": os.environ})
|
||||
|
@ -128,8 +129,7 @@ def manager_thread():
|
|||
ignore += ["manage_athenad", "uploader"]
|
||||
if os.getenv("NOBOARD") is not None:
|
||||
ignore.append("pandad")
|
||||
if os.getenv("BLOCK") is not None:
|
||||
ignore += os.getenv("BLOCK").split(",")
|
||||
ignore += [x for x in os.getenv("BLOCK", "").split(",") if len(x) > 0]
|
||||
|
||||
ensure_running(managed_processes.values(), started=False, not_run=ignore)
|
||||
|
||||
|
@ -176,7 +176,7 @@ def manager_thread():
|
|||
break
|
||||
|
||||
|
||||
def main():
|
||||
def main() -> None:
|
||||
prepare_only = os.getenv("PREPAREONLY") is not None
|
||||
|
||||
manager_init()
|
||||
|
|
|
@ -4,6 +4,7 @@ import signal
|
|||
import struct
|
||||
import time
|
||||
import subprocess
|
||||
from typing import Optional, List, ValuesView
|
||||
from abc import ABC, abstractmethod
|
||||
from multiprocessing import Process
|
||||
|
||||
|
@ -22,7 +23,7 @@ WATCHDOG_FN = "/dev/shm/wd_"
|
|||
ENABLE_WATCHDOG = os.getenv("NO_WATCHDOG") is None
|
||||
|
||||
|
||||
def launcher(proc, name):
|
||||
def launcher(proc: str, name: str) -> None:
|
||||
try:
|
||||
# import the process
|
||||
mod = importlib.import_module(proc)
|
||||
|
@ -37,7 +38,7 @@ def launcher(proc, name):
|
|||
cloudlog.bind(daemon=name)
|
||||
|
||||
# exec the process
|
||||
mod.main()
|
||||
getattr(mod, 'main')()
|
||||
except KeyboardInterrupt:
|
||||
cloudlog.warning(f"child {proc} got SIGINT")
|
||||
except Exception:
|
||||
|
@ -47,13 +48,13 @@ def launcher(proc, name):
|
|||
raise
|
||||
|
||||
|
||||
def nativelauncher(pargs, cwd):
|
||||
def nativelauncher(pargs: List[str], cwd: str) -> None:
|
||||
# exec the process
|
||||
os.chdir(cwd)
|
||||
os.execvp(pargs[0], pargs)
|
||||
|
||||
|
||||
def join_process(process, timeout):
|
||||
def join_process(process: Process, timeout: float) -> None:
|
||||
# Process().join(timeout) will hang due to a python 3 bug: https://bugs.python.org/issue28382
|
||||
# We have to poll the exitcode instead
|
||||
t = time.monotonic()
|
||||
|
@ -65,7 +66,8 @@ class ManagerProcess(ABC):
|
|||
unkillable = False
|
||||
daemon = False
|
||||
sigkill = False
|
||||
proc = None
|
||||
persistent = False
|
||||
proc: Optional[Process] = None
|
||||
enabled = True
|
||||
name = ""
|
||||
|
||||
|
@ -75,24 +77,25 @@ class ManagerProcess(ABC):
|
|||
shutting_down = False
|
||||
|
||||
@abstractmethod
|
||||
def prepare(self):
|
||||
def prepare(self) -> None:
|
||||
pass
|
||||
|
||||
@abstractmethod
|
||||
def start(self):
|
||||
def start(self) -> None:
|
||||
pass
|
||||
|
||||
def restart(self):
|
||||
def restart(self) -> None:
|
||||
self.stop()
|
||||
self.start()
|
||||
|
||||
def check_watchdog(self, started):
|
||||
def check_watchdog(self, started: bool) -> None:
|
||||
if self.watchdog_max_dt is None or self.proc is None:
|
||||
return
|
||||
|
||||
try:
|
||||
fn = WATCHDOG_FN + str(self.proc.pid)
|
||||
self.last_watchdog_time = struct.unpack('Q', open(fn, "rb").read())[0]
|
||||
# TODO: why can't pylint find struct.unpack?
|
||||
self.last_watchdog_time = struct.unpack('Q', open(fn, "rb").read())[0] # pylint: disable=no-member
|
||||
except Exception:
|
||||
pass
|
||||
|
||||
|
@ -106,9 +109,9 @@ class ManagerProcess(ABC):
|
|||
else:
|
||||
self.watchdog_seen = True
|
||||
|
||||
def stop(self, retry=True, block=True):
|
||||
def stop(self, retry: bool=True, block: bool=True) -> Optional[int]:
|
||||
if self.proc is None:
|
||||
return
|
||||
return None
|
||||
|
||||
if self.proc.exitcode is None:
|
||||
if not self.shutting_down:
|
||||
|
@ -118,7 +121,7 @@ class ManagerProcess(ABC):
|
|||
self.shutting_down = True
|
||||
|
||||
if not block:
|
||||
return
|
||||
return None
|
||||
|
||||
join_process(self.proc, 5)
|
||||
|
||||
|
@ -148,7 +151,7 @@ class ManagerProcess(ABC):
|
|||
|
||||
return ret
|
||||
|
||||
def signal(self, sig):
|
||||
def signal(self, sig: int) -> None:
|
||||
if self.proc is None:
|
||||
return
|
||||
|
||||
|
@ -156,6 +159,10 @@ class ManagerProcess(ABC):
|
|||
if self.proc.exitcode is not None and self.proc.pid is not None:
|
||||
return
|
||||
|
||||
# Can't signal if we don't have a pid
|
||||
if self.proc.pid is None:
|
||||
return
|
||||
|
||||
cloudlog.info(f"sending signal {sig} to {self.name}")
|
||||
os.kill(self.proc.pid, sig)
|
||||
|
||||
|
@ -182,10 +189,10 @@ class NativeProcess(ManagerProcess):
|
|||
self.sigkill = sigkill
|
||||
self.watchdog_max_dt = watchdog_max_dt
|
||||
|
||||
def prepare(self):
|
||||
def prepare(self) -> None:
|
||||
pass
|
||||
|
||||
def start(self):
|
||||
def start(self) -> None:
|
||||
# In case we only tried a non blocking stop we need to stop it before restarting
|
||||
if self.shutting_down:
|
||||
self.stop()
|
||||
|
@ -212,12 +219,12 @@ class PythonProcess(ManagerProcess):
|
|||
self.sigkill = sigkill
|
||||
self.watchdog_max_dt = watchdog_max_dt
|
||||
|
||||
def prepare(self):
|
||||
def prepare(self) -> None:
|
||||
if self.enabled:
|
||||
cloudlog.info(f"preimporting {self.module}")
|
||||
importlib.import_module(self.module)
|
||||
|
||||
def start(self):
|
||||
def start(self) -> None:
|
||||
# In case we only tried a non blocking stop we need to stop it before restarting
|
||||
if self.shutting_down:
|
||||
self.stop()
|
||||
|
@ -242,10 +249,10 @@ class DaemonProcess(ManagerProcess):
|
|||
self.enabled = enabled
|
||||
self.persistent = True
|
||||
|
||||
def prepare(self):
|
||||
def prepare(self) -> None:
|
||||
pass
|
||||
|
||||
def start(self):
|
||||
def start(self) -> None:
|
||||
params = Params()
|
||||
pid = params.get(self.param_name, encoding='utf-8')
|
||||
|
||||
|
@ -269,11 +276,11 @@ class DaemonProcess(ManagerProcess):
|
|||
|
||||
params.put(self.param_name, str(proc.pid))
|
||||
|
||||
def stop(self, retry=True, block=True):
|
||||
def stop(self, retry=True, block=True) -> None:
|
||||
pass
|
||||
|
||||
|
||||
def ensure_running(procs, started, driverview=False, not_run=None):
|
||||
def ensure_running(procs: ValuesView[ManagerProcess], started: bool, driverview: bool=False, not_run: Optional[List[str]]=None) -> None:
|
||||
if not_run is None:
|
||||
not_run = []
|
||||
|
||||
|
@ -284,7 +291,8 @@ def ensure_running(procs, started, driverview=False, not_run=None):
|
|||
p.stop(block=False)
|
||||
elif p.persistent:
|
||||
p.start()
|
||||
elif p.driverview and driverview:
|
||||
elif getattr(p, 'driverview', False) and driverview:
|
||||
# TODO: why is driverview an argument here? can this be done with the name?
|
||||
p.start()
|
||||
elif started:
|
||||
p.start()
|
||||
|
|
|
@ -4,7 +4,7 @@ import os
|
|||
import usb1
|
||||
import time
|
||||
import subprocess
|
||||
from typing import List
|
||||
from typing import List, NoReturn
|
||||
from functools import cmp_to_key
|
||||
|
||||
from panda import DEFAULT_FW_FN, DEFAULT_H7_FW_FN, MCU_TYPE_H7, Panda, PandaDFU
|
||||
|
@ -76,7 +76,7 @@ def panda_sort_cmp(a : Panda, b : Panda):
|
|||
# last resort: sort by serial number
|
||||
return a.get_usb_serial() < b.get_usb_serial()
|
||||
|
||||
def main() -> None:
|
||||
def main() -> NoReturn:
|
||||
while True:
|
||||
try:
|
||||
# Flash all Pandas in DFU mode
|
||||
|
|
|
@ -2,6 +2,7 @@ import random
|
|||
import threading
|
||||
import time
|
||||
from statistics import mean
|
||||
from typing import Optional
|
||||
|
||||
from cereal import log
|
||||
from common.params import Params, put_nonblocking
|
||||
|
@ -135,7 +136,7 @@ class PowerMonitoring:
|
|||
except Exception:
|
||||
cloudlog.exception("Power monitoring calculation failed")
|
||||
|
||||
def _perform_integration(self, t, current_power):
|
||||
def _perform_integration(self, t: float, current_power: float) -> None:
|
||||
with self.integration_lock:
|
||||
try:
|
||||
if self.last_measurement_time:
|
||||
|
@ -150,14 +151,14 @@ class PowerMonitoring:
|
|||
cloudlog.exception("Integration failed")
|
||||
|
||||
# Get the power usage
|
||||
def get_power_used(self):
|
||||
def get_power_used(self) -> int:
|
||||
return int(self.power_used_uWh)
|
||||
|
||||
def get_car_battery_capacity(self):
|
||||
def get_car_battery_capacity(self) -> int:
|
||||
return int(self.car_battery_capacity_uWh)
|
||||
|
||||
# See if we need to disable charging
|
||||
def should_disable_charging(self, ignition, in_car, offroad_timestamp):
|
||||
def should_disable_charging(self, ignition: bool, in_car: bool, offroad_timestamp: Optional[float]) -> bool:
|
||||
if offroad_timestamp is None:
|
||||
return False
|
||||
|
||||
|
|
|
@ -3,7 +3,7 @@ import datetime
|
|||
import os
|
||||
import time
|
||||
from pathlib import Path
|
||||
from typing import Dict, Optional, Tuple
|
||||
from typing import Dict, NoReturn, Optional, Tuple
|
||||
from collections import namedtuple, OrderedDict
|
||||
|
||||
import psutil
|
||||
|
@ -152,7 +152,7 @@ def set_offroad_alert_if_changed(offroad_alert: str, show_alert: bool, extra_tex
|
|||
set_offroad_alert(offroad_alert, show_alert, extra_text)
|
||||
|
||||
|
||||
def thermald_thread():
|
||||
def thermald_thread() -> NoReturn:
|
||||
|
||||
pm = messaging.PubMaster(['deviceState'])
|
||||
|
||||
|
@ -163,11 +163,11 @@ def thermald_thread():
|
|||
fan_speed = 0
|
||||
count = 0
|
||||
|
||||
onroad_conditions = {
|
||||
onroad_conditions: Dict[str, bool] = {
|
||||
"ignition": False,
|
||||
}
|
||||
startup_conditions = {}
|
||||
startup_conditions_prev = {}
|
||||
startup_conditions: Dict[str, bool] = {}
|
||||
startup_conditions_prev: Dict[str, bool] = {}
|
||||
|
||||
off_ts = None
|
||||
started_ts = None
|
||||
|
@ -424,7 +424,7 @@ def thermald_thread():
|
|||
count += 1
|
||||
|
||||
|
||||
def main():
|
||||
def main() -> NoReturn:
|
||||
thermald_thread()
|
||||
|
||||
|
||||
|
|
|
@ -3,6 +3,7 @@ import json
|
|||
import os
|
||||
import time
|
||||
import subprocess
|
||||
from typing import NoReturn
|
||||
|
||||
import requests
|
||||
from timezonefinder import TimezoneFinder
|
||||
|
@ -30,7 +31,7 @@ def set_timezone(valid_timezones, timezone):
|
|||
cloudlog.exception(f"Error setting timezone to {timezone}")
|
||||
|
||||
|
||||
def main():
|
||||
def main() -> NoReturn:
|
||||
params = Params()
|
||||
tf = TimezoneFinder()
|
||||
|
||||
|
|
|
@ -7,6 +7,7 @@ import signal
|
|||
import subprocess
|
||||
import time
|
||||
import glob
|
||||
from typing import NoReturn
|
||||
|
||||
import sentry_sdk
|
||||
|
||||
|
@ -197,7 +198,7 @@ def report_tombstone_apport(fn):
|
|||
pass
|
||||
|
||||
|
||||
def main():
|
||||
def main() -> NoReturn:
|
||||
clear_apport_folder() # Clear apport folder on start, otherwise duplicate crashes won't register
|
||||
initial_tombstones = set(get_tombstones())
|
||||
|
||||
|
|
|
@ -370,7 +370,7 @@ def fetch_update(wait_helper: WaitTimeHelper) -> bool:
|
|||
return new_version
|
||||
|
||||
|
||||
def main():
|
||||
def main() -> None:
|
||||
params = Params()
|
||||
|
||||
if params.get_bool("DisableUpdates"):
|
||||
|
@ -400,7 +400,7 @@ def main():
|
|||
overlay_init.unlink(missing_ok=True)
|
||||
|
||||
first_run = True
|
||||
last_fetch_time = 0
|
||||
last_fetch_time = 0.0
|
||||
update_failed_count = 0
|
||||
|
||||
# Set initial params for offroad alerts
|
||||
|
|
Loading…
Reference in New Issue