diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 27a258b0a..7b77f3f5b 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,7 +17,7 @@ repos: - id: flake8 exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(laika_repo)|(rednose_repo)/' args: - - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E251,E265,E266,E302,E303,E305,E402,E501,E502,E722,E741,W504 + - --ignore=E111,E114,E121,E122,E123,E124,E126,E127,E128,E201,E202,E203,E226,E241,E251,E265,E266,E302,E305,E402,E501,E502,E722,E741,W504 - --statistics - repo: local hooks: diff --git a/cereal b/cereal index 76eb23e06..b25a7d6f6 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 76eb23e062679058025369204f4e9a81ea7d479b +Subproject commit b25a7d6f6e4dc923f1ee1fd5ea13d6e12100341e diff --git a/common/kalman/tests/test_simple_kalman.py b/common/kalman/tests/test_simple_kalman.py index c1f9f7b03..9b947a432 100644 --- a/common/kalman/tests/test_simple_kalman.py +++ b/common/kalman/tests/test_simple_kalman.py @@ -50,7 +50,6 @@ class TestSimpleKalman(unittest.TestCase): self.assertAlmostEqual(x_old[0], x[0]) self.assertAlmostEqual(x_old[1], x[1]) - def test_new_is_faster(self): setup = """ import numpy as np diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py index 4f15f9277..a0d179c35 100644 --- a/common/transformations/coordinates.py +++ b/common/transformations/coordinates.py @@ -5,7 +5,6 @@ with each row as a position. """ - a = 6378137 b = 6356752.3142 esq = 6.69437999014 * 0.001 @@ -91,7 +90,6 @@ class LocalCoord(): init_geodetic = ecef2geodetic(init_ecef) return LocalCoord(init_geodetic, init_ecef) - def ecef2ned(self, ecef): ecef = np.array(ecef) return np.dot(self.ecef2ned_matrix, (ecef - self.init_ecef).T).T diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py index 0a28524a6..f594f0567 100644 --- a/common/transformations/orientation.py +++ b/common/transformations/orientation.py @@ -132,10 +132,6 @@ rot_from_euler = euler2rot quat_from_euler = euler2quat - - - - ''' Random helpers below ''' diff --git a/common/transformations/tests/test_coordinates.py b/common/transformations/tests/test_coordinates.py index b0cbcd79d..a7fbfcde3 100755 --- a/common/transformations/tests/test_coordinates.py +++ b/common/transformations/tests/test_coordinates.py @@ -50,7 +50,6 @@ ned_offsets_batch = np.array([[ 53.88103168, 43.83445935, -46.27488057], [ 78.56272609, 18.53100158, -43.25290759]]) - class TestNED(unittest.TestCase): def test_small_distances(self): start_geodetic = np.array([33.8042184, -117.888593, 0.0]) @@ -83,8 +82,6 @@ class TestNED(unittest.TestCase): np.testing.assert_allclose(geodetic_positions_radians[:, :2], coord.ecef2geodetic(ecef_positions, radians=True)[:, :2], rtol=1e-7) np.testing.assert_allclose(geodetic_positions_radians[:, 2], coord.ecef2geodetic(ecef_positions, radians=True)[:, 2], rtol=1e-7, atol=1e-4) - - def test_ned(self): for ecef_pos in ecef_positions: converter = coord.LocalCoord.from_ecef(ecef_pos) @@ -99,7 +96,6 @@ class TestNED(unittest.TestCase): np.testing.assert_allclose(geo_pos_moved[:2], geo_pos_double_converted_moved[:2], rtol=1e-9, atol=1e-6) np.testing.assert_allclose(geo_pos_moved[2], geo_pos_double_converted_moved[2], rtol=1e-9, atol=1e-4) - def test_ned_saved_results(self): for i, ecef_pos in enumerate(ecef_positions): converter = coord.LocalCoord.from_ecef(ecef_pos) diff --git a/common/transformations/tests/test_orientation.py b/common/transformations/tests/test_orientation.py index 1e85c81a0..906389757 100755 --- a/common/transformations/tests/test_orientation.py +++ b/common/transformations/tests/test_orientation.py @@ -64,6 +64,5 @@ class TestOrientation(unittest.TestCase): np.testing.assert_allclose(ned_eulers, ned_euler_from_ecef(ecef_positions, eulers), rtol=1e-7) - if __name__ == "__main__": unittest.main() diff --git a/common/url_file.py b/common/url_file.py index 4ba819204..343e7537b 100644 --- a/common/url_file.py +++ b/common/url_file.py @@ -77,7 +77,6 @@ class URLFile(object): if response_code != 206 and response_code != 200: raise Exception("Error {} ({}): {}".format(response_code, self._url, repr(dats.getvalue())[:500])) - ret = dats.getvalue() self._pos += len(ret) return ret diff --git a/common/window.py b/common/window.py index 6fc36d06b..fada132b8 100644 --- a/common/window.py +++ b/common/window.py @@ -23,7 +23,6 @@ class Window(): pygame.surfarray.blit_array(self.screen, out.swapaxes(0, 1)) pygame.display.flip() - def getkey(self): while 1: event = pygame.event.wait() diff --git a/external/simpleperf/utils.py b/external/simpleperf/utils.py index 453447704..407703984 100644 --- a/external/simpleperf/utils.py +++ b/external/simpleperf/utils.py @@ -220,11 +220,9 @@ class AdbHelper(object): self.adb_path = adb_path self.enable_switch_to_root = enable_switch_to_root - def run(self, adb_args): return self.run_and_return_output(adb_args)[0] - def run_and_return_output(self, adb_args, stdout_file=None, log_output=True): adb_args = [self.adb_path] + adb_args log_debug('run adb cmd: %s' % adb_args) @@ -247,14 +245,12 @@ class AdbHelper(object): def check_run(self, adb_args): self.check_run_and_return_output(adb_args) - def check_run_and_return_output(self, adb_args, stdout_file=None, log_output=True): result, stdoutdata = self.run_and_return_output(adb_args, stdout_file, log_output) if not result: log_exit('run "adb %s" failed' % adb_args) return stdoutdata - def _unroot(self): result, stdoutdata = self.run_and_return_output(['shell', 'whoami']) if not result: @@ -266,7 +262,6 @@ class AdbHelper(object): self.run(['wait-for-device']) time.sleep(1) - def switch_to_root(self): if not self.enable_switch_to_root: self._unroot() @@ -292,7 +287,6 @@ class AdbHelper(object): def set_property(self, name, value): return self.run(['shell', 'setprop', name, value]) - def get_device_arch(self): output = self.check_run_and_return_output(['shell', 'uname', '-m']) if 'aarch64' in output: @@ -305,7 +299,6 @@ class AdbHelper(object): return 'x86' log_fatal('unsupported architecture: %s' % output.strip()) - def get_android_version(self): build_version = self.get_property('ro.build.version.release') android_version = 0 diff --git a/laika_repo b/laika_repo index d0872aa16..4d9df5eb0 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit d0872aa16155e8f73961d52952c8cef41d5702d4 +Subproject commit 4d9df5eb0994523d8061358e0210ca6e6a473e48 diff --git a/panda b/panda index 9102c1611..275e76c2b 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 9102c16118171597abf6cb7b9dee99b557f7eee7 +Subproject commit 275e76c2b2f9206c82990fe7ba0a6a96ecb8a0bc diff --git a/selfdrive/boardd/tests/replay_many.py b/selfdrive/boardd/tests/replay_many.py index 41e86f412..71db229a2 100755 --- a/selfdrive/boardd/tests/replay_many.py +++ b/selfdrive/boardd/tests/replay_many.py @@ -56,7 +56,6 @@ if __name__ == "__main__": serials = Panda.list() num_senders = len(serials) - if num_senders == 0: print("No senders found. Exiting") sys.exit(1) diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index c4db73036..f25cc69f7 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -17,7 +17,6 @@ class CarController(): self.packer = CANPacker(dbc_name) - def update(self, enabled, CS, actuators, pcm_cancel_cmd, hud_alert): # this seems needed to avoid steering faults and to force the sync with the EPS counter frame = CS.lkas_counter diff --git a/selfdrive/car/chrysler/test_chryslercan.py b/selfdrive/car/chrysler/test_chryslercan.py index 5b15666c0..a17252618 100644 --- a/selfdrive/car/chrysler/test_chryslercan.py +++ b/selfdrive/car/chrysler/test_chryslercan.py @@ -8,7 +8,6 @@ VisualAlert = car.CarControl.HUDControl.VisualAlert GearShifter = car.CarState.GearShifter - class TestChryslerCan(unittest.TestCase): def test_hud(self): diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 03c6dab93..9af22c07a 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -10,7 +10,6 @@ class SteerLimitParams: STEER_ERROR_MAX = 80 - class CAR: PACIFICA_2017_HYBRID = "CHRYSLER PACIFICA HYBRID 2017" PACIFICA_2018_HYBRID = "CHRYSLER PACIFICA HYBRID 2018" diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index 100855eac..b01814bca 100755 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -34,7 +34,6 @@ class RadarInterface(RadarInterfaceBase): if self.trigger_msg not in self.updated_messages: return None - ret = car.RadarData.new_message() errors = [] if not self.rcp.can_valid: diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 38f7efb4f..65f80187d 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -339,7 +339,6 @@ class CarState(CarStateBase): ("FCM_PROBLEM", "ACC_HUD", 0), ("ICONS", "ACC_HUD", 0)] - # all hondas except CRV, RDX and 2019 Odyssey@China use 0xe4 for steering checks = [(0xe4, 100)] if CP.carFingerprint in [CAR.CRV, CAR.CRV_EU, CAR.ACURA_RDX, CAR.ODYSSEY_CHN]: diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 1cb11bd11..56f216fc4 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -387,7 +387,6 @@ class CarInterface(CarInterfaceBase): ret.longitudinalTuning.kiBP = [0., 35.] ret.longitudinalTuning.kiV = [0.18, 0.12] - else: raise ValueError("unsupported car %s" % candidate) diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py index b1606e64a..a921534c5 100755 --- a/selfdrive/car/honda/radar_interface.py +++ b/selfdrive/car/honda/radar_interface.py @@ -52,7 +52,6 @@ class RadarInterface(RadarInterfaceBase): self.updated_messages.clear() return rr - def _update(self, updated_messages): ret = car.RadarData.new_message() diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index e31a0bcea..dfd07d581 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -94,7 +94,6 @@ class CarController(): elif self.last_lead_distance != 0: self.last_lead_distance = 0 - # 20 Hz LFA MFA message if frame % 5 == 0 and self.car_fingerprint in [CAR.SONATA, CAR.PALISADE]: can_sends.append(create_lfa_mfa(self.packer, frame, enabled)) diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py index ecac93690..ce31cd2c0 100644 --- a/selfdrive/car/mazda/carcontroller.py +++ b/selfdrive/car/mazda/carcontroller.py @@ -36,7 +36,6 @@ class CarController(): # Match stock message rate which is sent at 10hz can_sends.append(mazdacan.create_button_cmd(self.packer, CS.CP.carFingerprint, Buttons.CANCEL)) - self.apply_steer_last = apply_steer can_sends.append(mazdacan.create_steering_control(self.packer, CS.CP.carFingerprint, diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index ffa99dada..e1c9030a0 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -56,7 +56,6 @@ class CarState(CarStateBase): ret.gas = cp.vl["ENGINE_DATA"]['PEDAL_GAS'] ret.gasPressed = ret.gas > 0 - # LKAS is enabled at 52kph going up and disabled at 45kph going down if speed_kph > LKAS_LIMITS.ENABLE_SPEED: self.lkas_allowed = True @@ -155,7 +154,6 @@ class CarState(CarStateBase): return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) - @staticmethod def get_cam_can_parser(CP): signals = [ ] diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 160f531f2..f4af31894 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -46,7 +46,6 @@ class CarInterface(CarInterfaceBase): # No steer below disable speed ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS - ret.centerToFront = ret.wheelbase * 0.41 # TODO: get actual value, for now starting with reasonable value for diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py index 7f3fc3d84..0997b1200 100644 --- a/selfdrive/car/subaru/carcontroller.py +++ b/selfdrive/car/subaru/carcontroller.py @@ -16,7 +16,6 @@ class CarControllerParams(): self.STEER_DRIVER_FACTOR = 1 # from dbc - class CarController(): def __init__(self, dbc_name, CP, VM): self.lkas_active = False diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index c9970bead..1c8c3735d 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -160,7 +160,6 @@ class CarState(CarStateBase): signals.append(("LOW_SPEED_LOCKOUT", "PCM_CRUISE_2", 0)) checks.append(("PCM_CRUISE_2", 33)) - if CP.carFingerprint == CAR.PRIUS: signals += [("STATE", "AUTOPARK_STATUS", 0)] diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 46a657f3f..ae421892f 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -146,7 +146,6 @@ class Controls: self.rk = Ratekeeper(100, print_delay_threshold=None) self.prof = Profiler(False) # off by default - def update_events(self, CS): """Compute carEvents from carState""" @@ -226,7 +225,6 @@ class Controls: and not self.CP.radarOffCan and CS.vEgo < 0.3: self.events.add(EventName.noTarget) - def data_sample(self): """Receive data from sockets and update carState""" @@ -255,7 +253,6 @@ class Controls: return CS - def state_transition(self, CS): """Compute conditional state transitions and execute actions on state transitions""" @@ -331,7 +328,6 @@ class Controls: # Check if openpilot is engaged self.enabled = self.active or self.state == State.preEnabled - def state_control(self, CS): """Given the state, this function returns an actuators packet""" @@ -382,7 +378,6 @@ class Controls: return actuators, v_acc_sol, a_acc_sol, lac_log - def publish_logs(self, CS, start_time, actuators, v_acc, a_acc, lac_log): """Send actuators and hud commands to the car, send controlsstate and MPC logging""" diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index e4d6f9723..3ae766281 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -133,7 +133,6 @@ class RadarD(): idens = list(sorted(self.tracks.keys())) track_pts = list([self.tracks[iden].get_key_for_cluster() for iden in idens]) - # If we have multiple points, cluster them if len(track_pts) > 1: cluster_idxs = cluster_points_centroid(track_pts, 2.5) diff --git a/selfdrive/debug/internal/check_alive_valid.py b/selfdrive/debug/internal/check_alive_valid.py index cee03d6a3..cd8a2463e 100755 --- a/selfdrive/debug/internal/check_alive_valid.py +++ b/selfdrive/debug/internal/check_alive_valid.py @@ -6,12 +6,10 @@ import cereal.messaging as messaging if __name__ == "__main__": sm = messaging.SubMaster(['thermal', 'health', 'model', 'liveCalibration', 'dMonitoringState', 'plan', 'pathPlan']) - i = 0 while True: sm.update(0) - i += 1 if i % 100 == 0: print() diff --git a/selfdrive/debug/mpc/live_lateral_mpc.py b/selfdrive/debug/mpc/live_lateral_mpc.py index d1e8276c1..7cd5c677a 100755 --- a/selfdrive/debug/mpc/live_lateral_mpc.py +++ b/selfdrive/debug/mpc/live_lateral_mpc.py @@ -55,7 +55,6 @@ def mpc_vwr_thread(addr="127.0.0.1"): aa.invert_xaxis() plt.show() - # *** log *** livempc = messaging.sub_sock('liveMpc', addr=addr) model = messaging.sub_sock('model', addr=addr) diff --git a/selfdrive/debug/mpc/live_longitudinal_mpc.py b/selfdrive/debug/mpc/live_longitudinal_mpc.py index b5b4361e1..4861a03ed 100755 --- a/selfdrive/debug/mpc/live_longitudinal_mpc.py +++ b/selfdrive/debug/mpc/live_longitudinal_mpc.py @@ -97,8 +97,6 @@ def plot_longitudinal_mpc(addr="127.0.0.1"): fig.canvas.flush_events() - - if __name__ == "__main__": if len(sys.argv) > 1: plot_longitudinal_mpc(sys.argv[1]) diff --git a/selfdrive/debug/mpc/tune_lateral.py b/selfdrive/debug/mpc/tune_lateral.py index 95bf6023b..f01865574 100755 --- a/selfdrive/debug/mpc/tune_lateral.py +++ b/selfdrive/debug/mpc/tune_lateral.py @@ -151,7 +151,6 @@ ys.append(sol_y) deltas.append(delta) - plt.figure() for i in range(len(xs)): diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 14754f75b..cb35763cd 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -167,7 +167,6 @@ def calibrationd_thread(sm=None, pm=None): sm['cameraOdometry'].transStd, sm['cameraOdometry'].rotStd) - if DEBUG and new_vp is not None: print('got new vp', new_vp) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index ad8455060..3798b3a45 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -194,7 +194,6 @@ class Localizer(): ecef_pos_R = np.diag([(3*log.verticalAccuracy)**2]*3) ecef_vel_R = np.diag([(log.speedAccuracy)**2]*3) - #self.time = GPSTime.from_datetime(datetime.utcfromtimestamp(log.timestamp*1e-3)) self.unix_timestamp_millis = log.timestamp gps_est_error = np.sqrt((self.kf.x[0] - ecef_pos[0])**2 + diff --git a/selfdrive/locationd/models/constants.py b/selfdrive/locationd/models/constants.py index f0096aadb..ebe83186e 100644 --- a/selfdrive/locationd/models/constants.py +++ b/selfdrive/locationd/models/constants.py @@ -38,7 +38,6 @@ class ObservationKind: STEER_RATIO = 29 # [-] ROAD_FRAME_X_SPEED = 30 # (x) [m/s] - names = [ 'Unknown', 'No observation', diff --git a/selfdrive/locationd/test/test_params_learner.py b/selfdrive/locationd/test/test_params_learner.py index c1b75c5af..bd2399b24 100755 --- a/selfdrive/locationd/test/test_params_learner.py +++ b/selfdrive/locationd/test/test_params_learner.py @@ -46,8 +46,5 @@ class TestParamsLearner(unittest.TestCase): self.assertAlmostEqual(sr_target, sr, places=1) - - - if __name__ == "__main__": unittest.main() diff --git a/selfdrive/locationd/test/ublox.py b/selfdrive/locationd/test/ublox.py index cfb32ed81..8120f70fd 100644 --- a/selfdrive/locationd/test/ublox.py +++ b/selfdrive/locationd/test/ublox.py @@ -737,7 +737,6 @@ class UBlox: self.buf = self.buf[n:] return ret - def write(self, dat): pass diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index c5e48a863..6d858c9ec 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -80,7 +80,6 @@ def configure_ublox(dev): dev.configure_message_rate(ublox.CLASS_MON, ublox.MSG_MON_HW, 1) - def int_to_bool_list(num): # for parsing bool bytes return [bool(num & (1 << n)) for n in range(8)] @@ -181,8 +180,6 @@ def gen_nav_data(msg, nav_frame_buffer): return gen_ephemeris(ephem_data) - - def gen_raw(msg): # meta data is in first part of tuple # list of measurements is in second part @@ -284,7 +281,6 @@ def main(): for i in range(1, 33): nav_frame_buffer[0][i] = {} - gpsLocationExternal = messaging.pub_sock('gpsLocationExternal') ubloxGnss = messaging.pub_sock('ubloxGnss') diff --git a/selfdrive/modeld/visiontest.py b/selfdrive/modeld/visiontest.py index aead045bc..72dbe59ac 100644 --- a/selfdrive/modeld/visiontest.py +++ b/selfdrive/modeld/visiontest.py @@ -103,7 +103,6 @@ class VisionTest(): transform) return result - def transform_output_buffer(self, yuv_data, y_out, u_out, v_out, transform): assert len(yuv_data) == self.input_size[0] * self.input_size[1] * 3/2 diff --git a/selfdrive/test/longitudinal_maneuvers/maneuverplots.py b/selfdrive/test/longitudinal_maneuvers/maneuverplots.py index eb038c33a..9a5ea6155 100644 --- a/selfdrive/test/longitudinal_maneuvers/maneuverplots.py +++ b/selfdrive/test/longitudinal_maneuvers/maneuverplots.py @@ -61,7 +61,6 @@ class ManeuverPlot(): self.a_target_array.append(a_target) self.fcw_array.append(fcw) - def write_plot(self, path, maneuver_name): # title = self.title or maneuver_name # TODO: Missing plots from the old one: diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index f45ccda75..45a4a01f5 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -355,7 +355,6 @@ class Plant(): msg_data = fix(msg_data, 0xe4) can_msgs.append([0xe4, 0, msg_data, 2]) - # Fake sockets that controlsd subscribes to live_parameters = messaging.new_message('liveParameters') live_parameters.liveParameters.valid = True diff --git a/selfdrive/test/process_replay/inject_model.py b/selfdrive/test/process_replay/inject_model.py index aaba74441..ee1684675 100755 --- a/selfdrive/test/process_replay/inject_model.py +++ b/selfdrive/test/process_replay/inject_model.py @@ -65,7 +65,6 @@ def inject_model(msgs, segment_name): time.sleep(2) manager.kill_managed_process('camerad') - new_msgs = [] midx = 0 for msg in msgs: diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index ad0b9fc6f..ca438ed66 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -94,7 +94,6 @@ class FakeSubMaster(messaging.SubMaster): wait_for_event(self.update_ready) self.update_ready.clear() - def update_msgs(self, cur_time, msgs): wait_for_event(self.update_called) self.update_called.clear() diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py index 8fc4205cd..7e5217738 100755 --- a/selfdrive/test/update_ci_routes.py +++ b/selfdrive/test/update_ci_routes.py @@ -65,7 +65,6 @@ if __name__ == "__main__": if not sync_to_ci_public(r): failed_routes.append(r) - if len(failed_routes): print("failed routes:") print(failed_routes) diff --git a/tools/carcontrols/joystick_test.py b/tools/carcontrols/joystick_test.py index acf01c7fd..0d92c7042 100755 --- a/tools/carcontrols/joystick_test.py +++ b/tools/carcontrols/joystick_test.py @@ -63,7 +63,6 @@ while not done: if event.type == pygame.JOYBUTTONUP: print("Joystick button released.") - # DRAWING STEP # First, clear the screen to white. Don't put other drawing commands # above this, or they will be erased with this command. @@ -107,10 +106,8 @@ while not done: textPrint.printf(screen, "Button {:>2} value: {}".format(i, button) ) textPrint.unindent() - textPrint.unindent() - # ALL CODE TO DRAW SHOULD GO ABOVE THIS COMMENT # Go ahead and update the screen with what we've drawn. diff --git a/tools/lib/kbhit.py b/tools/lib/kbhit.py index 57958e3ba..fcb29c16a 100644 --- a/tools/lib/kbhit.py +++ b/tools/lib/kbhit.py @@ -31,14 +31,12 @@ class KBHit: termios.tcsetattr(self.fd, termios.TCSAFLUSH, self.old_term) - def getch(self): ''' Returns a keyboard character after kbhit() has been called. Should not be called in the same program as getarrow(). ''' return sys.stdin.read(1) - def getarrow(self): ''' Returns an arrow-key code after kbhit() has been called. Codes are 0 : up @@ -53,7 +51,6 @@ class KBHit: return vals.index(ord(c.decode('utf-8'))) - def kbhit(self): ''' Returns True if keyboard character was hit, False otherwise. ''' diff --git a/tools/lib/route_framereader.py b/tools/lib/route_framereader.py index 2045a4b4c..a60547cc0 100644 --- a/tools/lib/route_framereader.py +++ b/tools/lib/route_framereader.py @@ -75,7 +75,6 @@ class RouteFrameReader(object): return self._frame_readers[segment_num].get(segment_id, **kwargs)[0] - def close(self): frs = self._frame_readers self._frame_readers.clear() diff --git a/tools/lib/tests/test_readers.py b/tools/lib/tests/test_readers.py index c8688a4d8..cb6ba3e11 100755 --- a/tools/lib/tests/test_readers.py +++ b/tools/lib/tests/test_readers.py @@ -18,7 +18,6 @@ class TestReaders(unittest.TestCase): self.assertEqual(hist['carControl'], 6000) self.assertEqual(hist['logMessage'], 6857) - with tempfile.NamedTemporaryFile(suffix=".bz2") as fp: r = requests.get("https://github.com/commaai/comma2k19/blob/master/Example_1/b0c9d2329ad1606b%7C2018-08-02--08-34-47/40/raw_log.bz2?raw=true") fp.write(r.content) @@ -36,11 +35,9 @@ class TestReaders(unittest.TestCase): self.assertEqual(f.w, 1164) self.assertEqual(f.h, 874) - frame_first_30 = f.get(0, 30) self.assertEqual(len(frame_first_30), 30) - print(frame_first_30[15]) print("frame_0") diff --git a/tools/replay/camera.py b/tools/replay/camera.py index a726c27da..e1869048e 100755 --- a/tools/replay/camera.py +++ b/tools/replay/camera.py @@ -19,7 +19,6 @@ _FULL_FRAME_TO_BB = np.linalg.inv(_BB_TO_FULL_FRAME) _FULL_FRAME_SIZE = 1164, 874 - def pygame_modules_have_loaded(): return pygame.display.get_init() and pygame.font.get_init() diff --git a/tools/replay/lib/ui_helpers.py b/tools/replay/lib/ui_helpers.py index 277792f54..b95c8f63e 100644 --- a/tools/replay/lib/ui_helpers.py +++ b/tools/replay/lib/ui_helpers.py @@ -187,7 +187,6 @@ def draw_mpc(liveMpc, top_down): top_down[1][px, py] = mpc_color - class CalibrationTransformsForWarpMatrix(object): def __init__(self, model_to_full_frame, K, E): self._model_to_full_frame = model_to_full_frame diff --git a/tools/replay/sensorium.py b/tools/replay/sensorium.py index ea4a90996..10b2a960d 100755 --- a/tools/replay/sensorium.py +++ b/tools/replay/sensorium.py @@ -42,7 +42,6 @@ if __name__ == "__main__": calibration = CalibrationTransformsForWarpMatrix(warp_matrix, intrinsic_matrix, extrinsic_matrix) transform = np.dot(img_transform, calibration.model_to_full_frame) - if calibration is not None: imgw = cv2.warpAffine(imgff, transform[:2], (MEDMODEL_INPUT_SIZE[0], MEDMODEL_INPUT_SIZE[1]), diff --git a/tools/replay/ui.py b/tools/replay/ui.py index 5b7bf7b29..438f86f91 100755 --- a/tools/replay/ui.py +++ b/tools/replay/ui.py @@ -131,7 +131,6 @@ def ui_thread(addr, frame_address): [ 0.0, 0.0, 1.0] ]) - if rgb_img_raw and len(rgb_img_raw) == FULL_FRAME_SIZE[0] * FULL_FRAME_SIZE[1] * 3: imgff = np.frombuffer(rgb_img_raw, dtype=np.uint8).reshape((FULL_FRAME_SIZE[1], FULL_FRAME_SIZE[0], 3)) imgff = imgff[:, :, ::-1] # Convert BGR to RGB @@ -189,7 +188,6 @@ def ui_thread(addr, frame_address): # draw all radar points maybe_update_radar_points(sm['liveTracks'], top_down[1]) - if sm.updated['liveCalibration']: extrinsic_matrix = np.asarray(sm['liveCalibration'].extrinsicMatrix).reshape(3, 4) ke = intrinsic_matrix.dot(extrinsic_matrix)