From d9bf9f0a4036f55411f6dfbb438990a5eb7f4930 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Sat, 30 May 2020 20:14:58 -0700 Subject: [PATCH] Enable more flake8 checks (#1602) * enable some more flake8 checks * some more quick ones * bump opendbc * e401 * e711 e712 * e115 e116 * e222 * e301 * remove that * e129 * e701 e702 * e125 e131 * e227 * e306 * e262 * W503 * e713 * e704 * e731 * bump opendbc * fix some e722 --- .pre-commit-config.yaml | 3 +- common/android.py | 3 +- common/api/__init__.py | 1 - common/basedir.py | 1 - common/file_helpers.py | 6 ++-- common/logging_extra.py | 7 +++-- common/numpy_fast.py | 5 ++-- common/params.py | 3 +- common/profiler.py | 1 - common/stat_live.py | 2 +- common/string_helpers.py | 2 +- common/testing.py | 1 - common/timeout.py | 1 - common/transformations/camera.py | 1 - common/transformations/coordinates.py | 2 +- common/url_file.py | 6 +++- opendbc | 2 +- scripts/code_stats.py | 2 +- selfdrive/boardd/tests/boardd_old.py | 4 +-- selfdrive/camerad/test/frame_test.py | 4 +-- selfdrive/car/__init__.py | 1 - selfdrive/car/ford/carcontroller.py | 2 +- selfdrive/car/ford/fordcan.py | 2 +- selfdrive/car/gm/carcontroller.py | 3 +- selfdrive/car/gm/carstate.py | 6 ++-- selfdrive/car/gm/gmcan.py | 1 - selfdrive/car/gm/interface.py | 6 ++-- selfdrive/car/gm/radar_interface.py | 2 +- selfdrive/car/honda/carstate.py | 4 +-- selfdrive/car/hyundai/carcontroller.py | 2 +- selfdrive/car/hyundai/carstate.py | 4 +-- selfdrive/car/hyundai/interface.py | 4 +-- selfdrive/car/mazda/__init__.py | 1 - selfdrive/car/mazda/carcontroller.py | 2 +- selfdrive/car/mazda/carstate.py | 5 ++-- selfdrive/car/mazda/interface.py | 2 +- selfdrive/car/mazda/mazdacan.py | 8 +++--- selfdrive/car/mazda/radar_interface.py | 1 - selfdrive/car/mazda/values.py | 4 +-- selfdrive/car/subaru/__init__.py | 1 - selfdrive/car/toyota/carcontroller.py | 6 ++-- selfdrive/car/toyota/interface.py | 6 ++-- selfdrive/car/toyota/radar_interface.py | 2 +- selfdrive/car/toyota/values.py | 28 +++++++++---------- selfdrive/car/volkswagen/__init__.py | 1 - selfdrive/car/volkswagen/carcontroller.py | 2 +- selfdrive/config.py | 1 - selfdrive/controls/controlsd.py | 4 +-- selfdrive/controls/lib/driverview.py | 2 +- selfdrive/controls/lib/latcontrol_indi.py | 2 +- selfdrive/controls/lib/latcontrol_lqr.py | 4 +-- selfdrive/controls/lib/vehicle_model.py | 1 - selfdrive/controls/tests/test_events.py | 3 +- selfdrive/controls/tests/test_monitoring.py | 2 +- selfdrive/crash.py | 4 +++ selfdrive/launcher.py | 2 +- selfdrive/locationd/calibration_helpers.py | 1 - selfdrive/locationd/test/ephemeris.py | 2 -- selfdrive/locationd/test/ublox.py | 13 +++++---- selfdrive/locationd/test/ubloxd.py | 14 +++++----- selfdrive/loggerd/tools/mark_unuploaded.py | 1 - selfdrive/loggerd/uploader.py | 4 ++- .../longitudinal_maneuvers/maneuverplots.py | 11 ++++---- .../test/longitudinal_maneuvers/plant.py | 14 +++++----- selfdrive/test/process_replay/compare_logs.py | 8 +++--- .../test/process_replay/process_replay.py | 6 ++-- .../test/process_replay/test_processes.py | 6 ++-- selfdrive/test/test_car_models.py | 10 +++---- selfdrive/test/test_leeco_alt_fan.py | 2 +- selfdrive/thermald/thermald.py | 2 +- tools/carcontrols/joystick_test.py | 4 +-- tools/lib/route.py | 12 +++++--- tools/lib/route_framereader.py | 7 +++-- tools/replay/lib/ui_helpers.py | 14 ++++------ tools/replay/unlogger.py | 10 +++++-- tools/sim/bridge.py | 2 +- tools/sim/lib/can.py | 6 ++-- tools/sim/lib/manual_ctrl.py | 4 ++- tools/webcam/accept_terms.py | 2 +- 79 files changed, 179 insertions(+), 164 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 5eebcfa4b..020c7e9e7 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,7 +17,8 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - - --select=F + - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E221,E225,E226,E231,E241,E251,E261,E265,E266,E302,E303,E305,E402,E501,E502,E722,E741,W504 + - --statistics - repo: local hooks: - id: pylint diff --git a/common/android.py b/common/android.py index 4342a4259..cb6a7748d 100644 --- a/common/android.py +++ b/common/android.py @@ -25,7 +25,7 @@ def get_imei(slot): ret = parse_service_call_string(service_call(["iphonesubinfo", "3" ,"i32", str(slot)])) if not ret: # allow non android to be identified differently - ret = "%015d" % random.randint(0, 1<<32) + ret = "%015d" % random.randint(0, 1 << 32) return ret def get_serial(): @@ -132,6 +132,7 @@ def get_network_type(): def get_network_strength(network_type): network_strength = NetworkStrength.unknown + # from SignalStrength.java def get_lte_level(rsrp, rssnr): INT_MAX = 2147483647 diff --git a/common/api/__init__.py b/common/api/__init__.py index 38fe6b247..f44e48f96 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -39,4 +39,3 @@ def api_get(endpoint, method='GET', timeout=None, access_token=None, **params): headers['User-Agent'] = "openpilot-" + version return requests.request(method, backend+endpoint, timeout=timeout, headers = headers, params=params) - diff --git a/common/basedir.py b/common/basedir.py index e928ded4c..4d62fdc19 100644 --- a/common/basedir.py +++ b/common/basedir.py @@ -8,4 +8,3 @@ if ANDROID: else: PERSIST = os.path.join(BASEDIR, "persist") PARAMS = os.path.join(BASEDIR, "persist", "params") - diff --git a/common/file_helpers.py b/common/file_helpers.py index 40c89fab0..187f0f9ac 100644 --- a/common/file_helpers.py +++ b/common/file_helpers.py @@ -44,7 +44,8 @@ class AutoMoveTempdir(): def close(self): os.rename(self._path, self._target_path) - def __enter__(self): return self + def __enter__(self): + return self def __exit__(self, type, value, traceback): if type is None: @@ -63,7 +64,8 @@ class NamedTemporaryDir(): def close(self): shutil.rmtree(self._path) - def __enter__(self): return self + def __enter__(self): + return self def __exit__(self, type, value, traceback): self.close() diff --git a/common/logging_extra.py b/common/logging_extra.py index b5d07f220..2c49561fb 100644 --- a/common/logging_extra.py +++ b/common/logging_extra.py @@ -68,8 +68,11 @@ class SwagErrorFilter(logging.Filter): def filter(self, record): return record.levelno < logging.ERROR -_tmpfunc = lambda: 0 -_srcfile = os.path.normcase(_tmpfunc.__code__.co_filename) +def _tmpfunc(): + return 0 + +def _srcfile(): + return os.path.normcase(_tmpfunc.__code__.co_filename) class SwagLogger(logging.Logger): def __init__(self): diff --git a/common/numpy_fast.py b/common/numpy_fast.py index a5d5ad3f5..a8361214d 100644 --- a/common/numpy_fast.py +++ b/common/numpy_fast.py @@ -6,6 +6,7 @@ def clip(x, lo, hi): def interp(x, xp, fp): N = len(xp) + def get_interp(xv): hi = 0 while hi < N and xv > xp[hi]: @@ -14,8 +15,8 @@ def interp(x, xp, fp): return fp[-1] if hi == N and xv > xp[low] else ( fp[0] if hi == 0 else (xv - xp[low]) * (fp[hi] - fp[low]) / (xp[hi] - xp[low]) + fp[low]) - return [get_interp(v) for v in x] if hasattr( - x, '__iter__') else get_interp(x) + + return [get_interp(v) for v in x] if hasattr(x, '__iter__') else get_interp(x) def mean(x): return sum(x) / len(x) diff --git a/common/params.py b/common/params.py index 0a7e6daf9..b92f17ca2 100755 --- a/common/params.py +++ b/common/params.py @@ -195,7 +195,8 @@ class DBReader(DBAccessor): finally: lock.release() - def __exit__(self, type, value, traceback): pass + def __exit__(self, type, value, traceback): + pass class DBWriter(DBAccessor): diff --git a/common/profiler.py b/common/profiler.py index f8262dd83..ac28bdac4 100644 --- a/common/profiler.py +++ b/common/profiler.py @@ -43,4 +43,3 @@ class Profiler(): else: print("%30s: %9.2f percent: %3.0f" % (n, ms*1000.0, ms/self.tot*100)) print("Iter clock: %2.6f TOTAL: %2.2f" % (self.tot/self.iter, self.tot)) - diff --git a/common/stat_live.py b/common/stat_live.py index e528c3dea..bab982888 100644 --- a/common/stat_live.py +++ b/common/stat_live.py @@ -32,7 +32,7 @@ class RunningStat(): self.S_last = 0. else: self.M = self.M_last + (new_data - self.M_last) / self.n - self.S = self.S_last + (new_data - self.M_last) * (new_data - self.M); + self.S = self.S_last + (new_data - self.M_last) * (new_data - self.M) self.M_last = self.M self.S_last = self.S diff --git a/common/string_helpers.py b/common/string_helpers.py index 8a7624a27..3038605fb 100644 --- a/common/string_helpers.py +++ b/common/string_helpers.py @@ -3,4 +3,4 @@ def replace_right(s, old, new, occurrence): # replace_right('1232425', '2', ' ', 2) -> '123 4 5' split = s.rsplit(old, occurrence) - return new.join(split) \ No newline at end of file + return new.join(split) diff --git a/common/testing.py b/common/testing.py index 7e8b16d5c..95c43b574 100644 --- a/common/testing.py +++ b/common/testing.py @@ -6,4 +6,3 @@ def phone_only(x): return x else: return nottest(x) - diff --git a/common/timeout.py b/common/timeout.py index c2c1f6971..4d424cdc0 100644 --- a/common/timeout.py +++ b/common/timeout.py @@ -25,4 +25,3 @@ class Timeout: def __exit__(self, exc_type, exc_val, exc_tb): signal.alarm(0) - diff --git a/common/transformations/camera.py b/common/transformations/camera.py index 5ca9eb57d..3e8ee16e3 100644 --- a/common/transformations/camera.py +++ b/common/transformations/camera.py @@ -145,4 +145,3 @@ def pretransform_from_calib(calib): camera_frame_from_road_frame = np.dot(eon_intrinsics, view_frame_from_road_frame) camera_frame_from_calib_frame = get_camera_frame_from_calib_frame(camera_frame_from_road_frame) return np.linalg.inv(camera_frame_from_calib_frame) - diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index c5d76b6e0..3f9ba23f2 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -52,7 +52,7 @@ def ecef2geodetic(ecef, radians=False): S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C)) P = F / (3 * pow((S + 1 / S + 1), 2) * G * G) Q = np.sqrt(1 + 2 * esq * esq * P) - r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \ + r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \ P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r) U = np.sqrt(pow((r - esq * r_0), 2) + z * z) V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z) diff --git a/common/url_file.py b/common/url_file.py index 184b7452b..4ba819204 100644 --- a/common/url_file.py +++ b/common/url_file.py @@ -50,12 +50,16 @@ class URLFile(object): if self._debug: print("downloading", self._url) + def header(x): if b'MISS' in x: print(x.strip()) + c.setopt(pycurl.HEADERFUNCTION, header) + def test(debug_type, debug_msg): print(" debug(%d): %s" % (debug_type, debug_msg.strip())) + c.setopt(pycurl.VERBOSE, 1) c.setopt(pycurl.DEBUGFUNCTION, test) t1 = time.time() @@ -68,7 +72,7 @@ class URLFile(object): print("get %s %r %.f slow" % (self._url, trange, t2-t1)) response_code = c.getinfo(pycurl.RESPONSE_CODE) - if response_code == 416: # Requested Range Not Satisfiable + if response_code == 416: # Requested Range Not Satisfiable return "" if response_code != 206 and response_code != 200: raise Exception("Error {} ({}): {}".format(response_code, self._url, repr(dats.getvalue())[:500])) diff --git a/opendbc b/opendbc index 0430bfa5c..b15edbc1b 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 0430bfa5c2b08f9cc6ab32470fe8ac9465e7a876 +Subproject commit b15edbc1b5a68fd725ea45ba9442a6c9be875971 diff --git a/scripts/code_stats.py b/scripts/code_stats.py index ccd32c7e5..d3bc48bce 100755 --- a/scripts/code_stats.py +++ b/scripts/code_stats.py @@ -20,6 +20,7 @@ class Analyzer(ast.NodeVisitor): for alias in node.names: imps.add(alias.name) self.generic_visit(node) + def visit_ImportFrom(self, node): imps.add(node.module) self.generic_visit(node) @@ -38,4 +39,3 @@ for f in sorted(pyf): print("%d lines of parsed openpilot python" % tlns) #print(sorted(list(imps))) - diff --git a/selfdrive/boardd/tests/boardd_old.py b/selfdrive/boardd/tests/boardd_old.py index f6ca7eb87..c5ff9263b 100755 --- a/selfdrive/boardd/tests/boardd_old.py +++ b/selfdrive/boardd/tests/boardd_old.py @@ -21,7 +21,7 @@ SafetyModel = car.CarParams.SafetyModel # USB is optional try: import usb1 - from usb1 import USBErrorIO, USBErrorOverflow #pylint: disable=no-name-in-module + from usb1 import USBErrorIO, USBErrorOverflow # pylint: disable=no-name-in-module except Exception: pass @@ -57,7 +57,7 @@ def __parse_can_buffer(dat): for j in range(0, len(dat), 0x10): ddat = dat[j:j+0x10] f1, f2 = struct.unpack("II", ddat[0:8]) - ret.append((f1 >> 21, f2>>16, ddat[8:8+(f2&0xF)], (f2>>4)&0xFF)) + ret.append((f1 >> 21, f2 >> 16, ddat[8:8 + (f2 & 0xF)], (f2 >> 4) & 0xFF)) return ret def can_send_many(arr): diff --git a/selfdrive/camerad/test/frame_test.py b/selfdrive/camerad/test/frame_test.py index d7b677c23..6b8b99ae8 100755 --- a/selfdrive/camerad/test/frame_test.py +++ b/selfdrive/camerad/test/frame_test.py @@ -6,7 +6,7 @@ from PIL import ImageFont, ImageDraw, Image font = ImageFont.truetype("arial", size=72) def get_frame(idx): img = np.zeros((874, 1164, 3), np.uint8) - img[100:400, 100:100+(idx%10)*100] = 255 + img[100:400, 100:100+(idx % 10)* 100] = 255 # big number im2 = Image.new("RGB", (200,200)) @@ -28,7 +28,7 @@ if __name__ == "__main__": dat.valid = True dat.frame = { "frameId": idx, - "image": frm[idx%len(frm)], + "image": frm[idx % len(frm)], } pm.send('frame', dat) diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 6ad29d4b3..1d579543a 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -128,4 +128,3 @@ def is_ecu_disconnected(fingerprint, fingerprint_list, ecu_fingerprint, car, ecu def make_can_msg(addr, dat, bus): return [addr, 0, dat, bus] - diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py index 4c0a37ab0..648fa0774 100644 --- a/selfdrive/car/ford/carcontroller.py +++ b/selfdrive/car/ford/carcontroller.py @@ -78,7 +78,7 @@ class CarController(): static_msgs = range(1653, 1658) for addr in static_msgs: cnt = (frame % 10) + 1 - can_sends.append(make_can_msg(addr, (cnt<<4).to_bytes(1, 'little') + b'\x00\x00\x00\x00\x00\x00\x00', 1)) + can_sends.append(make_can_msg(addr, (cnt << 4).to_bytes(1, 'little') + b'\x00\x00\x00\x00\x00\x00\x00', 1)) self.enabled_last = enabled self.main_on_last = CS.out.cruiseState.available diff --git a/selfdrive/car/ford/fordcan.py b/selfdrive/car/ford/fordcan.py index dd0c15415..f2ebb9100 100644 --- a/selfdrive/car/ford/fordcan.py +++ b/selfdrive/car/ford/fordcan.py @@ -6,7 +6,7 @@ def create_steer_command(packer, angle_cmd, enabled, lkas_state, angle_steers, c """Creates a CAN message for the Ford Steer Command.""" #if enabled and lkas available: - if enabled and lkas_state in [2,3]: #and (frame % 500) >= 3: + if enabled and lkas_state in [2,3]: # and (frame % 500) >= 3: action = lkas_action else: action = 0xf diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index f84ea3e32..06f87113a 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -161,8 +161,7 @@ class CarController(): lka_active = CS.lkas_status == 1 lka_critical = lka_active and abs(actuators.steer) > 0.9 lka_icon_status = (lka_active, lka_critical) - if frame % P.CAMERA_KEEPALIVE_STEP == 0 \ - or lka_icon_status != self.lka_icon_status_last: + if frame % P.CAMERA_KEEPALIVE_STEP == 0 or lka_icon_status != self.lka_icon_status_last: steer_alert = hud_alert == VisualAlert.steerRequired can_sends.append(gmcan.create_lka_icon_command(CanBus.SW_GMLAN, lka_active, lka_critical, steer_alert)) self.lka_icon_status_last = lka_icon_status diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index ac866ba22..2eb3ff7cd 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -44,9 +44,9 @@ class CarState(CarStateBase): # 1 - open, 0 - closed ret.doorOpen = (pt_cp.vl["BCMDoorBeltStatus"]['FrontLeftDoor'] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]['FrontRightDoor'] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]['RearLeftDoor'] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]['RearRightDoor'] == 1) + pt_cp.vl["BCMDoorBeltStatus"]['FrontRightDoor'] == 1 or + pt_cp.vl["BCMDoorBeltStatus"]['RearLeftDoor'] == 1 or + pt_cp.vl["BCMDoorBeltStatus"]['RearRightDoor'] == 1) # 1 - latched ret.seatbeltUnlatched = pt_cp.vl["BCMDoorBeltStatus"]['LeftSeatBelt'] == 0 diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py index ba13df921..67acb7c48 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/selfdrive/car/gm/gmcan.py @@ -121,4 +121,3 @@ def create_lka_icon_command(bus, active, critical, steer): else: dat = b"\x00\x00\x00" return make_can_msg(0x104c006c, dat, bus) - diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 55dffce20..18baf8886 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -71,15 +71,15 @@ class CarInterface(CarInterfaceBase): ret.minEnableSpeed = -1. # engage speed is decided by pcm ret.mass = 4353. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.86 - ret.steerRatio = 14.4 #end to end is 13.46 + ret.steerRatio = 14.4 # end to end is 13.46 ret.steerRatioRear = 0. ret.centerToFront = ret.wheelbase * 0.4 elif candidate == CAR.BUICK_REGAL: ret.minEnableSpeed = 18 * CV.MPH_TO_MS ret.mass = 3779. * CV.LB_TO_KG + STD_CARGO_KG # (3849+3708)/2 - ret.wheelbase = 2.83 #111.4 inches in meters - ret.steerRatio = 14.4 # guess for tourx + ret.wheelbase = 2.83 # 111.4 inches in meters + ret.steerRatio = 14.4 # guess for tourx ret.steerRatioRear = 0. ret.centerToFront = ret.wheelbase * 0.4 # guess for tourx diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py index 8a2f9a2e6..b63acaddc 100755 --- a/selfdrive/car/gm/radar_interface.py +++ b/selfdrive/car/gm/radar_interface.py @@ -103,7 +103,7 @@ class RadarInterface(RadarInterfaceBase): self.pts[targetId].yvRel = float('nan') for oldTarget in list(self.pts.keys()): - if not oldTarget in currentTargets: + if oldTarget not in currentTargets: del self.pts[oldTarget] ret.points = list(self.pts.values()) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 91124564e..71c0299dd 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -20,7 +20,7 @@ def calc_cruise_offset(offset, speed): def get_can_signals(CP): -# this function generates lists for signal, messages and initial values + # this function generates lists for signal, messages and initial values signals = [ ("XMISSION_SPEED", "ENGINE_DATA", 0), ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), @@ -345,5 +345,5 @@ class CarState(CarStateBase): if CP.carFingerprint in [CAR.CRV, CAR.CRV_EU, CAR.ACURA_RDX, CAR.ODYSSEY_CHN]: checks = [(0x194, 100)] - bus_cam = 1 if CP.carFingerprint in HONDA_BOSCH and not CP.isPandaBlack else 2 + bus_cam = 1 if CP.carFingerprint in HONDA_BOSCH and not CP.isPandaBlack else 2 return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, bus_cam) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 59fef40d2..e31a0bcea 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -13,7 +13,7 @@ def process_hud_alert(enabled, fingerprint, visual_alert, left_lane, # initialize to no line visible sys_state = 1 - if left_lane and right_lane or sys_warning: #HUD alert only display when LKAS status is active + if left_lane and right_lane or sys_warning: # HUD alert only display when LKAS status is active if enabled or sys_warning: sys_state = 3 else: diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index d6f7d30ec..c108bd583 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -113,7 +113,7 @@ class CarState(CarStateBase): self.lkas11 = cp_cam.vl["LKAS11"] self.clu11 = cp.vl["CLU11"] self.park_brake = cp.vl["CGW1"]['CF_Gway_ParkBrakeSw'] - self.steer_state = cp.vl["MDPS12"]['CF_Mdps_ToiActive'] #0 NOT ACTIVE, 1 ACTIVE + self.steer_state = cp.vl["MDPS12"]['CF_Mdps_ToiActive'] # 0 NOT ACTIVE, 1 ACTIVE self.lead_distance = cp.vl["SCC11"]['ACC_ObjDist'] return ret @@ -163,7 +163,7 @@ class CarState(CarStateBase): ("ESC_Off_Step", "TCS15", 0), - ("CF_Lvr_GearInf", "LVR11", 0), #Transmission Gear (0 = N or P, 1-8 = Fwd, 14 = Rev) + ("CF_Lvr_GearInf", "LVR11", 0), # Transmission Gear (0 = N or P, 1-8 = Fwd, 14 = Rev) ("CR_Mdps_StrColTq", "MDPS12", 0), ("CF_Mdps_ToiActive", "MDPS12", 0), diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 598a52e5e..5b28d573b 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -113,7 +113,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1275. + STD_CARGO_KG ret.wheelbase = 2.7 - ret.steerRatio = 13.73 #Spec + ret.steerRatio = 13.73 # Spec tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] @@ -121,7 +121,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1685. + STD_CARGO_KG ret.wheelbase = 2.7 - ret.steerRatio = 13.73 #Spec + ret.steerRatio = 13.73 # Spec tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] diff --git a/selfdrive/car/mazda/__init__.py b/selfdrive/car/mazda/__init__.py index 8b1378917..e69de29bb 100644 --- a/selfdrive/car/mazda/__init__.py +++ b/selfdrive/car/mazda/__init__.py @@ -1 +0,0 @@ - diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py index 5714bdaf0..ecac93690 100644 --- a/selfdrive/car/mazda/carcontroller.py +++ b/selfdrive/car/mazda/carcontroller.py @@ -38,7 +38,7 @@ class CarController(): self.apply_steer_last = apply_steer - + can_sends.append(mazdacan.create_steering_control(self.packer, CS.CP.carFingerprint, frame, apply_steer, CS.cam_lkas)) return can_sends diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index a089ea13e..86d1643c4 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -38,7 +38,7 @@ class CarState(CarStateBase): ret.leftBlinker = cp.vl["BLINK_INFO"]['LEFT_BLINK'] == 1 ret.rightBlinker = cp.vl["BLINK_INFO"]['RIGHT_BLINK'] == 1 - ret.steeringAngle = cp.vl["STEER"]['STEER_ANGLE'] + ret.steeringAngle = cp.vl["STEER"]['STEER_ANGLE'] ret.steeringTorque = cp.vl["STEER_TORQUE"]['STEER_TORQUE_SENSOR'] ret.steeringPressed = abs(ret.steeringTorque) > LKAS_LIMITS.STEER_THRESHOLD @@ -70,7 +70,7 @@ class CarState(CarStateBase): self.cruise_speed = ret.vEgoRaw ret.cruiseState.available = True - ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]['CRZ_ACTIVE'] == 1 + ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]['CRZ_ACTIVE'] == 1 ret.cruiseState.speed = self.cruise_speed if ret.cruiseState.enabled: @@ -182,4 +182,3 @@ class CarState(CarStateBase): ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) - diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 1e6b05ba0..160f531f2 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -34,7 +34,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.70 # not optimized yet if candidate in [CAR.CX5]: - ret.mass = 3655 * CV.LB_TO_KG + STD_CARGO_KG + ret.mass = 3655 * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.7 ret.steerRatio = 15.5 diff --git a/selfdrive/car/mazda/mazdacan.py b/selfdrive/car/mazda/mazdacan.py index 3fae424fa..5728bfed9 100644 --- a/selfdrive/car/mazda/mazdacan.py +++ b/selfdrive/car/mazda/mazdacan.py @@ -17,10 +17,10 @@ def create_steering_control(packer, car_fingerprint, frame, apply_steer, lkas): b2 = int(lkas["ANGLE_ENABLED"]) tmp = steering_angle + 2048 - ahi = tmp >> 10 - amd = (tmp & 0x3FF) >> 2 - amd = (amd >> 4) | (( amd & 0xF) << 4) - alo = (tmp & 0x3) << 2 + ahi = tmp >> 10 + amd = (tmp & 0x3FF) >> 2 + amd = (amd >> 4) | (( amd & 0xF) << 4) + alo = (tmp & 0x3) << 2 ctr = frame % 16 # bytes: [ 1 ] [ 2 ] [ 3 ] [ 4 ] diff --git a/selfdrive/car/mazda/radar_interface.py b/selfdrive/car/mazda/radar_interface.py index 55f92f632..b2f765113 100755 --- a/selfdrive/car/mazda/radar_interface.py +++ b/selfdrive/car/mazda/radar_interface.py @@ -3,4 +3,3 @@ from selfdrive.car.interfaces import RadarInterfaceBase class RadarInterface(RadarInterfaceBase): pass - diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 2cab11d1f..491fa72c8 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -19,8 +19,8 @@ class CAR: class LKAS_LIMITS: STEER_THRESHOLD = 15 - DISABLE_SPEED = 45 #kph - ENABLE_SPEED = 52 #kph + DISABLE_SPEED = 45 # kph + ENABLE_SPEED = 52 # kph class Buttons: NONE = 0 diff --git a/selfdrive/car/subaru/__init__.py b/selfdrive/car/subaru/__init__.py index 8b1378917..e69de29bb 100644 --- a/selfdrive/car/subaru/__init__.py +++ b/selfdrive/car/subaru/__init__.py @@ -1 +0,0 @@ - diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 0346801c0..9b68c1940 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -42,8 +42,10 @@ class CarController(): self.steer_rate_limited = False self.fake_ecus = set() - if CP.enableCamera: self.fake_ecus.add(Ecu.fwdCamera) - if CP.enableDsu: self.fake_ecus.add(Ecu.dsu) + if CP.enableCamera: + self.fake_ecus.add(Ecu.fwdCamera) + if CP.enableDsu: + self.fake_ecus.add(Ecu.dsu) self.packer = CANPacker(dbc_name) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 78c428557..89149b6ae 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -127,7 +127,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.82448 ret.steerRatio = 13.7 tire_stiffness_factor = 0.7933 - ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG #mean between normal and hybrid + ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] ret.lateralTuning.pid.kf = 0.00006 @@ -147,7 +147,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.78 ret.steerRatio = 16.0 tire_stiffness_factor = 0.8 - ret.mass = 4607. * CV.LB_TO_KG + STD_CARGO_KG #mean between normal and hybrid limited + ret.mass = 4607. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid limited ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.18], [0.015]] # community tuning ret.lateralTuning.pid.kf = 0.00012 # community tuning @@ -155,7 +155,7 @@ class CarInterface(CarInterfaceBase): stop_and_go = False ret.safetyParam = 73 ret.wheelbase = 2.82 - ret.steerRatio = 14.8 #Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download + ret.steerRatio = 14.8 # Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download tire_stiffness_factor = 0.7983 ret.mass = 3505. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.17], [0.03]] diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py index 12387d489..b831b005d 100755 --- a/selfdrive/car/toyota/radar_interface.py +++ b/selfdrive/car/toyota/radar_interface.py @@ -62,7 +62,7 @@ class RadarInterface(RadarInterfaceBase): if self.trigger_msg not in self.updated_messages: return None - rr = self._update(self.updated_messages) + rr = self._update(self.updated_messages) self.updated_messages.clear() return rr diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 24305382b..bd499c762 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -803,7 +803,7 @@ FW_VERSIONS = { b'\x01896630852100\x00\x00\x00\x00', b'\x01896630859000\x00\x00\x00\x00', ], - (Ecu.eps, 0x7a1, None): [ + (Ecu.eps, 0x7a1, None): [ b'8965B45070\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ @@ -844,24 +844,24 @@ FW_VERSIONS = { }, CAR.LEXUS_RX: { (Ecu.engine, 0x700, None): [ - b'\x01896630E41200\x00\x00\x00\x00', - ], + b'\x01896630E41200\x00\x00\x00\x00', + ], (Ecu.esp, 0x7b0, None): [ - b'F152648473\x00\x00\x00\x00\x00\x00', - ], + b'F152648473\x00\x00\x00\x00\x00\x00', + ], (Ecu.dsu, 0x791, None): [ - b'881514810500\x00\x00\x00\x00', - ], + b'881514810500\x00\x00\x00\x00', + ], (Ecu.eps, 0x7a1, None): [ - b'8965B0E012\x00\x00\x00\x00\x00\x00', - ], + b'8965B0E012\x00\x00\x00\x00\x00\x00', + ], (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701100\x00\x00\x00\x00', - ], + b'8821F4701100\x00\x00\x00\x00', + ], (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4802001\x00\x00\x00\x00', - b'8646F4802100\x00\x00\x00\x00', - ], + b'8646F4802001\x00\x00\x00\x00', + b'8646F4802100\x00\x00\x00\x00', + ], }, CAR.LEXUS_RXH: { (Ecu.engine, 0x7e0, None): [ diff --git a/selfdrive/car/volkswagen/__init__.py b/selfdrive/car/volkswagen/__init__.py index 8b1378917..e69de29bb 100644 --- a/selfdrive/car/volkswagen/__init__.py +++ b/selfdrive/car/volkswagen/__init__.py @@ -1 +0,0 @@ - diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index 6c90d69e7..a157805c1 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -67,7 +67,7 @@ class CarController(): self.hcaEnabledFrameCount = 0 else: self.hcaEnabledFrameCount += 1 - if self.hcaEnabledFrameCount >= 118 * (100 / P.HCA_STEP): # 118s + if self.hcaEnabledFrameCount >= 118 * (100 / P.HCA_STEP): # 118s # The Kansas I-70 Crosswind Problem: if we truly do need to steer # in one direction for > 360 seconds, we have to disable HCA for a # frame while actively steering. Testing shows we can just set the diff --git a/selfdrive/config.py b/selfdrive/config.py index 6c2296273..0e18c31f4 100644 --- a/selfdrive/config.py +++ b/selfdrive/config.py @@ -27,4 +27,3 @@ class UIParams: car_front = 2.6924 * lidar_zoom car_back = 1.8796 * lidar_zoom car_color = 110 - diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index e3e502c1a..55cfe1bf1 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -223,7 +223,7 @@ class Controls: # Only allow engagement with brake pressed when stopped behind another stopped car if CS.brakePressed and self.sm['plan'].vTargetFuture >= STARTING_TARGET_SPEED \ - and not self.CP.radarOffCan and CS.vEgo < 0.3: + and not self.CP.radarOffCan and CS.vEgo < 0.3: self.events.add(EventName.noTarget) @@ -372,7 +372,7 @@ class Controls: # Send a "steering required alert" if saturation count has reached the limit if (lac_log.saturated and not CS.steeringPressed) or \ - (self.saturated_count > STEER_ANGLE_SATURATION_TIMEOUT): + (self.saturated_count > STEER_ANGLE_SATURATION_TIMEOUT): # Check if we deviated from the path left_deviation = actuators.steer > 0 and path_plan.dPoly[3] > 0.1 right_deviation = actuators.steer < 0 and path_plan.dPoly[3] < -0.1 diff --git a/selfdrive/controls/lib/driverview.py b/selfdrive/controls/lib/driverview.py index 298858bd4..ad49fb77e 100755 --- a/selfdrive/controls/lib/driverview.py +++ b/selfdrive/controls/lib/driverview.py @@ -71,4 +71,4 @@ def main(): is_rhd_checked = True if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/selfdrive/controls/lib/latcontrol_indi.py b/selfdrive/controls/lib/latcontrol_indi.py index 91a5e2d6a..2b41dc6f7 100644 --- a/selfdrive/controls/lib/latcontrol_indi.py +++ b/selfdrive/controls/lib/latcontrol_indi.py @@ -116,7 +116,7 @@ class LatControlINDI(): indi_log.delta = float(delta_u) indi_log.output = float(self.output_steer) - check_saturation = (CS.vEgo> 10.) and not CS.steeringRateLimited and not CS.steeringPressed + check_saturation = (CS.vEgo> 10.) and not CS.steeringRateLimited and not CS.steeringPressed indi_log.saturated = self._check_saturation(self.output_steer, check_saturation, steers_max) return float(self.output_steer), float(self.angle_steers_des), indi_log diff --git a/selfdrive/controls/lib/latcontrol_lqr.py b/selfdrive/controls/lib/latcontrol_lqr.py index a12aee2e9..b27f8c3e3 100644 --- a/selfdrive/controls/lib/latcontrol_lqr.py +++ b/selfdrive/controls/lib/latcontrol_lqr.py @@ -79,8 +79,8 @@ class LatControlLQR(): i = self.i_lqr + self.ki * self.i_rate * error control = lqr_output + i - if ((error >= 0 and (control <= steers_max or i < 0.0)) or \ - (error <= 0 and (control >= -steers_max or i > 0.0))): + if (error >= 0 and (control <= steers_max or i < 0.0)) or \ + (error <= 0 and (control >= -steers_max or i > 0.0)): self.i_lqr = i self.output_steer = lqr_output + self.i_lqr diff --git a/selfdrive/controls/lib/vehicle_model.py b/selfdrive/controls/lib/vehicle_model.py index 6ac5f856f..9959f82dc 100755 --- a/selfdrive/controls/lib/vehicle_model.py +++ b/selfdrive/controls/lib/vehicle_model.py @@ -194,4 +194,3 @@ class VehicleModel(): Yaw rate [rad/s] """ return self.calc_curvature(sa, u) * u - diff --git a/selfdrive/controls/tests/test_events.py b/selfdrive/controls/tests/test_events.py index 79662b719..2951dcebb 100755 --- a/selfdrive/controls/tests/test_events.py +++ b/selfdrive/controls/tests/test_events.py @@ -52,7 +52,8 @@ class TestAlerts(unittest.TestCase): continue for i, txt in enumerate([alert.alert_text_1, alert.alert_text_2]): - if i >= len(fonts[alert.alert_size]): break + if i >= len(fonts[alert.alert_size]): + break font = fonts[alert.alert_size][i] w, h = draw.textsize(txt, font) diff --git a/selfdrive/controls/tests/test_monitoring.py b/selfdrive/controls/tests/test_monitoring.py index 67e97040c..93a3b553c 100644 --- a/selfdrive/controls/tests/test_monitoring.py +++ b/selfdrive/controls/tests/test_monitoring.py @@ -65,7 +65,7 @@ def run_DState_seq(driver_state_msgs, driver_car_interaction, openpilot_status, for idx in range(len(driver_state_msgs)): e = Events() DS.get_pose(driver_state_msgs[idx], [0,0,0], 0, openpilot_status[idx]) - # cal_rpy and car_speed don't matter here + # cal_rpy and car_speed don't matter here # evaluate events at 10Hz for tests DS.update(e, driver_car_interaction[idx], openpilot_status[idx], car_standstill_status[idx]) diff --git a/selfdrive/crash.py b/selfdrive/crash.py index 000109dc9..a24466622 100644 --- a/selfdrive/crash.py +++ b/selfdrive/crash.py @@ -11,10 +11,13 @@ from common.android import ANDROID if os.getenv("NOLOG") or os.getenv("NOCRASH") or not ANDROID: def capture_exception(*args, **kwargs): pass + def bind_user(**kwargs): pass + def bind_extra(**kwargs): pass + def install(): pass else: @@ -38,6 +41,7 @@ else: def install(): # installs a sys.excepthook __excepthook__ = sys.excepthook + def handle_exception(*exc_info): if exc_info[0] not in (KeyboardInterrupt, SystemExit): capture_exception() diff --git a/selfdrive/launcher.py b/selfdrive/launcher.py index 8253347d6..dcedf0716 100644 --- a/selfdrive/launcher.py +++ b/selfdrive/launcher.py @@ -1,5 +1,5 @@ import importlib -from setproctitle import setproctitle #pylint: disable=no-name-in-module +from setproctitle import setproctitle # pylint: disable=no-name-in-module import cereal.messaging as messaging import selfdrive.crash as crash diff --git a/selfdrive/locationd/calibration_helpers.py b/selfdrive/locationd/calibration_helpers.py index f29090075..cdc0345f3 100644 --- a/selfdrive/locationd/calibration_helpers.py +++ b/selfdrive/locationd/calibration_helpers.py @@ -8,4 +8,3 @@ class Calibration: UNCALIBRATED = 0 CALIBRATED = 1 INVALID = 2 - diff --git a/selfdrive/locationd/test/ephemeris.py b/selfdrive/locationd/test/ephemeris.py index dd8155e19..bca45c59e 100644 --- a/selfdrive/locationd/test/ephemeris.py +++ b/selfdrive/locationd/test/ephemeris.py @@ -133,5 +133,3 @@ on of this parser self.ionoAlpha = [] self.ionoBeta = [] self.ionoCoeffsValid = False - - diff --git a/selfdrive/locationd/test/ublox.py b/selfdrive/locationd/test/ublox.py index d99e71469..b699a3721 100644 --- a/selfdrive/locationd/test/ublox.py +++ b/selfdrive/locationd/test/ublox.py @@ -12,7 +12,8 @@ for ublox version 8, not all functions may work. import struct -import time, os +import os +import time # protocol constants PREAMBLE1 = 0xb5 @@ -291,7 +292,7 @@ class UBloxDescriptor: fields = self.fields[:] for f in fields: (fieldname, alen) = ArrayParse(f) - if not fieldname in msg._fields: + if fieldname not in msg._fields: break if alen == -1: f1.append(msg._fields[fieldname]) @@ -327,7 +328,7 @@ class UBloxDescriptor: ret = self.name + ': ' for f in self.fields: (fieldname, alen) = ArrayParse(f) - if not fieldname in msg._fields: + if fieldname not in msg._fields: continue v = msg._fields[fieldname] if isinstance(v, list): @@ -591,7 +592,7 @@ class UBloxMessage: if not self.valid(): raise UBloxError('INVALID MESSAGE') type = self.msg_type() - if not type in msg_types: + if type not in msg_types: raise UBloxError('Unknown message %s length=%u' % (str(type), len(self._buf))) msg_types[type].unpack(self) return self._fields, self._recs @@ -601,7 +602,7 @@ class UBloxMessage: if not self.valid(): raise UBloxError('INVALID MESSAGE') type = self.msg_type() - if not type in msg_types: + if type not in msg_types: raise UBloxError('Unknown message %s' % str(type)) msg_types[type].pack(self) @@ -610,7 +611,7 @@ class UBloxMessage: if not self.valid(): raise UBloxError('INVALID MESSAGE') type = self.msg_type() - if not type in msg_types: + if type not in msg_types: raise UBloxError('Unknown message %s length=%u' % (str(type), len(self._buf))) return msg_types[type].name diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index 5dbe8cff4..6ba4c38a9 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -83,7 +83,7 @@ def configure_ublox(dev): def int_to_bool_list(num): # for parsing bool bytes - return [bool(num & (1<>4) + s += (c >> 4) s += c & 0xF s = 8-s s %= 0x10 @@ -45,7 +45,7 @@ def car_plant(pos, speed, grade, gas, brake): mass = 1700 aero_cd = 0.3 force_peak = mass*3. - force_brake_peak = -mass*10. #1g + force_brake_peak = -mass*10. # 1g power_peak = 100000 # 100kW speed_base = power_peak/force_peak rolling_res = 0.01 @@ -277,13 +277,13 @@ class Plant(): vls = vls_tuple( self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), - self.angle_steer, self.angle_steer_rate, 0, 0,#Steer torque sensor + self.angle_steer, self.angle_steer_rate, 0, 0, # Steer torque sensor 0, 0, # Blinkers self.gear_choice, speed != 0, self.brake_error, self.brake_error, not self.seatbelt, self.seatbelt, # Seatbelt - self.brake_pressed, 0., #Brake pressed, Brake switch + self.brake_pressed, 0., # Brake pressed, Brake switch cruise_buttons, self.esp_disabled, 0, # HUD lead @@ -339,9 +339,9 @@ class Plant(): # TODO: use the DBC if self.frame % 5 == 0: radar_state_msg = b'\x79\x00\x00\x00\x00\x00\x00\x00' - radar_msg = to_3_byte(d_rel*16.0) + \ - to_3_byte(int(lateral_pos_rel*16.0)&0x3ff) + \ - to_3s_byte(int(v_rel*32.0)) + \ + radar_msg = to_3_byte(d_rel * 16.0) + \ + to_3_byte(int(lateral_pos_rel * 16.0) & 0x3ff) + \ + to_3s_byte(int(v_rel * 32.0)) + \ b"0f00000" radar_msg = binascii.unhexlify(radar_msg) diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py index addcfa931..985e59f87 100755 --- a/selfdrive/test/process_replay/compare_logs.py +++ b/selfdrive/test/process_replay/compare_logs.py @@ -6,7 +6,8 @@ import numbers import dictdiffer if "CI" in os.environ: - tqdm = lambda x: x + def tqdm(x): + return x else: from tqdm import tqdm # type: ignore @@ -32,7 +33,7 @@ def remove_ignored_fields(msg, ignore): for k in keys[:-1]: try: attr = getattr(msg, k) - except: + except AttributeError: break else: v = getattr(attr, keys[-1]) @@ -46,8 +47,7 @@ def remove_ignored_fields(msg, ignore): return msg.as_reader() def compare_logs(log1, log2, ignore_fields=[], ignore_msgs=[]): - filter_msgs = lambda m: m.which() not in ignore_msgs - log1, log2 = [list(filter(filter_msgs, log)) for log in (log1, log2)] + log1, log2 = [list(filter(lambda m: m.which() not in ignore_msgs, log)) for log in (log1, log2)] assert len(log1) == len(log2), "logs are not same length: " + str(len(log1)) + " VS " + str(len(log2)) diff = [] diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 46eb5a09e..d6fe5ef6f 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -1,11 +1,13 @@ #!/usr/bin/env python3 +import capnp import os import sys import threading import importlib if "CI" in os.environ: - tqdm = lambda x: x + def tqdm(x): + return x else: from tqdm import tqdm # type: ignore @@ -110,7 +112,7 @@ class FakePubMaster(messaging.PubMaster): for s in services: try: data = messaging.new_message(s) - except: + except capnp.lib.capnp.KjException: data = messaging.new_message(s, 0) self.data[s] = data.as_reader() self.sock[s] = DumbSocket() diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index f9deac671..6e4e11119 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -124,7 +124,7 @@ if __name__ == "__main__": process_replay_dir = os.path.dirname(os.path.abspath(__file__)) try: ref_commit = open(os.path.join(process_replay_dir, "ref_commit")).read().strip() - except: + except FileNotFoundError: print("couldn't find reference commit") sys.exit(1) @@ -139,7 +139,7 @@ if __name__ == "__main__": results: Any = {} for car_brand, segment in segments: if (cars_whitelisted and car_brand.upper() not in args.whitelist_cars) or \ - (not cars_whitelisted and car_brand.upper() in args.blacklist_cars): + (not cars_whitelisted and car_brand.upper() in args.blacklist_cars): continue print("***** testing route segment %s *****\n" % segment) @@ -151,7 +151,7 @@ if __name__ == "__main__": for cfg in CONFIGS: if (procs_whitelisted and cfg.proc_name not in args.whitelist_procs) or \ - (not procs_whitelisted and cfg.proc_name in args.blacklist_procs): + (not procs_whitelisted and cfg.proc_name in args.blacklist_procs): continue cmp_log_fn = os.path.join(process_replay_dir, "%s_%s_%s.bz2" % (segment, cfg.proc_name, ref_commit)) diff --git a/selfdrive/test/test_car_models.py b/selfdrive/test/test_car_models.py index 06d333094..868115fb7 100755 --- a/selfdrive/test/test_car_models.py +++ b/selfdrive/test/test_car_models.py @@ -261,7 +261,7 @@ routes = { 'enableCamera': True, 'enableDsu': False, }, - "7e34a988419b5307|2019-12-18--19-13-30": { + "7e34a988419b5307|2019-12-18--19-13-30": { 'carFingerprint': TOYOTA.RAV4H_TSS2, 'enableCamera': True, 'fingerprintSource': 'fixed' @@ -286,12 +286,12 @@ routes = { 'enableCamera': True, 'enableDsu': False, }, - "886fcd8408d570e9|2020-01-29--05-11-22": { + "886fcd8408d570e9|2020-01-29--05-11-22": { 'carFingerprint': TOYOTA.LEXUS_RX, 'enableCamera': True, 'enableDsu': True, }, - "886fcd8408d570e9|2020-01-29--02-18-55": { + "886fcd8408d570e9|2020-01-29--02-18-55": { 'carFingerprint': TOYOTA.LEXUS_RX, 'enableCamera': True, 'enableDsu': False, @@ -301,12 +301,12 @@ routes = { 'enableCamera': True, 'enableDsu': True, }, - "01b22eb2ed121565|2020-02-02--11-25-51": { + "01b22eb2ed121565|2020-02-02--11-25-51": { 'carFingerprint': TOYOTA.LEXUS_RX_TSS2, 'enableCamera': True, 'fingerprintSource': 'fixed', }, - "b74758c690a49668|2020-05-20--15-58-57": { + "b74758c690a49668|2020-05-20--15-58-57": { 'carFingerprint': TOYOTA.LEXUS_RXH_TSS2, 'enableCamera': True, 'fingerprintSource': 'fixed', diff --git a/selfdrive/test/test_leeco_alt_fan.py b/selfdrive/test/test_leeco_alt_fan.py index c14d943e2..b1ab5c54d 100755 --- a/selfdrive/test/test_leeco_alt_fan.py +++ b/selfdrive/test/test_leeco_alt_fan.py @@ -14,7 +14,7 @@ def setup_leon_fan(): bus.write_i2c_block_data(0x67, 0xa, [0]) else: bus.write_i2c_block_data(0x67, 0xa, [0x20]) - bus.write_i2c_block_data(0x67, 0x8, [(i-1)<<6]) + bus.write_i2c_block_data(0x67, 0x8, [(i - 1) << 6]) time.sleep(1) bus.close() diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 1d69547cd..5d97141cb 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -100,7 +100,7 @@ def set_eon_fan(val): else: #bus.write_i2c_block_data(0x67, 0x45, [0]) bus.write_i2c_block_data(0x67, 0xa, [0x20]) - bus.write_i2c_block_data(0x67, 0x8, [(val-1)<<6]) + bus.write_i2c_block_data(0x67, 0x8, [(val - 1) << 6]) else: bus.write_byte_data(0x21, 0x04, 0x2) bus.write_byte_data(0x21, 0x03, (val*2)+1) diff --git a/tools/carcontrols/joystick_test.py b/tools/carcontrols/joystick_test.py index 1a41d4729..2f008af14 100755 --- a/tools/carcontrols/joystick_test.py +++ b/tools/carcontrols/joystick_test.py @@ -51,7 +51,7 @@ pygame.joystick.init() textPrint = TextPrint() # -------- Main Program Loop ----------- -while done==False: +while not done: # EVENT PROCESSING STEP for event in pygame.event.get(): # User did something if event.type == pygame.QUIT: # If user clicked close @@ -122,4 +122,4 @@ while done==False: # Close the window and quit. # If you forget this line, the program will 'hang' # on exit if running from IDLE. -pygame.quit () +pygame.quit() diff --git a/tools/lib/route.py b/tools/lib/route.py index 2a5ab5e4a..306074154 100644 --- a/tools/lib/route.py +++ b/tools/lib/route.py @@ -111,10 +111,12 @@ class RouteSegment(object): self.camera_path = camera_path @property - def name(self): return str(self._name) + def name(self): + return str(self._name) @property - def canonical_name(self): return self._name + def canonical_name(self): + return self._name class RouteSegmentName(object): def __init__(self, name_str): @@ -123,6 +125,8 @@ class RouteSegmentName(object): self._num = int(num_str) @property - def segment_num(self): return self._num + def segment_num(self): + return self._num - def __str__(self): return self._segment_name_str + def __str__(self): + return self._segment_name_str diff --git a/tools/lib/route_framereader.py b/tools/lib/route_framereader.py index 47250383c..2045a4b4c 100644 --- a/tools/lib/route_framereader.py +++ b/tools/lib/route_framereader.py @@ -82,5 +82,8 @@ class RouteFrameReader(object): for fr in frs: fr.close() - def __enter__(self): return self - def __exit__(self, type, value, traceback): self.close() + def __enter__(self): + return self + + def __exit__(self, type, value, traceback): + self.close() diff --git a/tools/replay/lib/ui_helpers.py b/tools/replay/lib/ui_helpers.py index 78cbefddf..44fdb2c0f 100644 --- a/tools/replay/lib/ui_helpers.py +++ b/tools/replay/lib/ui_helpers.py @@ -73,7 +73,7 @@ def draw_path(y, x, color, img, calibration, top_down, lid_color=None): uv_model > 0, axis=1), uv_model[:, 0] < img.shape[1] - 1, uv_model[:, 1] < img.shape[0] - 1))] - for i, j in ((-1, 0), (0, -1), (0, 0), (0, 1), (1, 0)): + for i, j in ((-1, 0), (0, -1), (0, 0), (0, 1), (1, 0)): img[uv_model_dots[:, 1] + i, uv_model_dots[:, 0] + j] = color # draw lidar path point on lidar @@ -88,12 +88,12 @@ def draw_path(y, x, color, img, calibration, top_down, lid_color=None): def draw_steer_path(speed_ms, curvature, color, img, calibration, top_down, VM, lid_color=None): path_x = np.arange(101.) - path_y = np.multiply(path_x, np.tan(np.arcsin(np.clip(path_x * curvature, -0.999, 0.999)) / 2.)) + path_y = np.multiply(path_x, np.tan(np.arcsin(np.clip(path_x * curvature, -0.999, 0.999)) / 2.)) draw_path(path_y, path_x, color, img, calibration, top_down, lid_color) def draw_lead_car(closest, top_down): - if closest != None: + if closest is not None: closest_y = int(round(UP.lidar_car_y - closest * UP.lidar_zoom)) if closest_y > 0: top_down[1][int(round(UP.lidar_car_x - METER_WIDTH * 2)):int( @@ -118,12 +118,10 @@ def init_plots(arr, name_to_arr_idx, plot_xlims, plot_ylims, plot_names, plot_co "p": (0,1,1), "m": (1,0,1) } - if bigplots == True: + if bigplots: fig = plt.figure(figsize=(6.4, 7.0)) - elif bigplots == False: - fig = plt.figure() else: - fig = plt.figure(figsize=bigplots) + fig = plt.figure() fig.set_facecolor((0.2,0.2,0.2)) @@ -135,7 +133,7 @@ def init_plots(arr, name_to_arr_idx, plot_xlims, plot_ylims, plot_names, plot_co ax.patch.set_facecolor((0.4, 0.4, 0.4)) axs.append(ax) - plots = [] ;idxs = [] ;plot_select = [] + plots, idxs, plot_select = [], [], [] for i, pl_list in enumerate(plot_names): for j, item in enumerate(pl_list): plot, = axs[i].plot(arr[:, name_to_arr_idx[item]], diff --git a/tools/replay/unlogger.py b/tools/replay/unlogger.py index 3463660e8..4b71d2a14 100755 --- a/tools/replay/unlogger.py +++ b/tools/replay/unlogger.py @@ -341,15 +341,19 @@ def get_arg_parser(): parser.add_argument("route_name", type=(lambda x: x.replace("#", "|")), nargs="?", help="The route whose messages will be published.") parser.add_argument("data_dir", nargs='?', default=os.getenv('UNLOGGER_DATA_DIR'), - help="Path to directory in which log and camera files are located.") + help="Path to directory in which log and camera files are located.") parser.add_argument("--no-loop", action="store_true", help="Stop at the end of the replay.") - key_value_pair = lambda x: x.split("=") + def key_value_pair(x): + return x.split("=") + parser.add_argument("address_mapping", nargs="*", type=key_value_pair, help="Pairs = to publish on .") - comma_list = lambda x: x.split(",") + def comma_list(x): + return x.split(",") + to_mock_group = parser.add_mutually_exclusive_group() to_mock_group.add_argument("--min", action="store_true", default=os.getenv("MIN")) to_mock_group.add_argument("--enabled", default=os.getenv("ENABLED"), type=comma_list) diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index b0ea6fa7c..3c402c415 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -200,7 +200,7 @@ def go(q): speed = math.sqrt(vel.x**2 + vel.y**2 + vel.z**2) * 3.6 can_function(pm, speed, fake_wheel.angle, rk.frame, cruise_button=cruise_button, is_engaged=is_openpilot_engaged) - if rk.frame%1 == 0: # 20Hz? + if rk.frame % 1 == 0: # 20Hz? throttle_op, brake_op, steer_torque_op = sendcan_function(sendcan) # print(" === torq, ",steer_torque_op, " ===") if is_openpilot_engaged: diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index 9fbb2006f..5e206e337 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -28,8 +28,8 @@ def can_function(pm, speed, angle, idx, cruise_button=0, is_engaged=False): msg.append(packer.make_can_msg("SCM_BUTTONS", 0, {"CRUISE_BUTTONS": cruise_button}, idx)) - values = {"COUNTER_PEDAL": idx&0xF} - checksum = crc8_pedal(packer.make_can_msg("GAS_SENSOR", 0, {"COUNTER_PEDAL": idx&0xF}, -1)[2][:-1]) + values = {"COUNTER_PEDAL": idx & 0xF} + checksum = crc8_pedal(packer.make_can_msg("GAS_SENSOR", 0, {"COUNTER_PEDAL": idx & 0xF}, -1)[2][:-1]) values["CHECKSUM_PEDAL"] = checksum msg.append(packer.make_can_msg("GAS_SENSOR", 0, values, -1)) @@ -56,7 +56,7 @@ def can_function(pm, speed, angle, idx, cruise_button=0, is_engaged=False): msg.append(packer.make_can_msg("BRAKE_COMMAND", 2, {}, idx)) # radar - if idx%5 == 0: + if idx % 5 == 0: msg.append(rpacker.make_can_msg("RADAR_DIAGNOSTIC", 1, {"RADAR_STATE": 0x79}, -1)) for i in range(16): msg.append(rpacker.make_can_msg("TRACK_%d" % i, 1, {"LONG_DIST": 255.5}, -1)) diff --git a/tools/sim/lib/manual_ctrl.py b/tools/sim/lib/manual_ctrl.py index 6e7fe6e6a..6d66097df 100755 --- a/tools/sim/lib/manual_ctrl.py +++ b/tools/sim/lib/manual_ctrl.py @@ -1,6 +1,8 @@ #!/usr/bin/env python3 # set up wheel -import os, struct, array +import array +import os +import struct from fcntl import ioctl # Iterate over the joystick devices. diff --git a/tools/webcam/accept_terms.py b/tools/webcam/accept_terms.py index e7757511d..a5445a571 100755 --- a/tools/webcam/accept_terms.py +++ b/tools/webcam/accept_terms.py @@ -6,4 +6,4 @@ if __name__ == '__main__': params = Params() params.put("HasAcceptedTerms", str(terms_version, 'utf-8')) params.put("CompletedTrainingVersion", str(training_version, 'utf-8')) - print("Terms Accepted!") \ No newline at end of file + print("Terms Accepted!")