diff --git a/README.md b/README.md index b8b4400b23..ed864e30b7 100644 --- a/README.md +++ b/README.md @@ -327,3 +327,6 @@ NO WARRANTY EXPRESSED OR IMPLIED.** --- + +[![Total alerts](https://img.shields.io/lgtm/alerts/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/alerts/) +[![Language grade: Python](https://img.shields.io/lgtm/grade/python/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/context:python) diff --git a/common/android.py b/common/android.py index 16e60bf249..4342a4259a 100644 --- a/common/android.py +++ b/common/android.py @@ -135,8 +135,6 @@ def get_network_strength(network_type): # from SignalStrength.java def get_lte_level(rsrp, rssnr): INT_MAX = 2147483647 - lvl_rsrp = NetworkStrength.unknown - lvl_rssnr = NetworkStrength.unknown if rsrp == INT_MAX: lvl_rsrp = NetworkStrength.unknown elif rsrp >= -95: @@ -174,7 +172,6 @@ def get_network_strength(network_type): return lvl def get_gsm_level(asu): - lvl = NetworkStrength.unknown if asu <= 2 or asu == 99: lvl = NetworkStrength.unknown elif asu >= 12: diff --git a/common/url_file.py b/common/url_file.py index 0e44b0e42f..1f6d4a0813 100644 --- a/common/url_file.py +++ b/common/url_file.py @@ -1,14 +1,11 @@ import os -import sys import time import tempfile import threading import urllib.parse import pycurl -import hashlib from io import BytesIO from tenacity import retry, wait_random_exponential, stop_after_attempt -from common.file_helpers import mkdirs_exists_ok, atomic_write_in_dir class URLFile(object): _tlocal = threading.local() diff --git a/common/window.py b/common/window.py index a3ff020c6f..f93f532cb4 100644 --- a/common/window.py +++ b/common/window.py @@ -1,6 +1,5 @@ import sys import pygame -from pygame.locals import * class Window(): def __init__(self, w, h, caption="window", double=False): diff --git a/scripts/code_stats.py b/scripts/code_stats.py index 0fc3462102..ccd32c7e50 100755 --- a/scripts/code_stats.py +++ b/scripts/code_stats.py @@ -1,5 +1,5 @@ #!/usr/bin/env python3 -import os, glob +import os import ast import stat import subprocess diff --git a/selfdrive/athena/manage_athenad.py b/selfdrive/athena/manage_athenad.py index 2954c70b8b..49120d972f 100755 --- a/selfdrive/athena/manage_athenad.py +++ b/selfdrive/athena/manage_athenad.py @@ -27,10 +27,10 @@ def main(): proc.join() cloudlog.event("athenad exited", exitcode=proc.exitcode) time.sleep(5) - except: + except Exception: cloudlog.exception("manage_athenad.exception") finally: params.delete(ATHENA_MGR_PID_PARAM) if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/selfdrive/car/chrysler/radar_interface.py b/selfdrive/car/chrysler/radar_interface.py index 0713bf1d16..40a7c5a742 100755 --- a/selfdrive/car/chrysler/radar_interface.py +++ b/selfdrive/car/chrysler/radar_interface.py @@ -48,8 +48,7 @@ def _address_to_track(address): class RadarInterface(RadarInterfaceBase): def __init__(self, CP): - self.pts = {} - self.delay = 0 # Delay of radar #TUNE + super().__init__(CP) self.rcp = _create_radar_can_parser() self.updated_messages = set() self.trigger_msg = LAST_MSG diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index 048f556fd3..3733ddce7f 100755 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -19,13 +19,10 @@ def _create_radar_can_parser(car_fingerprint): class RadarInterface(RadarInterfaceBase): def __init__(self, CP): - # radar - self.pts = {} + super().__init__(CP) self.validCnt = {key: 0 for key in RADAR_MSGS} self.track_id = 0 - self.delay = 0 # Delay of radar - self.rcp = _create_radar_can_parser(CP.carFingerprint) self.trigger_msg = 0x53f self.updated_messages = set() diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py index b20706a058..8a2f9a2e69 100755 --- a/selfdrive/car/gm/radar_interface.py +++ b/selfdrive/car/gm/radar_interface.py @@ -43,10 +43,7 @@ def create_radar_can_parser(car_fingerprint): class RadarInterface(RadarInterfaceBase): def __init__(self, CP): - # radar - self.pts = {} - - self.delay = 0 # Delay of radar + super().__init__(CP) self.rcp = create_radar_can_parser(CP.carFingerprint) diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py index 3c07cd74cd..b1606e64ad 100755 --- a/selfdrive/car/honda/radar_interface.py +++ b/selfdrive/car/honda/radar_interface.py @@ -20,8 +20,7 @@ def _create_nidec_can_parser(): class RadarInterface(RadarInterfaceBase): def __init__(self, CP): - # radar - self.pts = {} + super().__init__(CP) self.track_id = 0 self.radar_fault = False self.radar_wrong_config = False diff --git a/selfdrive/car/hyundai/radar_interface.py b/selfdrive/car/hyundai/radar_interface.py index 444fab781f..b5bdcd8363 100644 --- a/selfdrive/car/hyundai/radar_interface.py +++ b/selfdrive/car/hyundai/radar_interface.py @@ -24,9 +24,7 @@ def get_radar_can_parser(CP): class RadarInterface(RadarInterfaceBase): def __init__(self, CP): - # radar - self.pts = {} - self.delay = 0 # Delay of radar + super().__init__(CP) self.rcp = get_radar_can_parser(CP) self.updated_messages = set() self.trigger_msg = 0x420 diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index 6988a5ff77..1539fe6e80 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 from cereal import car -from selfdrive.config import Conversions as CV from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET from selfdrive.car.nissan.values import CAR from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint diff --git a/selfdrive/car/nissan/nissancan.py b/selfdrive/car/nissan/nissancan.py index 6786774c3e..a264442e64 100644 --- a/selfdrive/car/nissan/nissancan.py +++ b/selfdrive/car/nissan/nissancan.py @@ -1,6 +1,5 @@ import copy import crcmod -from selfdrive.car.nissan.values import CAR nissan_checksum = crcmod.mkCrcFun(0x11d, initCrc=0x00, rev=False, xorOut=0xff) diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py index 80977b706c..12387d489f 100755 --- a/selfdrive/car/toyota/radar_interface.py +++ b/selfdrive/car/toyota/radar_interface.py @@ -30,11 +30,8 @@ def _create_radar_can_parser(car_fingerprint): class RadarInterface(RadarInterfaceBase): def __init__(self, CP): - # radar - self.pts = {} + super().__init__(CP) self.track_id = 0 - - self.delay = 0 # Delay of radar self.radar_ts = CP.radarTimeStep if CP.carFingerprint in TSS2_CAR: diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 45047d4185..828ef85751 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -98,7 +98,7 @@ FINGERPRINTS = { }, #2017 German Prius { - 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296:8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8,740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1792: 8, 1767:4, 800: 8, 1863:8, 1904: 8, 1912: 8, 1984: 8, 1988: 8, 1990: 8, 1992: 8, 1996:8, 1998: 8, 2002: 8, 2010: 8, 2015: 8, 2016: 8, 2018: 8, 2024: 8, 2026: 8, 2030: 8 + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296:8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8,740: 5, 742: 8, 743: 8, 767:4, 800: 8, 810: 2, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1792: 8, 1767:4, 1863:8, 1904: 8, 1912: 8, 1984: 8, 1988: 8, 1990: 8, 1992: 8, 1996:8, 1998: 8, 2002: 8, 2010: 8, 2015: 8, 2016: 8, 2018: 8, 2024: 8, 2026: 8, 2030: 8 }], #Corolla w/ added Pedal Support (512L and 513L) CAR.COROLLA: [{ @@ -151,7 +151,7 @@ FINGERPRINTS = { }, { # 2019 XSE - 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 942: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1792: 8, 1767:4, 800: 8, 1808: 8, 1816: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1937: 8, 1945: 8, 1953: 8, 1961: 8, 1968: 8, 1976: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767:4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 942: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1792: 8, 1767:4, 1808: 8, 1816: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1937: 8, 1945: 8, 1953: 8, 1961: 8, 1968: 8, 1976: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 }], CAR.CAMRYH: [ #SE, LE and LE with Blindspot Monitor diff --git a/selfdrive/crash.py b/selfdrive/crash.py index 74a7094ae5..a8cb758a7e 100644 --- a/selfdrive/crash.py +++ b/selfdrive/crash.py @@ -40,7 +40,7 @@ else: __excepthook__ = sys.excepthook def handle_exception(*exc_info): if exc_info[0] not in (KeyboardInterrupt, SystemExit): - capture_exception(exc_info=exc_info) + capture_exception() __excepthook__(*exc_info) sys.excepthook = handle_exception diff --git a/selfdrive/debug/internal/measure_steering_accuracy.py b/selfdrive/debug/internal/measure_steering_accuracy.py index 83f297bcb7..fabf8030d1 100755 --- a/selfdrive/debug/internal/measure_steering_accuracy.py +++ b/selfdrive/debug/internal/measure_steering_accuracy.py @@ -2,8 +2,7 @@ import os import argparse import signal -from collections import deque, defaultdict -from statistics import mean +from collections import defaultdict import cereal.messaging as messaging diff --git a/selfdrive/debug/internal/measure_torque_time_to_max.py b/selfdrive/debug/internal/measure_torque_time_to_max.py index a7d450ede9..d1beeae44d 100755 --- a/selfdrive/debug/internal/measure_torque_time_to_max.py +++ b/selfdrive/debug/internal/measure_torque_time_to_max.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 import os -import sys import argparse import struct from collections import deque @@ -8,7 +7,6 @@ from statistics import mean from cereal import log import cereal.messaging as messaging -from cereal.services import service_list if __name__ == "__main__": diff --git a/selfdrive/debug/mpc/tune_longitudinal.py b/selfdrive/debug/mpc/tune_longitudinal.py index 0af444631d..ed3eb6378a 100755 --- a/selfdrive/debug/mpc/tune_longitudinal.py +++ b/selfdrive/debug/mpc/tune_longitudinal.py @@ -3,7 +3,6 @@ import numpy as np import matplotlib.pyplot as plt from selfdrive.controls.lib.longitudinal_mpc import libmpc_py from selfdrive.controls.lib.drive_helpers import MPC_COST_LONG -import math # plot liongitudinal MPC trajectory by defining boundary conditions: # ego and lead vehicles state. Use this script to tune MPC costs @@ -16,7 +15,7 @@ def RW(v_ego, v_l): def NORM_RW_ERROR(v_ego, v_l, p): return (RW(v_ego, v_l) + 4.0 - p) - return (RW(v_ego, v_l) + 4.0 - p) / (np.sqrt(v_ego + 0.5) + 0.1) + #return (RW(v_ego, v_l) + 4.0 - p) / (np.sqrt(v_ego + 0.5) + 0.1) v_ego = 20.0 @@ -36,7 +35,7 @@ a_lead_tau = 0. # a_lead_tau = 2.90729817665 -min_a_lead_tau = (a_lead**2 * math.pi) / (2 * (v_lead + 0.01)**2) +#min_a_lead_tau = (a_lead**2 * math.pi) / (2 * (v_lead + 0.01)**2) min_a_lead_tau = 0.0 print(a_lead_tau, min_a_lead_tau) diff --git a/selfdrive/debug/tuner.py b/selfdrive/debug/tuner.py deleted file mode 100755 index b8a023ba29..0000000000 --- a/selfdrive/debug/tuner.py +++ /dev/null @@ -1,67 +0,0 @@ -#!/usr/bin/env python3 -""" -This tool can be used to quickly changes the values in a JSON file used for tuning -Keys like in vim: - - h: decrease by 0.05 - - l: increase by 0.05 - - k: move pointer up - - j: move pointer down -""" - -import tty -import sys -import json -import termios -from collections import OrderedDict - -FILENAME = '/data/tuning.json' - -def read_tuning(): - while True: - try: - return json.loads(open(FILENAME).read()) - except: - pass - -def main(): - dat = json.loads(open(FILENAME, 'r').read()) - dat = OrderedDict(sorted(dat.items(), key=lambda i: i[0])) - - cur = 0 - while True: - sys.stdout.write("\x1Bc") - - for i, (k, v) in enumerate(dat.items()): - prefix = "> " if cur == i else " " - print((prefix + k).ljust(20) + "%.2f" % v) - - key = sys.stdin.read(1)[0] - - write = False - if key == "k": - cur = max(0, cur - 1) - elif key == "j": - cur = min(len(dat.keys()) - 1, cur + 1) - elif key == "l": - dat[dat.keys()[cur]] += 0.05 - write = True - elif key == "h": - dat[dat.keys()[cur]] -= 0.05 - write = True - elif key == "q": - break - - if write: - open(FILENAME, 'w').write(json.dumps(dat)) - - -if __name__ == "__main__": - orig_settings = termios.tcgetattr(sys.stdin) - tty.setcbreak(sys.stdin) - - try: - main() - termios.tcsetattr(sys.stdin, termios.TCSADRAIN, orig_settings) - except: - termios.tcsetattr(sys.stdin, termios.TCSADRAIN, orig_settings) - raise diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 0df43d0dcd..a147dde503 100644 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -182,7 +182,6 @@ class Localizer(): initial_pose_ecef_quat = quat_from_euler(initial_pose_ecef) gps_speed = log.speed quat_uncertainty = 0.2**2 - initial_pose_ecef_quat = quat_from_euler(initial_pose_ecef) initial_state = LiveKalman.initial_x initial_covs_diag = LiveKalman.initial_P_diag diff --git a/selfdrive/loggerd/ethernetsniffer.py b/selfdrive/loggerd/ethernetsniffer.py index 9f17c29d7c..023dacc90b 100755 --- a/selfdrive/loggerd/ethernetsniffer.py +++ b/selfdrive/loggerd/ethernetsniffer.py @@ -1,7 +1,5 @@ #!/usr/bin/env python3 -import zmq import cereal.messaging as messaging -from cereal.services import service_list import pcap def main(): diff --git a/selfdrive/modeld/visiontest.py b/selfdrive/modeld/visiontest.py index f9661bf463..f3c10c5986 100644 --- a/selfdrive/modeld/visiontest.py +++ b/selfdrive/modeld/visiontest.py @@ -10,7 +10,7 @@ try: # bacause this crashes somtimes when running pipeline subprocess.check_output(["make", "-C", _visiond_dir, "-f", os.path.join(_visiond_dir, "visiontest.mk"), _libvisiontest]) -except: +except Exception: pass class VisionTest(): diff --git a/tools/lib/framereader.py b/tools/lib/framereader.py index 727abea743..f9c070b0bd 100644 --- a/tools/lib/framereader.py +++ b/tools/lib/framereader.py @@ -21,7 +21,6 @@ import subprocess from aenum import Enum from lru import LRU from functools import wraps -from concurrent.futures import ThreadPoolExecutor, as_completed from tools.lib.cache import cache_path_for_file_path from tools.lib.exceptions import DataUnreadableError diff --git a/tools/lib/logreader.py b/tools/lib/logreader.py index f5bca5607f..1760494522 100755 --- a/tools/lib/logreader.py +++ b/tools/lib/logreader.py @@ -4,10 +4,8 @@ import sys import json import bz2 import tempfile -import requests import subprocess import urllib.parse -from aenum import Enum import capnp import numpy as np diff --git a/tools/lib/mkvparse/mkvindex.py b/tools/lib/mkvparse/mkvindex.py index f985280d9d..c05423006a 100644 --- a/tools/lib/mkvparse/mkvindex.py +++ b/tools/lib/mkvparse/mkvindex.py @@ -1,7 +1,6 @@ #!/usr/bin/env python # Copyright (c) 2016, Comma.ai, Inc. -import sys import re import binascii @@ -64,24 +63,3 @@ def simple_gen(of, config_record, w, h, framedata): # + ebml_element(0xA7, ben(0)) # Position, uint + ''.join(blocks))) -if __name__ == "__main__": - import random - - if len(sys.argv) != 2: - print("usage: %s mkvpath" % sys.argv[0]) - with open(sys.argv[1], "rb") as f: - cr, index = mkvindex(f) - - # cr = "280000003002000030010000010018004646563100cb070000000000000000000000000000000000".decode("hex") - - def geti(i): - pos, length = index[i] - with open(sys.argv[1], "rb") as f: - f.seek(pos) - return f.read(length) - - dats = [geti(random.randrange(200)) for _ in xrange(30)] - - with open("tmpout.mkv", "wb") as of: - simple_gen(of, cr, dats) - diff --git a/tools/livedm/livedm.py b/tools/livedm/livedm.py index 5125f0e2c7..60361d9207 100644 --- a/tools/livedm/livedm.py +++ b/tools/livedm/livedm.py @@ -23,7 +23,7 @@ if __name__ == "__main__": poller = messaging.Poller() m = 'driverMonitoring' - sock = messaging.sub_sock(m, poller, addr=args.addr) + messaging.sub_sock(m, poller, addr=args.addr) pygame.init() pygame.display.set_caption('livedm') diff --git a/tools/nui/.gitignore b/tools/nui/.gitignore index 9341b87ec5..73f9715483 100644 --- a/tools/nui/.gitignore +++ b/tools/nui/.gitignore @@ -6,4 +6,5 @@ moc_* .qmake.stash nui.app/* routes.json +_nui.app diff --git a/tools/nui/Unlogger.cpp b/tools/nui/Unlogger.cpp index 843ef51e3f..c217a06783 100644 --- a/tools/nui/Unlogger.cpp +++ b/tools/nui/Unlogger.cpp @@ -15,7 +15,11 @@ static inline uint64_t nanos_since_boot() { struct timespec t; - clock_gettime(CLOCK_BOOTTIME, &t); + #ifdef __APPLE__ + clock_gettime(CLOCK_REALTIME, &t); + #else + clock_gettime(CLOCK_BOOTTIME, &t); + #endif return t.tv_sec * 1000000000ULL + t.tv_nsec; } diff --git a/tools/replay/camera.py b/tools/replay/camera.py index af59af54c7..ab0f5f8c45 100755 --- a/tools/replay/camera.py +++ b/tools/replay/camera.py @@ -6,18 +6,11 @@ os.environ['BASEDIR'] = BASEDIR SCALE = float(os.getenv("SCALE", 1.0)) import argparse -import zmq import pygame import numpy as np import cv2 import sys -import traceback -from collections import namedtuple -from cereal import car -from common.params import Params from tools.lib.lazy_property import lazy_property -from cereal.messaging import sub_sock, recv_one_or_none, recv_one -from cereal.services import service_list import cereal.messaging as messaging _BB_OFFSET = 0, 0 @@ -33,8 +26,6 @@ def pygame_modules_have_loaded(): def ui_thread(addr, frame_address): - context = zmq.Context.instance() - pygame.init() pygame.font.init() assert pygame_modules_have_loaded() diff --git a/tools/replay/lib/ui_helpers.py b/tools/replay/lib/ui_helpers.py index 7c918b160f..8aaf40afcb 100644 --- a/tools/replay/lib/ui_helpers.py +++ b/tools/replay/lib/ui_helpers.py @@ -1,4 +1,3 @@ -import platform from collections import namedtuple import matplotlib diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index 6979e44f81..0235e1d9ff 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -1,7 +1,5 @@ #!/usr/bin/env python3 -import carla -import os -import time, termios, tty, sys +import time import math import atexit import numpy as np @@ -9,7 +7,6 @@ import threading import random import cereal.messaging as messaging import argparse -import queue from common.params import Params from common.realtime import Ratekeeper from lib.can import can_function, sendcan_function diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index 509bb30198..867a8447e7 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -1,5 +1,4 @@ #!/usr/bin/env python3 -import time import cereal.messaging as messaging from opendbc.can.parser import CANParser from opendbc.can.packer import CANPacker @@ -92,13 +91,3 @@ def sendcan_function(sendcan): return (gas, brake, steer_torque) -if __name__ == "__main__": - pm = messaging.PubMaster(['can']) - sendcan = messaging.sub_sock('sendcan') - idx = 0 - while 1: - sendcan_function(sendcan) - can_function(pm, 10.0, idx) - time.sleep(0.01) - idx += 1 -