From 77f4f57e73eb5219a3641899c9d4e48b53f0f47c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 4 Sep 2024 16:44:28 -0700 Subject: [PATCH 001/214] controlsd: pull out selfdrive state machine (#33477) * controlsd: pull out selfdrive state machine * cleanup test * cleanup --- selfdrive/controls/controlsd.py | 105 ++---------------- selfdrive/controls/lib/selfdrive.py | 98 ++++++++++++++++ .../controls/tests/test_state_machine.py | 92 +++++++-------- 3 files changed, 148 insertions(+), 147 deletions(-) create mode 100644 selfdrive/controls/lib/selfdrive.py diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 27cf7c2134..a56c335ed4 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -29,11 +29,11 @@ from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle, S from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.longcontrol import LongControl from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel +from openpilot.selfdrive.controls.lib.selfdrive import StateMachine from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose from openpilot.system.hardware import HARDWARE -SOFT_DISABLE_TIME = 3 # seconds LDW_MIN_SPEED = 31 * CV.MPH_TO_MS LANE_DEPARTURE_THRESHOLD = 0.1 CAMERA_OFFSET = 0.04 @@ -58,8 +58,6 @@ SafetyModel = car.CarParams.SafetyModel IGNORED_SAFETY_MODES = (SafetyModel.silent, SafetyModel.noOutput) CSID_MAP = {"1": EventName.roadCameraError, "2": EventName.wideRoadCameraError, "0": EventName.driverCameraError} ACTUATOR_FIELDS = tuple(car.CarControl.Actuators.schema.fields.keys()) -ACTIVE_STATES = (State.enabled, State.softDisabling, State.overriding) -ENABLED_STATES = (State.preEnabled, *ACTIVE_STATES) class Controls: @@ -141,10 +139,8 @@ class Controls: self.LaC = LatControlTorque(self.CP, self.CI) self.initialized = False - self.state = State.disabled self.enabled = False self.active = False - self.soft_disable_timer = 0 self.mismatch_counter = 0 self.cruise_mismatch_counter = 0 self.last_blinker_frame = 0 @@ -152,7 +148,6 @@ class Controls: self.distance_traveled = 0 self.last_functional_fan_frame = 0 self.events_prev = [] - self.current_alert_types = [ET.PERMANENT] self.logged_comm_issue = None self.not_running_prev = None self.steer_limited = False @@ -160,6 +155,7 @@ class Controls: self.experimental_mode = False self.personality = self.read_personality_param() self.recalibrating_seen = False + self.state_machine = StateMachine() self.can_log_mono_time = 0 @@ -181,7 +177,7 @@ class Controls: def set_initial_state(self): if REPLAY and any(ps.controlsAllowed for ps in self.sm['pandaStates']): - self.state = State.enabled + self.state_machine.state = State.enabled def update_events(self, CS): """Compute onroadEvents from carState""" @@ -439,89 +435,6 @@ class Controls: return CS - def state_transition(self, CS): - """Compute conditional state transitions and execute actions on state transitions""" - - # decrement the soft disable timer at every step, as it's reset on - # entrance in SOFT_DISABLING state - self.soft_disable_timer = max(0, self.soft_disable_timer - 1) - - self.current_alert_types = [ET.PERMANENT] - - # ENABLED, SOFT DISABLING, PRE ENABLING, OVERRIDING - if self.state != State.disabled: - # user and immediate disable always have priority in a non-disabled state - if self.events.contains(ET.USER_DISABLE): - self.state = State.disabled - self.current_alert_types.append(ET.USER_DISABLE) - - elif self.events.contains(ET.IMMEDIATE_DISABLE): - self.state = State.disabled - self.current_alert_types.append(ET.IMMEDIATE_DISABLE) - - else: - # ENABLED - if self.state == State.enabled: - if self.events.contains(ET.SOFT_DISABLE): - self.state = State.softDisabling - self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) - self.current_alert_types.append(ET.SOFT_DISABLE) - - elif self.events.contains(ET.OVERRIDE_LATERAL) or self.events.contains(ET.OVERRIDE_LONGITUDINAL): - self.state = State.overriding - self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] - - # SOFT DISABLING - elif self.state == State.softDisabling: - if not self.events.contains(ET.SOFT_DISABLE): - # no more soft disabling condition, so go back to ENABLED - self.state = State.enabled - - elif self.soft_disable_timer > 0: - self.current_alert_types.append(ET.SOFT_DISABLE) - - elif self.soft_disable_timer <= 0: - self.state = State.disabled - - # PRE ENABLING - elif self.state == State.preEnabled: - if not self.events.contains(ET.PRE_ENABLE): - self.state = State.enabled - else: - self.current_alert_types.append(ET.PRE_ENABLE) - - # OVERRIDING - elif self.state == State.overriding: - if self.events.contains(ET.SOFT_DISABLE): - self.state = State.softDisabling - self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) - self.current_alert_types.append(ET.SOFT_DISABLE) - elif not (self.events.contains(ET.OVERRIDE_LATERAL) or self.events.contains(ET.OVERRIDE_LONGITUDINAL)): - self.state = State.enabled - else: - self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] - - # DISABLED - elif self.state == State.disabled: - if self.events.contains(ET.ENABLE): - if self.events.contains(ET.NO_ENTRY): - self.current_alert_types.append(ET.NO_ENTRY) - - else: - if self.events.contains(ET.PRE_ENABLE): - self.state = State.preEnabled - elif self.events.contains(ET.OVERRIDE_LATERAL) or self.events.contains(ET.OVERRIDE_LONGITUDINAL): - self.state = State.overriding - else: - self.state = State.enabled - self.current_alert_types.append(ET.ENABLE) - - # Check if openpilot is engaged and actuators are enabled - self.enabled = self.state in ENABLED_STATES - self.active = self.state in ACTIVE_STATES - if self.active: - self.current_alert_types.append(ET.WARNING) - def state_control(self, CS): """Given the state, this function returns a CarControl packet""" @@ -704,13 +617,14 @@ class Controls: self.events.add(EventName.ldw) clear_event_types = set() - if ET.WARNING not in self.current_alert_types: + if ET.WARNING not in self.state_machine.current_alert_types: clear_event_types.add(ET.WARNING) if self.enabled: clear_event_types.add(ET.NO_ENTRY) pers = {v: k for k, v in log.LongitudinalPersonality.schema.enumerants.items()}[self.personality] - alerts = self.events.create_alerts(self.current_alert_types, [self.CP, CS, self.sm, self.is_metric, self.soft_disable_timer, pers]) + alerts = self.events.create_alerts(self.state_machine.current_alert_types, [self.CP, CS, self.sm, self.is_metric, + self.state_machine.soft_disable_timer, pers]) self.AM.add_many(self.sm.frame, alerts) current_alert = self.AM.process_alerts(self.sm.frame, clear_event_types) if current_alert: @@ -725,7 +639,7 @@ class Controls: self.steer_limited = abs(CC.actuators.steer - CO.actuatorsOutput.steer) > 1e-2 force_decel = (self.sm['driverMonitoringState'].awarenessStatus < 0.) or \ - (self.state == State.softDisabling) + (self.state_machine.state == State.softDisabling) # Curvature & Steering angle lp = self.sm['liveParameters'] @@ -773,7 +687,7 @@ class Controls: ss.alertSound = current_alert.audible_alert ss.enabled = self.enabled ss.active = self.active - ss.state = self.state + ss.state = self.state_machine.state ss.engageable = not self.events.contains(ET.NO_ENTRY) ss.experimentalMode = self.experimental_mode ss.personality = self.personality @@ -802,8 +716,7 @@ class Controls: cloudlog.timestamp("Events updated") if not self.CP.passive and self.initialized: - # Update control state - self.state_transition(CS) + self.enabled, self.active = self.state_machine.update(self.events) # Compute actuators (runs PID loops and lateral MPC) CC, lac_log = self.state_control(CS) diff --git a/selfdrive/controls/lib/selfdrive.py b/selfdrive/controls/lib/selfdrive.py new file mode 100644 index 0000000000..adbcd1d926 --- /dev/null +++ b/selfdrive/controls/lib/selfdrive.py @@ -0,0 +1,98 @@ +from cereal import log +from openpilot.selfdrive.controls.lib.events import Events, ET +from openpilot.common.realtime import DT_CTRL + +State = log.SelfdriveState.OpenpilotState + +SOFT_DISABLE_TIME = 3 # seconds +ACTIVE_STATES = (State.enabled, State.softDisabling, State.overriding) +ENABLED_STATES = (State.preEnabled, *ACTIVE_STATES) + +class StateMachine: + def __init__(self): + self.current_alert_types = [ET.PERMANENT] + self.state = State.disabled + self.soft_disable_timer = 0 + + def update(self, events: Events): + # decrement the soft disable timer at every step, as it's reset on + # entrance in SOFT_DISABLING state + self.soft_disable_timer = max(0, self.soft_disable_timer - 1) + + self.current_alert_types = [ET.PERMANENT] + + # ENABLED, SOFT DISABLING, PRE ENABLING, OVERRIDING + if self.state != State.disabled: + # user and immediate disable always have priority in a non-disabled state + if events.contains(ET.USER_DISABLE): + self.state = State.disabled + self.current_alert_types.append(ET.USER_DISABLE) + + elif events.contains(ET.IMMEDIATE_DISABLE): + self.state = State.disabled + self.current_alert_types.append(ET.IMMEDIATE_DISABLE) + + else: + # ENABLED + if self.state == State.enabled: + if events.contains(ET.SOFT_DISABLE): + self.state = State.softDisabling + self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) + self.current_alert_types.append(ET.SOFT_DISABLE) + + elif events.contains(ET.OVERRIDE_LATERAL) or events.contains(ET.OVERRIDE_LONGITUDINAL): + self.state = State.overriding + self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] + + # SOFT DISABLING + elif self.state == State.softDisabling: + if not events.contains(ET.SOFT_DISABLE): + # no more soft disabling condition, so go back to ENABLED + self.state = State.enabled + + elif self.soft_disable_timer > 0: + self.current_alert_types.append(ET.SOFT_DISABLE) + + elif self.soft_disable_timer <= 0: + self.state = State.disabled + + # PRE ENABLING + elif self.state == State.preEnabled: + if not events.contains(ET.PRE_ENABLE): + self.state = State.enabled + else: + self.current_alert_types.append(ET.PRE_ENABLE) + + # OVERRIDING + elif self.state == State.overriding: + if events.contains(ET.SOFT_DISABLE): + self.state = State.softDisabling + self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) + self.current_alert_types.append(ET.SOFT_DISABLE) + elif not (events.contains(ET.OVERRIDE_LATERAL) or events.contains(ET.OVERRIDE_LONGITUDINAL)): + self.state = State.enabled + else: + self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] + + # DISABLED + elif self.state == State.disabled: + if events.contains(ET.ENABLE): + if events.contains(ET.NO_ENTRY): + self.current_alert_types.append(ET.NO_ENTRY) + + else: + if events.contains(ET.PRE_ENABLE): + self.state = State.preEnabled + elif events.contains(ET.OVERRIDE_LATERAL) or events.contains(ET.OVERRIDE_LONGITUDINAL): + self.state = State.overriding + else: + self.state = State.enabled + self.current_alert_types.append(ET.ENABLE) + + # Check if openpilot is engaged and actuators are enabled + enabled = self.state in ENABLED_STATES + active = self.state in ACTIVE_STATES + if active: + self.current_alert_types.append(ET.WARNING) + return enabled, active + diff --git a/selfdrive/controls/tests/test_state_machine.py b/selfdrive/controls/tests/test_state_machine.py index a42cd6056b..d2117b3342 100644 --- a/selfdrive/controls/tests/test_state_machine.py +++ b/selfdrive/controls/tests/test_state_machine.py @@ -1,10 +1,7 @@ -from cereal import car, log -from opendbc.car.car_helpers import interfaces -from opendbc.car.mock.values import CAR as MOCK +from cereal import log from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.controls.controlsd import Controls, SOFT_DISABLE_TIME -from openpilot.selfdrive.controls.lib.events import Events, ET, Alert, Priority, AlertSize, AlertStatus, VisualAlert, \ - AudibleAlert, EVENTS +from openpilot.selfdrive.controls.lib.selfdrive import StateMachine, SOFT_DISABLE_TIME +from openpilot.selfdrive.controls.lib.events import Events, ET, EVENTS, NormalPermanentAlert State = log.SelfdriveState.OpenpilotState @@ -19,84 +16,77 @@ ENABLE_EVENT_TYPES = (ET.ENABLE, ET.PRE_ENABLE, ET.OVERRIDE_LATERAL, ET.OVERRIDE def make_event(event_types): event = {} for ev in event_types: - event[ev] = Alert("", "", AlertStatus.normal, AlertSize.small, Priority.LOW, - VisualAlert.none, AudibleAlert.none, 1.) + event[ev] = NormalPermanentAlert("alert") EVENTS[0] = event return 0 class TestStateMachine: - def setup_method(self): - CarInterface, CarController, CarState, RadarInterface = interfaces[MOCK.MOCK] - CP = CarInterface.get_non_essential_params(MOCK.MOCK) - CI = CarInterface(CP, CarController, CarState) - - self.controlsd = Controls(CI=CI) - self.controlsd.events = Events() - self.controlsd.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) - self.CS = car.CarState() + self.events = Events() + self.state_machine = StateMachine() + self.state_machine.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) def test_immediate_disable(self): for state in ALL_STATES: for et in MAINTAIN_STATES[state]: - self.controlsd.events.add(make_event([et, ET.IMMEDIATE_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - assert State.disabled == self.controlsd.state - self.controlsd.events.clear() + self.events.add(make_event([et, ET.IMMEDIATE_DISABLE])) + self.state_machine.state = state + self.state_machine.update(self.events) + assert State.disabled == self.state_machine.state + self.events.clear() def test_user_disable(self): for state in ALL_STATES: for et in MAINTAIN_STATES[state]: - self.controlsd.events.add(make_event([et, ET.USER_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - assert State.disabled == self.controlsd.state - self.controlsd.events.clear() + self.events.add(make_event([et, ET.USER_DISABLE])) + self.state_machine.state = state + self.state_machine.update(self.events) + assert State.disabled == self.state_machine.state + self.events.clear() def test_soft_disable(self): for state in ALL_STATES: if state == State.preEnabled: # preEnabled considers NO_ENTRY instead continue for et in MAINTAIN_STATES[state]: - self.controlsd.events.add(make_event([et, ET.SOFT_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - assert self.controlsd.state == State.disabled if state == State.disabled else State.softDisabling - self.controlsd.events.clear() + self.events.add(make_event([et, ET.SOFT_DISABLE])) + self.state_machine.state = state + self.state_machine.update(self.events) + assert self.state_machine.state == State.disabled if state == State.disabled else State.softDisabling + self.events.clear() def test_soft_disable_timer(self): - self.controlsd.state = State.enabled - self.controlsd.events.add(make_event([ET.SOFT_DISABLE])) - self.controlsd.state_transition(self.CS) + self.state_machine.state = State.enabled + self.events.add(make_event([ET.SOFT_DISABLE])) + self.state_machine.update(self.events) for _ in range(int(SOFT_DISABLE_TIME / DT_CTRL)): - assert self.controlsd.state == State.softDisabling - self.controlsd.state_transition(self.CS) + assert self.state_machine.state == State.softDisabling + self.state_machine.update(self.events) - assert self.controlsd.state == State.disabled + assert self.state_machine.state == State.disabled def test_no_entry(self): # Make sure noEntry keeps us disabled for et in ENABLE_EVENT_TYPES: - self.controlsd.events.add(make_event([ET.NO_ENTRY, et])) - self.controlsd.state_transition(self.CS) - assert self.controlsd.state == State.disabled - self.controlsd.events.clear() + self.events.add(make_event([ET.NO_ENTRY, et])) + self.state_machine.update(self.events) + assert self.state_machine.state == State.disabled + self.events.clear() def test_no_entry_pre_enable(self): # preEnabled with noEntry event - self.controlsd.state = State.preEnabled - self.controlsd.events.add(make_event([ET.NO_ENTRY, ET.PRE_ENABLE])) - self.controlsd.state_transition(self.CS) - assert self.controlsd.state == State.preEnabled + self.state_machine.state = State.preEnabled + self.events.add(make_event([ET.NO_ENTRY, ET.PRE_ENABLE])) + self.state_machine.update(self.events) + assert self.state_machine.state == State.preEnabled def test_maintain_states(self): # Given current state's event type, we should maintain state for state in ALL_STATES: for et in MAINTAIN_STATES[state]: - self.controlsd.state = state - self.controlsd.events.add(make_event([et])) - self.controlsd.state_transition(self.CS) - assert self.controlsd.state == state - self.controlsd.events.clear() + self.state_machine.state = state + self.events.add(make_event([et])) + self.state_machine.update(self.events) + assert self.state_machine.state == state + self.events.clear() From 73d31d50c41b312869d409fd2329dcacf8333d3f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 4 Sep 2024 17:45:09 -0700 Subject: [PATCH 002/214] controlsd: pull out LDW (#33479) * controlsd: pull out LDW * cleanup * good ol mypy --- selfdrive/controls/controlsd.py | 50 +++++++++++---------------------- selfdrive/controls/lib/ldw.py | 41 +++++++++++++++++++++++++++ 2 files changed, 57 insertions(+), 34 deletions(-) create mode 100644 selfdrive/controls/lib/ldw.py diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index a56c335ed4..d9e258f07f 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -22,6 +22,7 @@ from openpilot.common.gps import get_gps_location_service from opendbc.car.car_helpers import get_car_interface from openpilot.selfdrive.controls.lib.alertmanager import AlertManager, set_offroad_alert from openpilot.selfdrive.controls.lib.drive_helpers import clip_curvature, get_startup_event +from openpilot.selfdrive.controls.lib.ldw import LaneDepartureWarning from openpilot.selfdrive.controls.lib.events import Events, ET from openpilot.selfdrive.controls.lib.latcontrol import LatControl, MIN_LATERAL_CONTROL_SPEED from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID @@ -34,10 +35,6 @@ from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose from openpilot.system.hardware import HARDWARE -LDW_MIN_SPEED = 31 * CV.MPH_TO_MS -LANE_DEPARTURE_THRESHOLD = 0.1 -CAMERA_OFFSET = 0.04 - JOYSTICK_MAX_LAT_ACCEL = 2.5 # m/s^2 REPLAY = "REPLAY" in os.environ @@ -48,7 +45,6 @@ IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd"} ThermalStatus = log.DeviceState.ThermalStatus State = log.SelfdriveState.OpenpilotState PandaType = log.PandaState.PandaType -Desire = log.Desire LaneChangeState = log.LaneChangeState LaneChangeDirection = log.LaneChangeDirection EventName = car.OnroadEvent.EventName @@ -130,6 +126,8 @@ class Controls: self.LoC = LongControl(self.CP) self.VM = VehicleModel(self.CP) + self.ldw = LaneDepartureWarning() + self.LaC: LatControl if self.CP.steerControlType == car.CarParams.SteerControlType.angle: self.LaC = LatControlAngle(self.CP, self.CI) @@ -143,7 +141,6 @@ class Controls: self.active = False self.mismatch_counter = 0 self.cruise_mismatch_counter = 0 - self.last_blinker_frame = 0 self.last_steering_pressed_frame = 0 self.distance_traveled = 0 self.last_functional_fan_frame = 0 @@ -382,6 +379,13 @@ class Controls: if self.sm['modelV2'].frameDropPerc > 20: self.events.add(EventName.modeldLagging) + # decrement personality on distance button press + if self.CP.openpilotLongitudinalControl: + if any(not be.pressed and be.type == ButtonType.gapAdjustCruise for be in CS.buttonEvents): + self.personality = (self.personality - 1) % 3 + self.params.put_nonblocking('LongitudinalPersonality', str(self.personality)) + self.events.add(EventName.personalityChanged) + def data_sample(self): """Receive data from sockets""" @@ -557,13 +561,6 @@ class Controls: cloudlog.error(f"actuators.{p} not finite {actuators.to_dict()}") setattr(actuators, p, 0.0) - # decrement personality on distance button press - if self.CP.openpilotLongitudinalControl: - if any(not be.pressed and be.type == ButtonType.gapAdjustCruise for be in CS.buttonEvents): - self.personality = (self.personality - 1) % 3 - self.params.put_nonblocking('LongitudinalPersonality', str(self.personality)) - self.events.add(EventName.personalityChanged) - return CC, lac_log def publish_logs(self, CS, CC, lac_log): @@ -594,27 +591,12 @@ class Controls: hudControl.rightLaneVisible = True hudControl.leftLaneVisible = True - recent_blinker = (self.sm.frame - self.last_blinker_frame) * DT_CTRL < 5.0 # 5s blinker cooldown - ldw_allowed = self.is_ldw_enabled and CS.vEgo > LDW_MIN_SPEED and not recent_blinker \ - and not CC.latActive and self.sm['liveCalibration'].calStatus == log.LiveCalibrationData.Status.calibrated - - model_v2 = self.sm['modelV2'] - desire_prediction = model_v2.meta.desirePrediction - if len(desire_prediction) and ldw_allowed: - right_lane_visible = model_v2.laneLineProbs[2] > 0.5 - left_lane_visible = model_v2.laneLineProbs[1] > 0.5 - l_lane_change_prob = desire_prediction[Desire.laneChangeLeft] - r_lane_change_prob = desire_prediction[Desire.laneChangeRight] - - lane_lines = model_v2.laneLines - l_lane_close = left_lane_visible and (lane_lines[1].y[0] > -(1.08 + CAMERA_OFFSET)) - r_lane_close = right_lane_visible and (lane_lines[2].y[0] < (1.08 - CAMERA_OFFSET)) - - hudControl.leftLaneDepart = bool(l_lane_change_prob > LANE_DEPARTURE_THRESHOLD and l_lane_close) - hudControl.rightLaneDepart = bool(r_lane_change_prob > LANE_DEPARTURE_THRESHOLD and r_lane_close) - - if hudControl.rightLaneDepart or hudControl.leftLaneDepart: - self.events.add(EventName.ldw) + self.ldw.update(self.sm.frame, self.sm['modelV2'], CS, CC) + if self.is_ldw_enabled and self.sm['liveCalibration'].calStatus == log.LiveCalibrationData.Status.calibrated: + hudControl.leftLaneDepart = self.ldw.left + hudControl.rightLaneDepart = self.ldw.right + if self.ldw.warning: + self.events.add(EventName.ldw) clear_event_types = set() if ET.WARNING not in self.state_machine.current_alert_types: diff --git a/selfdrive/controls/lib/ldw.py b/selfdrive/controls/lib/ldw.py new file mode 100644 index 0000000000..caf03fec73 --- /dev/null +++ b/selfdrive/controls/lib/ldw.py @@ -0,0 +1,41 @@ +from cereal import log +from openpilot.common.realtime import DT_CTRL +from openpilot.common.conversions import Conversions as CV + + +CAMERA_OFFSET = 0.04 +LDW_MIN_SPEED = 31 * CV.MPH_TO_MS +LANE_DEPARTURE_THRESHOLD = 0.1 + +class LaneDepartureWarning: + def __init__(self): + self.left = False + self.right = False + self.last_blinker_frame = 0 + + def update(self, frame, modelV2, CS, CC): + if CS.leftBlinker or CS.rightBlinker: + self.last_blinker_frame = frame + + recent_blinker = (frame - self.last_blinker_frame) * DT_CTRL < 5.0 # 5s blinker cooldown + ldw_allowed = CS.vEgo > LDW_MIN_SPEED and not recent_blinker and not CC.latActive + + desire_prediction = modelV2.meta.desirePrediction + if len(desire_prediction) and ldw_allowed: + right_lane_visible = modelV2.laneLineProbs[2] > 0.5 + left_lane_visible = modelV2.laneLineProbs[1] > 0.5 + l_lane_change_prob = desire_prediction[log.Desire.laneChangeLeft] + r_lane_change_prob = desire_prediction[log.Desire.laneChangeRight] + + lane_lines = modelV2.laneLines + l_lane_close = left_lane_visible and (lane_lines[1].y[0] > -(1.08 + CAMERA_OFFSET)) + r_lane_close = right_lane_visible and (lane_lines[2].y[0] < (1.08 - CAMERA_OFFSET)) + + self.left = bool(l_lane_change_prob > LANE_DEPARTURE_THRESHOLD and l_lane_close) + self.right = bool(r_lane_change_prob > LANE_DEPARTURE_THRESHOLD and r_lane_close) + else: + self.left, self.right = False, False + + @property + def warning(self) -> bool: + return bool(self.left or self.right) From e39466f53523b3ffd3d101cde0ab8d5be74a5f57 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 5 Sep 2024 13:50:58 -0700 Subject: [PATCH 003/214] bump opendbc (#33482) * bump * update --- docs/CARS.md | 2 +- opendbc_repo | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index e4813eb1d9..02ed887864 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -126,7 +126,7 @@ A supported vehicle is one that just works when you install a comma device. All |Kia|Carnival 2022-24[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Carnival (China only) 2023[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|EV6 (Non-US only) 2022-24[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Kia|EV6 (Southeast Asia only) 2022-24[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|EV6 (with HDA II) 2022-24[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|EV6 (without HDA II) 2022-24[5](#footnotes)|Highway Driving Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Forte 2019-21|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|6 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai G connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| diff --git a/opendbc_repo b/opendbc_repo index ff198e9af1..86be858a37 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit ff198e9af1cea1ab93d24b01beeb04ab3f2de742 +Subproject commit 86be858a37217d003e8d8b0097522656df7a5870 From e0be4a1f851cf1f3b39bdf4a488ce1f05f58aa1c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 6 Sep 2024 07:24:25 +0800 Subject: [PATCH 004/214] ci: eliminate unnecessary sleep to shorten UI report run time (#33462) reduce sleep --- selfdrive/ui/tests/test_ui/run.py | 20 ++++---------------- 1 file changed, 4 insertions(+), 16 deletions(-) diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 1a075b3c44..c8b14dad95 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -34,34 +34,24 @@ DATA: dict[str, capnp.lib.capnp._DynamicStructBuilder] = dict.fromkeys( "liveCalibration", "modelV2", "radarState", "driverMonitoringState", "carState", "driverStateV2", "roadCameraState", "wideRoadCameraState", "driverCameraState"], None) -def setup_common(click, pm: PubMaster): - Params().put("DongleId", "123456789012345") - pm.send('deviceState', DATA['deviceState']) - def setup_homescreen(click, pm: PubMaster): - setup_common(click, pm) + pass def setup_settings_device(click, pm: PubMaster): - setup_common(click, pm) - click(100, 100) def setup_onroad(click, pm: PubMaster): - setup_common(click, pm) - vipc_server = VisionIpcServer("camerad") for stream_type, cam, _ in STREAMS: vipc_server.create_buffers(stream_type, 5, False, cam.width, cam.height) vipc_server.start_listener() - packet_id = 0 - for _ in range(20): + for packet_id in range(20): for service, data in DATA.items(): if data: data.clear_write_flag() pm.send(service, data) - packet_id = packet_id + 1 for stream_type, _, image in STREAMS: vipc_server.send(stream_type, image, packet_id, packet_id, packet_id) @@ -116,7 +106,6 @@ def setup_onroad_alert_full(click, pm: PubMaster): setup_onroad_alert(click, pm, 'Full Alert', 'This is a full alert message', log.SelfdriveState.AlertSize.full) def setup_offroad_alert(click, pm: PubMaster): - setup_common(click, pm) for alert in OFFROAD_ALERTS: set_offroad_alert(alert, True) @@ -125,7 +114,6 @@ def setup_offroad_alert(click, pm: PubMaster): click(240, 216) def setup_update_available(click, pm: PubMaster): - setup_common(click, pm) Params().put_bool("UpdateAvailable", True) release_notes_path = os.path.join(BASEDIR, "RELEASES.md") with open(release_notes_path) as file: @@ -164,11 +152,13 @@ class TestUI: sys.modules["mouseinfo"] = False def setup(self): + Params().put("DongleId", "123456789012345") self.sm = SubMaster(["uiDebug"]) self.pm = PubMaster(list(DATA.keys())) while not self.sm.valid["uiDebug"]: self.sm.update(1) time.sleep(UI_DELAY) # wait a bit more for the UI to start rendering + self.pm.send('deviceState', DATA['deviceState']) try: self.ui = pywinctl.getWindowsWithTitle("ui")[0] except Exception as e: @@ -195,8 +185,6 @@ class TestUI: setup_case(self.click, self.pm) - time.sleep(UI_DELAY) # wait a bit more for the UI to finish rendering - im = self.screenshot() plt.imsave(SCREENSHOTS_DIR / f"{name}.png", im) From aef650013ee15e8f96ac8a56279e4c251938388e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 5 Sep 2024 16:28:57 -0700 Subject: [PATCH 005/214] controlsd: split up publishing and logic (#33483) * split up the pubs * move all event adds * split out alerts * lil more * clenaup * update test * cleanup --- selfdrive/controls/controlsd.py | 192 +++++++++--------- selfdrive/controls/lib/alertmanager.py | 11 +- .../controls/lib/tests/test_alertmanager.py | 4 +- selfdrive/debug/count_events.py | 4 +- selfdrive/test/process_replay/ref_commit | 2 +- 5 files changed, 106 insertions(+), 107 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index d9e258f07f..1a2136aa7a 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -117,6 +117,8 @@ class Controls: self.params.remove("ExperimentalMode") self.CS_prev = car.CarState.new_message() + self.CC_prev = car.CarControl.new_message() + self.lac_log_prev = None self.AM = AlertManager() self.events = Events() @@ -216,16 +218,10 @@ class Controls: if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: self.events.add(EventName.overheat) if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: - # under 7% of space free no enable allowed self.events.add(EventName.outOfSpace) if self.sm['deviceState'].memoryUsagePercent > 90 and not SIMULATION: self.events.add(EventName.lowMemory) - # TODO: enable this once loggerd CPU usage is more reasonable - #cpus = list(self.sm['deviceState'].cpuUsagePercent) - #if max(cpus, default=0) > 95 and not SIMULATION: - # self.events.add(EventName.highCpuUsage) - # Alert if fan isn't spinning for 5 seconds if self.sm['peripheralState'].pandaType != log.PandaState.PandaType.unknown: if self.sm['peripheralState'].fanSpeedRpm < 500 and self.sm['deviceState'].fanSpeedPercentDesired > 50: @@ -248,6 +244,13 @@ class Controls: else: self.events.add(EventName.calibrationInvalid) + # Lane departure warning + if self.sm.valid['modelV2'] and CS.canValid: + self.ldw.update(self.sm.frame, self.sm['modelV2'], CS, self.CC_prev) + if self.is_ldw_enabled and self.sm['liveCalibration'].calStatus == log.LiveCalibrationData.Status.calibrated: + if self.ldw.warning: + self.events.add(EventName.ldw) + # Handle lane change if self.sm['modelV2'].meta.laneChangeState == LaneChangeState.preLaneChange: direction = self.sm['modelV2'].meta.laneChangeDirection @@ -348,6 +351,37 @@ class Controls: if self.cruise_mismatch_counter > int(6. / DT_CTRL): self.events.add(EventName.cruiseMismatch) + # Send a "steering required alert" if saturation count has reached the limit + lac_log = self.lac_log_prev + if CS.steeringPressed: + self.last_steering_pressed_frame = self.sm.frame + recent_steer_pressed = (self.sm.frame - self.last_steering_pressed_frame)*DT_CTRL < 2.0 + if self.lac_log_prev is not None and self.lac_log_prev.active and not recent_steer_pressed and not self.CP.notCar: + lac_log = self.lac_log_prev + if self.CP.lateralTuning.which() == 'torque' and not self.joystick_mode: + undershooting = abs(lac_log.desiredLateralAccel) / abs(1e-3 + lac_log.actualLateralAccel) > 1.2 + turning = abs(lac_log.desiredLateralAccel) > 1.0 + good_speed = CS.vEgo > 5 + max_torque = abs(self.sm['carOutput'].actuatorsOutput.steer) > 0.99 + if undershooting and turning and good_speed and max_torque: + self.events.add(EventName.steerSaturated) + elif lac_log.saturated: + # TODO probably should not use dpath_points but curvature + dpath_points = self.sm['modelV2'].position.y + if len(dpath_points): + # Check if we deviated from the path + # TODO use desired vs actual curvature + if self.CP.steerControlType == car.CarParams.SteerControlType.angle: + steering_value = self.CC_prev.actuators.steeringAngleDeg + else: + steering_value = self.CC_prev.actuators.steer + + left_deviation = steering_value > 0 and dpath_points[0] < -0.20 + right_deviation = steering_value < 0 and dpath_points[0] > 0.20 + + if left_deviation or right_deviation: + self.events.add(EventName.steerSaturated) + # Check for FCW stock_long_is_braking = self.enabled and not self.CP.openpilotLongitudinalControl and CS.aEgo < -1.25 model_fcw = self.sm['modelV2'].meta.hardBrakePredicted and not CS.brakePressed and not stock_long_is_braking @@ -521,36 +555,6 @@ class Controls: lac_log.output = actuators.steer lac_log.saturated = abs(actuators.steer) >= 0.9 - if CS.steeringPressed: - self.last_steering_pressed_frame = self.sm.frame - recent_steer_pressed = (self.sm.frame - self.last_steering_pressed_frame)*DT_CTRL < 2.0 - - # Send a "steering required alert" if saturation count has reached the limit - if lac_log.active and not recent_steer_pressed and not self.CP.notCar: - if self.CP.lateralTuning.which() == 'torque' and not self.joystick_mode: - undershooting = abs(lac_log.desiredLateralAccel) / abs(1e-3 + lac_log.actualLateralAccel) > 1.2 - turning = abs(lac_log.desiredLateralAccel) > 1.0 - good_speed = CS.vEgo > 5 - max_torque = abs(self.sm['carOutput'].actuatorsOutput.steer) > 0.99 - if undershooting and turning and good_speed and max_torque: - lac_log.active and self.events.add(EventName.steerSaturated) - elif lac_log.saturated: - # TODO probably should not use dpath_points but curvature - dpath_points = model_v2.position.y - if len(dpath_points): - # Check if we deviated from the path - # TODO use desired vs actual curvature - if self.CP.steerControlType == car.CarParams.SteerControlType.angle: - steering_value = actuators.steeringAngleDeg - else: - steering_value = actuators.steer - - left_deviation = steering_value > 0 and dpath_points[0] < -0.20 - right_deviation = steering_value < 0 and dpath_points[0] > 0.20 - - if left_deviation or right_deviation: - self.events.add(EventName.steerSaturated) - # Ensure no NaNs/Infs for p in ACTUATOR_FIELDS: attr = getattr(actuators, p) @@ -563,9 +567,20 @@ class Controls: return CC, lac_log - def publish_logs(self, CS, CC, lac_log): - """Send actuators and hud commands to the car, send controlsstate and MPC logging""" + def update_alerts(self, CS): + clear_event_types = set() + if ET.WARNING not in self.state_machine.current_alert_types: + clear_event_types.add(ET.WARNING) + if self.enabled: + clear_event_types.add(ET.NO_ENTRY) + pers = {v: k for k, v in log.LongitudinalPersonality.schema.enumerants.items()}[self.personality] + alerts = self.events.create_alerts(self.state_machine.current_alert_types, [self.CP, CS, self.sm, self.is_metric, + self.state_machine.soft_disable_timer, pers]) + self.AM.add_many(self.sm.frame, alerts) + self.AM.process_alerts(self.sm.frame, clear_event_types) + + def publish_carControl(self, CS, CC, lac_log): # Orientation and angle rates can be useful for carcontroller # Only calibrated (car) frame is relevant for the carcontroller if self.calibrated_pose is not None: @@ -591,26 +606,12 @@ class Controls: hudControl.rightLaneVisible = True hudControl.leftLaneVisible = True - self.ldw.update(self.sm.frame, self.sm['modelV2'], CS, CC) - if self.is_ldw_enabled and self.sm['liveCalibration'].calStatus == log.LiveCalibrationData.Status.calibrated: + if self.sm.valid['modelV2'] and CS.canValid and self.is_ldw_enabled and self.sm['liveCalibration'].calStatus == log.LiveCalibrationData.Status.calibrated: hudControl.leftLaneDepart = self.ldw.left hudControl.rightLaneDepart = self.ldw.right - if self.ldw.warning: - self.events.add(EventName.ldw) - clear_event_types = set() - if ET.WARNING not in self.state_machine.current_alert_types: - clear_event_types.add(ET.WARNING) - if self.enabled: - clear_event_types.add(ET.NO_ENTRY) - - pers = {v: k for k, v in log.LongitudinalPersonality.schema.enumerants.items()}[self.personality] - alerts = self.events.create_alerts(self.state_machine.current_alert_types, [self.CP, CS, self.sm, self.is_metric, - self.state_machine.soft_disable_timer, pers]) - self.AM.add_many(self.sm.frame, alerts) - current_alert = self.AM.process_alerts(self.sm.frame, clear_event_types) - if current_alert: - hudControl.visualAlert = current_alert.visual_alert + if self.AM.current_alert: + hudControl.visualAlert = self.AM.current_alert.visual_alert if not self.CP.passive and self.initialized: CO = self.sm['carOutput'] @@ -620,53 +621,57 @@ class Controls: else: self.steer_limited = abs(CC.actuators.steer - CO.actuatorsOutput.steer) > 1e-2 - force_decel = (self.sm['driverMonitoringState'].awarenessStatus < 0.) or \ - (self.state_machine.state == State.softDisabling) - - # Curvature & Steering angle - lp = self.sm['liveParameters'] - - steer_angle_without_offset = math.radians(CS.steeringAngleDeg - lp.angleOffsetDeg) - curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, lp.roll) # controlsState dat = messaging.new_message('controlsState') dat.valid = CS.canValid - controlsState = dat.controlsState - controlsState.longitudinalPlanMonoTime = self.sm.logMonoTime['longitudinalPlan'] - controlsState.lateralPlanMonoTime = self.sm.logMonoTime['modelV2'] - controlsState.curvature = curvature - controlsState.desiredCurvature = self.desired_curvature - controlsState.longControlState = self.LoC.long_control_state - controlsState.upAccelCmd = float(self.LoC.pid.p) - controlsState.uiAccelCmd = float(self.LoC.pid.i) - controlsState.ufAccelCmd = float(self.LoC.pid.f) - controlsState.cumLagMs = -self.rk.remaining * 1000. - controlsState.forceDecel = bool(force_decel) + cs = dat.controlsState + + lp = self.sm['liveParameters'] + steer_angle_without_offset = math.radians(CS.steeringAngleDeg - lp.angleOffsetDeg) + cs.curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, lp.roll) + + cs.longitudinalPlanMonoTime = self.sm.logMonoTime['longitudinalPlan'] + cs.lateralPlanMonoTime = self.sm.logMonoTime['modelV2'] + cs.desiredCurvature = self.desired_curvature + cs.longControlState = self.LoC.long_control_state + cs.upAccelCmd = float(self.LoC.pid.p) + cs.uiAccelCmd = float(self.LoC.pid.i) + cs.ufAccelCmd = float(self.LoC.pid.f) + cs.cumLagMs = -self.rk.remaining * 1000. + cs.forceDecel = bool((self.sm['driverMonitoringState'].awarenessStatus < 0.) or + (self.state_machine.state == State.softDisabling)) lat_tuning = self.CP.lateralTuning.which() if self.joystick_mode: - controlsState.lateralControlState.debugState = lac_log + cs.lateralControlState.debugState = lac_log elif self.CP.steerControlType == car.CarParams.SteerControlType.angle: - controlsState.lateralControlState.angleState = lac_log + cs.lateralControlState.angleState = lac_log elif lat_tuning == 'pid': - controlsState.lateralControlState.pidState = lac_log + cs.lateralControlState.pidState = lac_log elif lat_tuning == 'torque': - controlsState.lateralControlState.torqueState = lac_log + cs.lateralControlState.torqueState = lac_log self.pm.send('controlsState', dat) + # carControl + cc_send = messaging.new_message('carControl') + cc_send.valid = CS.canValid + cc_send.carControl = CC + self.pm.send('carControl', cc_send) + + def publish_selfdriveState(self, CS): # selfdriveState ss_msg = messaging.new_message('selfdriveState') ss_msg.valid = CS.canValid ss = ss_msg.selfdriveState - if current_alert: - ss.alertText1 = current_alert.alert_text_1 - ss.alertText2 = current_alert.alert_text_2 - ss.alertSize = current_alert.alert_size - ss.alertStatus = current_alert.alert_status - ss.alertType = current_alert.alert_type - ss.alertSound = current_alert.audible_alert + if self.AM.current_alert: + ss.alertText1 = self.AM.current_alert.alert_text_1 + ss.alertText2 = self.AM.current_alert.alert_text_2 + ss.alertSize = self.AM.current_alert.alert_size + ss.alertStatus = self.AM.current_alert.alert_status + ss.alertType = self.AM.current_alert.alert_type + ss.alertSound = self.AM.current_alert.audible_alert ss.enabled = self.enabled ss.active = self.active ss.state = self.state_machine.state @@ -683,30 +688,23 @@ class Controls: self.pm.send('onroadEvents', ce_send) self.events_prev = self.events.names.copy() - # carControl - cc_send = messaging.new_message('carControl') - cc_send.valid = CS.canValid - cc_send.carControl = CC - self.pm.send('carControl', cc_send) - def step(self): - # Sample data from sockets and get a carState CS = self.data_sample() - cloudlog.timestamp("Data sampled") - self.update_events(CS) - cloudlog.timestamp("Events updated") - if not self.CP.passive and self.initialized: self.enabled, self.active = self.state_machine.update(self.events) + self.update_alerts(CS) # Compute actuators (runs PID loops and lateral MPC) CC, lac_log = self.state_control(CS) # Publish data - self.publish_logs(CS, CC, lac_log) + self.publish_carControl(CS, CC, lac_log) + self.publish_selfdriveState(CS) self.CS_prev = CS + self.CC_prev = CC + self.lac_log_prev = lac_log def read_personality_param(self): try: diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index f67e269fa9..a3b8684871 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -34,6 +34,7 @@ class AlertEntry: class AlertManager: def __init__(self): self.alerts: dict[str, AlertEntry] = defaultdict(AlertEntry) + self.current_alert: Alert | None = None def add_many(self, frame: int, alerts: list[Alert]) -> None: for alert in alerts: @@ -44,8 +45,8 @@ class AlertManager: min_end_frame = entry.start_frame + alert.duration entry.end_frame = max(frame + 1, min_end_frame) - def process_alerts(self, frame: int, clear_event_types: set) -> Alert | None: - current_alert = AlertEntry() + def process_alerts(self, frame: int, clear_event_types: set): + ae = AlertEntry() for v in self.alerts.values(): if not v.alert: continue @@ -54,8 +55,8 @@ class AlertManager: v.end_frame = -1 # sort by priority first and then by start_frame - greater = current_alert.alert is None or (v.alert.priority, v.start_frame) > (current_alert.alert.priority, current_alert.start_frame) + greater = ae.alert is None or (v.alert.priority, v.start_frame) > (ae.alert.priority, ae.start_frame) if v.active(frame) and greater: - current_alert = v + ae = v - return current_alert.alert + self.current_alert = ae.alert diff --git a/selfdrive/controls/lib/tests/test_alertmanager.py b/selfdrive/controls/lib/tests/test_alertmanager.py index 8b9c18a9d4..bc0da0da8c 100644 --- a/selfdrive/controls/lib/tests/test_alertmanager.py +++ b/selfdrive/controls/lib/tests/test_alertmanager.py @@ -32,8 +32,8 @@ class TestAlertManager: for frame in range(duration+10): if frame < add_duration: AM.add_many(frame, [alert, ]) - current_alert = AM.process_alerts(frame, {}) + AM.process_alerts(frame, {}) - shown = current_alert is not None + shown = AM.current_alert is not None should_show = frame <= show_duration assert shown == should_show, f"{frame=} {add_duration=} {duration=}" diff --git a/selfdrive/debug/count_events.py b/selfdrive/debug/count_events.py index 5942054757..4095ae3fc1 100755 --- a/selfdrive/debug/count_events.py +++ b/selfdrive/debug/count_events.py @@ -33,8 +33,8 @@ if __name__ == "__main__": if len(events) == 0 or ae != events[-1][1]: events.append((t, ae)) - elif msg.which() == 'controlsState': - at = msg.controlsState.alertType + elif msg.which() == 'selfdriveState': + at = msg.selfdriveState.alertType if "/override" not in at or "lanechange" in at.lower(): if len(alerts) == 0 or alerts[-1][1] != at: alerts.append((t, at)) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 4942a6920a..90d6c85cb9 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -c2022c388da6eb2e26bb23ad6009be9d5314c0be +fb0827a00b21b97733f8385cf7ce87a21a526f4c \ No newline at end of file From 922348f33d8b4479f8559d13cd9a6c90fd97df40 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 5 Sep 2024 22:40:17 -0700 Subject: [PATCH 006/214] card parses radar points (#33443) * interfaces returns radarinterface old-commit-hash: 9ad1f096bfca3712320f19b1b49aa9e6ac9b68e4 * bump old-commit-hash: 20334a8b257c6037e11d02f2ba7b1f02c59f3240 * get RI from opendbc old-commit-hash: b5f6d0c48c90927926e9dd557130075aeec5edee * stash so far old-commit-hash: 5aa2c842eb152316434c17a661df05bb8af61f47 * new liveTracks message (radard expects and needs RadarData) * this should just work? * whoops * fix that * rm liveTracks from radard pm * fix proceess replay * lol fcw diff, something's not right * actually there's fcw in original route. it's pretty close * no tracks! * fix test_leads * CPU moved across procs * fix not engageable from onroadEvents * bump * fixes * bump to master * radard publishes w/ modelV2 now, so it will always be sent. check valid which radard sets using liveTracks avg freq * fix that (it works!) * combine join * bump * bump * deprecate * why * fix incorrect args * remove cumLagMs from process_replay * update refs --- cereal/car.capnp | 1 + cereal/log.capnp | 7 +-- opendbc_repo | 2 +- selfdrive/car/card.py | 37 +++++++++---- selfdrive/car/helpers.py | 4 +- selfdrive/car/tests/test_models.py | 2 +- selfdrive/controls/controlsd.py | 4 +- selfdrive/controls/radard.py | 54 +++++-------------- selfdrive/controls/tests/test_leads.py | 10 ++-- selfdrive/test/process_replay/migration.py | 32 ++++++++++- .../test/process_replay/process_replay.py | 11 ++-- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/test_onroad.py | 4 +- 13 files changed, 95 insertions(+), 75 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index 9f72e31637..026aa7baa5 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -508,6 +508,7 @@ struct CarParams { carFw @44 :List(CarFw); radarTimeStep @45: Float32 = 0.05; # time delta between radar updates, 20Hz is very standard + radarDelay @74 :Float32; fingerprintSource @49: FingerprintSource; networkLocation @50 :NetworkLocation; # Where Panda/C2 is integrated into the car's CAN network diff --git a/cereal/log.capnp b/cereal/log.capnp index 079b62e209..b715d14220 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -611,7 +611,6 @@ struct RadarState @0x9a185389d6fdd05f { leadOne @3 :LeadData; leadTwo @4 :LeadData; - cumLagMs @5 :Float32; struct LeadData { dRel @0 :Float32; @@ -641,6 +640,7 @@ struct RadarState @0x9a185389d6fdd05f { calCycleDEPRECATED @8 :Int32; calPercDEPRECATED @9 :Int8; canMonoTimesDEPRECATED @10 :List(UInt64); + cumLagMsDEPRECATED @5 :Float32; } struct LiveCalibrationData { @@ -671,7 +671,7 @@ struct LiveCalibrationData { } } -struct LiveTracks { +struct LiveTracksDEPRECATED { trackId @0 :Int32; dRel @1 :Float32; yRel @2 :Float32; @@ -2335,7 +2335,7 @@ struct Event { pandaStates @81 :List(PandaState); peripheralState @80 :PeripheralState; radarState @13 :RadarState; - liveTracks @16 :List(LiveTracks); + liveTracks @131 :Car.RadarData; sendcan @17 :List(CanData); liveCalibration @19 :LiveCalibrationData; carState @22 :Car.CarState; @@ -2465,5 +2465,6 @@ struct Event { navModelDEPRECATED @104 :NavModelData; uiPlanDEPRECATED @106 :UiPlan; liveLocationKalmanDEPRECATED @72 :LiveLocationKalman; + liveTracksDEPRECATED @16 :List(LiveTracksDEPRECATED); } } diff --git a/opendbc_repo b/opendbc_repo index 86be858a37..c0a9ab5c39 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 86be858a37217d003e8d8b0097522656df7a5870 +Subproject commit c0a9ab5c39197d48cc920a818a85610e526f9e73 diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 57b41a5cf5..541a7c44ae 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -16,8 +16,8 @@ from openpilot.common.swaglog import cloudlog, ForwardingHandler from opendbc.car import DT_CTRL, carlog, structs from opendbc.car.can_definitions import CanData, CanRecvCallable, CanSendCallable from opendbc.car.fw_versions import ObdCallback -from opendbc.car.car_helpers import get_car -from opendbc.car.interfaces import CarInterfaceBase +from opendbc.car.car_helpers import get_car, get_radar_interface +from opendbc.car.interfaces import CarInterfaceBase, RadarInterfaceBase from openpilot.selfdrive.pandad import can_capnp_to_list, can_list_to_can_capnp from openpilot.selfdrive.car.cruise import VCruiseHelper from openpilot.selfdrive.car.car_specific import CarSpecificEvents, MockCarState @@ -63,13 +63,14 @@ def can_comm_callbacks(logcan: messaging.SubSocket, sendcan: messaging.PubSocket class Car: CI: CarInterfaceBase + RI: RadarInterfaceBase CP: structs.CarParams CP_capnp: car.CarParams - def __init__(self, CI=None) -> None: + def __init__(self, CI=None, RI=None) -> None: self.can_sock = messaging.sub_sock('can', timeout=20) self.sm = messaging.SubMaster(['pandaStates', 'carControl', 'onroadEvents']) - self.pm = messaging.PubMaster(['sendcan', 'carState', 'carParams', 'carOutput']) + self.pm = messaging.PubMaster(['sendcan', 'carState', 'carParams', 'carOutput', 'liveTracks']) self.can_rcv_cum_timeout_counter = 0 @@ -101,12 +102,14 @@ class Car: cached_params = structs.CarParams(carName=_cached_params.carName, carFw=_cached_params.carFw, carVin=_cached_params.carVin) self.CI = get_car(*self.can_callbacks, obd_callback(self.params), experimental_long_allowed, num_pandas, cached_params) + self.RI = get_radar_interface(self.CI.CP) self.CP = self.CI.CP # continue onto next fingerprinting step in pandad self.params.put_bool("FirmwareQueryDone", True) else: self.CI, self.CP = CI, CI.CP + self.RI = RI # set alternative experiences from parameters self.disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") @@ -149,7 +152,7 @@ class Car: # card is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) - def state_update(self) -> car.CarState: + def state_update(self) -> tuple[car.CarState, structs.RadarData | None]: """carState update loop, driven by can""" # Update carState from CAN @@ -159,6 +162,9 @@ class Car: if self.CP.carName == 'mock': CS = self.mock_carstate.update(CS) + # Update radar tracks from CAN + RD: structs.RadarData | None = self.RI.update(can_capnp_to_list(can_strs)) + self.sm.update(0) can_rcv_valid = len(can_strs) > 0 @@ -175,9 +181,9 @@ class Car: CS.vCruise = float(self.v_cruise_helper.v_cruise_kph) CS.vCruiseCluster = float(self.v_cruise_helper.v_cruise_cluster_kph) - return CS + return CS, RD - def update_events(self, CS: car.CarState): + def update_events(self, CS: car.CarState, RD: structs.RadarData | None): self.events.clear() CS.events = self.car_events.update(self.CI.CS, self.CS_prev, self.CI.CC, self.CC_prev).to_msg() @@ -196,9 +202,12 @@ class Car: (CS.regenBraking and (not self.CS_prev.regenBraking or not CS.standstill)): self.events.add(EventName.pedalPressed) + if RD is not None and len(RD.errors): + self.events.add(EventName.radarFault) + CS.events = self.events.to_msg() - def state_publish(self, CS: car.CarState): + def state_publish(self, CS: car.CarState, RD: structs.RadarData | None): """carState and carParams publish loop""" # carParams - logged every 50 seconds (> 1 per segment) @@ -222,6 +231,12 @@ class Car: cs_send.carState.cumLagMs = -self.rk.remaining * 1000. self.pm.send('carState', cs_send) + if RD is not None: + tracks_msg = messaging.new_message('liveTracks') + tracks_msg.valid = CS.canValid and len(RD.errors) == 0 + tracks_msg.liveTracks = convert_to_capnp(RD) + self.pm.send('liveTracks', tracks_msg) + def controls_update(self, CS: car.CarState, CC: car.CarControl): """control update loop, driven by carControl""" @@ -241,14 +256,14 @@ class Car: self.CC_prev = CC def step(self): - CS = self.state_update() + CS, RD = self.state_update() - self.update_events(CS) + self.update_events(CS, RD) if not self.sm['carControl'].enabled and self.events.contains(ET.ENABLE): self.v_cruise_helper.initialize_v_cruise(CS, self.experimental_mode) - self.state_publish(CS) + self.state_publish(CS, RD) initialized = (not any(e.name == EventName.controlsInitializing for e in self.sm['onroadEvents']) and self.sm.seen['onroadEvents']) diff --git a/selfdrive/car/helpers.py b/selfdrive/car/helpers.py index f4d8993468..75e1c66d24 100644 --- a/selfdrive/car/helpers.py +++ b/selfdrive/car/helpers.py @@ -35,7 +35,7 @@ def asdictref(obj) -> dict[str, Any]: return _asdictref_inner(obj) -def convert_to_capnp(struct: structs.CarParams | structs.CarState | structs.CarControl.Actuators) -> capnp.lib.capnp._DynamicStructBuilder: +def convert_to_capnp(struct: structs.CarParams | structs.CarState | structs.CarControl.Actuators | structs.RadarData) -> capnp.lib.capnp._DynamicStructBuilder: struct_dict = asdictref(struct) if isinstance(struct, structs.CarParams): @@ -51,6 +51,8 @@ def convert_to_capnp(struct: structs.CarParams | structs.CarState | structs.CarC struct_capnp = car.CarState.new_message(**struct_dict) elif isinstance(struct, structs.CarControl.Actuators): struct_capnp = car.CarControl.Actuators.new_message(**struct_dict) + elif isinstance(struct, structs.RadarData): + struct_capnp = car.RadarData.new_message(**struct_dict) else: raise ValueError(f"Unsupported struct type: {type(struct)}") diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index e8df0a8310..0548f52764 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -448,7 +448,7 @@ class TestCarModelBase(unittest.TestCase): checks['cruiseState'] += CS.cruiseState.enabled != self.safety.get_cruise_engaged_prev() else: # Check for enable events on rising edge of controls allowed - card.update_events(CS) + card.update_events(CS, None) card.CS_prev = CS button_enable = (any(evt.enable for evt in CS.events) and not any(evt == EventName.pedalPressed for evt in card.events.names)) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 1a2136aa7a..14ea9ebb0d 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -96,7 +96,7 @@ class Controls: 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', 'testJoystick'] + self.camera_packets + self.sensor_packets + self.gps_packets, - ignore_alive=ignore, ignore_avg_freq=ignore+['radarState', 'testJoystick'], ignore_valid=['testJoystick', ], + ignore_alive=ignore, ignore_avg_freq=ignore+['testJoystick'], ignore_valid=['testJoystick', ], frequency=int(1/DT_CTRL)) self.joystick_mode = self.params.get_bool("JoystickDebugMode") @@ -301,7 +301,7 @@ class Controls: self.events.add(EventName.cameraFrameRate) if not REPLAY and self.rk.lagging: self.events.add(EventName.controlsdLagging) - if len(self.sm['radarState'].radarErrors) or ((not self.rk.lagging or REPLAY) and not self.sm.all_checks(['radarState'])): + if not self.sm.valid['radarState']: self.events.add(EventName.radarFault) if not self.sm.valid['pandaStates']: self.events.add(EventName.usbError) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index f3aa099bfb..f577025fa4 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -1,18 +1,15 @@ #!/usr/bin/env python3 -import importlib import math from collections import deque from typing import Any import capnp from cereal import messaging, log, car -from opendbc.car import structs from openpilot.common.numpy_fast import interp from openpilot.common.params import Params -from openpilot.common.realtime import DT_CTRL, Ratekeeper, Priority, config_realtime_process +from openpilot.common.realtime import DT_MDL, Priority, config_realtime_process from openpilot.common.swaglog import cloudlog from openpilot.common.simple_kalman import KF1D -from openpilot.selfdrive.pandad import can_capnp_to_list # Default lead acceleration decay set to 50% at 1s @@ -194,14 +191,14 @@ def get_lead(v_ego: float, ready: bool, tracks: dict[int, Track], lead_msg: capn class RadarD: - def __init__(self, radar_ts: float, delay: int = 0): + def __init__(self, delay: float = 0.0): self.current_time = 0.0 self.tracks: dict[int, Track] = {} - self.kalman_params = KalmanParams(radar_ts) + self.kalman_params = KalmanParams(DT_MDL) self.v_ego = 0.0 - self.v_ego_hist = deque([0.0], maxlen=delay+1) + self.v_ego_hist = deque([0.0], maxlen=int(round(delay / DT_MDL))+1) self.last_v_ego_frame = -1 self.radar_state: capnp._DynamicStructBuilder | None = None @@ -209,7 +206,7 @@ class RadarD: self.ready = False - def update(self, sm: messaging.SubMaster, rr: structs.RadarData): + def update(self, sm: messaging.SubMaster, rr: car.RadarData): self.ready = sm.seen['modelV2'] self.current_time = 1e-9*max(sm.logMonoTime.values()) @@ -255,27 +252,14 @@ class RadarD: self.radar_state.leadOne = get_lead(self.v_ego, self.ready, self.tracks, leads_v3[0], model_v_ego, low_speed_override=True) self.radar_state.leadTwo = get_lead(self.v_ego, self.ready, self.tracks, leads_v3[1], model_v_ego, low_speed_override=False) - def publish(self, pm: messaging.PubMaster, lag_ms: float): + def publish(self, pm: messaging.PubMaster): assert self.radar_state is not None radar_msg = messaging.new_message("radarState") radar_msg.valid = self.radar_state_valid radar_msg.radarState = self.radar_state - radar_msg.radarState.cumLagMs = lag_ms pm.send("radarState", radar_msg) - # publish tracks for UI debugging (keep last) - tracks_msg = messaging.new_message('liveTracks', len(self.tracks)) - tracks_msg.valid = self.radar_state_valid - for index, tid in enumerate(sorted(self.tracks.keys())): - tracks_msg.liveTracks[index] = { - "trackId": tid, - "dRel": float(self.tracks[tid].dRel), - "yRel": float(self.tracks[tid].yRel), - "vRel": float(self.tracks[tid].vRel), - } - pm.send('liveTracks', tracks_msg) - # fuses camera and radar data for best lead detection def main() -> None: @@ -286,31 +270,17 @@ def main() -> None: CP = messaging.log_from_bytes(Params().get("CarParams", block=True), car.CarParams) cloudlog.info("radard got CarParams") - # import the radar from the fingerprint - cloudlog.info("radard is importing %s", CP.carName) - RadarInterface = importlib.import_module(f'opendbc.car.{CP.carName}.radar_interface').RadarInterface - # *** setup messaging - can_sock = messaging.sub_sock('can') - sm = messaging.SubMaster(['modelV2', 'carState'], frequency=int(1./DT_CTRL)) - pm = messaging.PubMaster(['radarState', 'liveTracks']) + sm = messaging.SubMaster(['modelV2', 'carState', 'liveTracks'], poll='modelV2') + pm = messaging.PubMaster(['radarState']) - RI = RadarInterface(CP) - - rk = Ratekeeper(1.0 / CP.radarTimeStep, print_delay_threshold=None) - RD = RadarD(CP.radarTimeStep, RI.delay) + RD = RadarD(CP.radarDelay) while 1: - can_strings = messaging.drain_sock_raw(can_sock, wait_for_one=True) - rr: structs.RadarData | None = RI.update(can_capnp_to_list(can_strings)) - sm.update(0) - if rr is None: - continue - - RD.update(sm, rr) - RD.publish(pm, -rk.remaining*1000.0) + sm.update() - rk.monitor_time() + RD.update(sm, sm['liveTracks']) + RD.publish(pm) if __name__ == "__main__": diff --git a/selfdrive/controls/tests/test_leads.py b/selfdrive/controls/tests/test_leads.py index 4b98628bf6..89582d1e64 100644 --- a/selfdrive/controls/tests/test_leads.py +++ b/selfdrive/controls/tests/test_leads.py @@ -11,19 +11,21 @@ class TestLeads: def single_iter_pkg(): # single iter package, with meaningless cans and empty carState/modelV2 msgs = [] - for _ in range(5): + for _ in range(500): can = messaging.new_message("can", 1) cs = messaging.new_message("carState") + cp = messaging.new_message("carParams") msgs.append(can.as_reader()) msgs.append(cs.as_reader()) + msgs.append(cp.as_reader()) model = messaging.new_message("modelV2") msgs.append(model.as_reader()) return msgs msgs = [m for _ in range(3) for m in single_iter_pkg()] - out = replay_process_with_name("radard", msgs, fingerprint=TOYOTA.TOYOTA_COROLLA_TSS2) - states = [m for m in out if m.which() == "radarState"] - failures = [not state.valid and len(state.radarState.radarErrors) for state in states] + out = replay_process_with_name("card", msgs, fingerprint=TOYOTA.TOYOTA_COROLLA_TSS2) + states = [m for m in out if m.which() == "liveTracks"] + failures = [not state.valid and len(state.liveTracks.errors) for state in states] assert len(states) == 0 or all(failures) diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index 07979a06cc..723a9ff5b3 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -1,6 +1,6 @@ from collections import defaultdict -from cereal import messaging +from cereal import messaging, car from opendbc.car.fingerprints import MIGRATION from opendbc.car.toyota.values import EPS_SCALE from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_encode_index @@ -17,6 +17,7 @@ def migrate_all(lr, manager_states=False, panda_states=False, camera_states=Fals msgs = migrate_carOutput(msgs) msgs = migrate_controlsState(msgs) msgs = migrate_liveLocationKalman(msgs) + msgs = migrate_liveTracks(msgs) if manager_states: msgs = migrate_managerState(msgs) if panda_states: @@ -28,6 +29,35 @@ def migrate_all(lr, manager_states=False, panda_states=False, camera_states=Fals return msgs +def migrate_liveTracks(lr): + all_msgs = [] + for msg in lr: + if msg.which() != "liveTracksDEPRECATED": + all_msgs.append(msg) + continue + + new_msg = messaging.new_message('liveTracks') + new_msg.valid = msg.valid + new_msg.logMonoTime = msg.logMonoTime + + pts = [] + for track in msg.liveTracksDEPRECATED: + pt = car.RadarData.RadarPoint() + pt.trackId = track.trackId + + pt.dRel = track.dRel + pt.yRel = track.yRel + pt.vRel = track.vRel + pt.aRel = track.aRel + pt.measured = True + pts.append(pt) + + new_msg.liveTracks.points = pts + all_msgs.append(new_msg.as_reader()) + + return all_msgs + + def migrate_liveLocationKalman(lr): # migration needed only for routes before livePose if any(msg.which() == 'livePose' for msg in lr): diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 3a933fefc9..78008ca909 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -480,7 +480,7 @@ CONFIGS = [ ProcessConfig( proc_name="card", pubs=["pandaStates", "carControl", "onroadEvents", "can"], - subs=["sendcan", "carState", "carParams", "carOutput"], + subs=["sendcan", "carState", "carParams", "carOutput", "liveTracks"], ignore=["logMonoTime", "carState.cumLagMs"], init_callback=card_fingerprint_callback, should_recv_callback=card_rcv_callback, @@ -490,12 +490,11 @@ CONFIGS = [ ), ProcessConfig( proc_name="radard", - pubs=["can", "carState", "modelV2"], - subs=["radarState", "liveTracks"], - ignore=["logMonoTime", "radarState.cumLagMs"], + pubs=["liveTracks", "carState", "modelV2"], + subs=["radarState"], + ignore=["logMonoTime"], init_callback=get_car_params_callback, - should_recv_callback=MessageBasedRcvCallback("can"), - main_pub="can", + should_recv_callback=FrequencyBasedRcvCallback("modelV2"), ), ProcessConfig( proc_name="plannerd", diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 90d6c85cb9..1e3ef33c7e 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -fb0827a00b21b97733f8385cf7ce87a21a526f4c \ No newline at end of file +2b842a259e15f4b8679f16a14de405b5df06ae1f \ No newline at end of file diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 9dd781e89d..b3e66444a7 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -36,7 +36,7 @@ MAX_TOTAL_CPU = 260. # total for all 8 cores PROCS = { # Baseline CPU usage by process "selfdrive.controls.controlsd": 32.0, - "selfdrive.car.card": 26.0, + "selfdrive.car.card": 31.0, "./loggerd": 14.0, "./encoderd": 17.0, "./camerad": 14.5, @@ -44,7 +44,7 @@ PROCS = { "./ui": 18.0, "selfdrive.locationd.paramsd": 9.0, "./sensord": 7.0, - "selfdrive.controls.radard": 7.0, + "selfdrive.controls.radard": 2.0, "selfdrive.modeld.modeld": 13.0, "selfdrive.modeld.dmonitoringmodeld": 8.0, "system.hardware.hardwared": 3.87, From f6d5f8fccf5994e24591edc444e31d71d6243916 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 6 Sep 2024 11:40:06 -0700 Subject: [PATCH 007/214] ui: controls -> selfdrive (#33487) * ui: controls -> selfdrive * lil more --- selfdrive/ui/qt/onroad/alerts.cc | 36 +++++++++++----------- selfdrive/ui/qt/onroad/annotated_camera.cc | 4 +-- selfdrive/ui/soundd.py | 20 ++++++------ selfdrive/ui/tests/test_soundd.py | 10 +++--- selfdrive/ui/translations/main_ar.ts | 16 +++++----- selfdrive/ui/translations/main_de.ts | 8 ++--- selfdrive/ui/translations/main_es.ts | 16 +++++----- selfdrive/ui/translations/main_fr.ts | 8 ++--- selfdrive/ui/translations/main_ja.ts | 8 ++--- selfdrive/ui/translations/main_ko.ts | 16 +++++----- selfdrive/ui/translations/main_pt-BR.ts | 16 +++++----- selfdrive/ui/translations/main_th.ts | 16 +++++----- selfdrive/ui/translations/main_tr.ts | 8 ++--- selfdrive/ui/translations/main_zh-CHS.ts | 16 +++++----- selfdrive/ui/translations/main_zh-CHT.ts | 16 +++++----- 15 files changed, 107 insertions(+), 107 deletions(-) diff --git a/selfdrive/ui/qt/onroad/alerts.cc b/selfdrive/ui/qt/onroad/alerts.cc index d5d2e6c0de..0236e20f16 100644 --- a/selfdrive/ui/qt/onroad/alerts.cc +++ b/selfdrive/ui/qt/onroad/alerts.cc @@ -19,34 +19,34 @@ void OnroadAlerts::clear() { } OnroadAlerts::Alert OnroadAlerts::getAlert(const SubMaster &sm, uint64_t started_frame) { - const cereal::SelfdriveState::Reader &cs = sm["selfdriveState"].getSelfdriveState(); - const uint64_t controls_frame = sm.rcv_frame("selfdriveState"); + const cereal::SelfdriveState::Reader &ss = sm["selfdriveState"].getSelfdriveState(); + const uint64_t selfdrive_frame = sm.rcv_frame("selfdriveState"); Alert a = {}; - if (controls_frame >= started_frame) { // Don't get old alert. - a = {cs.getAlertText1().cStr(), cs.getAlertText2().cStr(), - cs.getAlertType().cStr(), cs.getAlertSize(), cs.getAlertStatus()}; + if (selfdrive_frame >= started_frame) { // Don't get old alert. + a = {ss.getAlertText1().cStr(), ss.getAlertText2().cStr(), + ss.getAlertType().cStr(), ss.getAlertSize(), ss.getAlertStatus()}; } if (!sm.updated("selfdriveState") && (sm.frame - started_frame) > 5 * UI_FREQ) { - const int CONTROLS_TIMEOUT = 5; - const int controls_missing = (nanos_since_boot() - sm.rcv_time("selfdriveState")) / 1e9; + const int SELFDRIVE_STATE_TIMEOUT = 5; + const int ss_missing = (nanos_since_boot() - sm.rcv_time("selfdriveState")) / 1e9; - // Handle controls timeout - if (controls_frame < started_frame) { + // Handle selfdrive timeout + if (selfdrive_frame < started_frame) { // car is started, but selfdriveState hasn't been seen at all - a = {tr("openpilot Unavailable"), tr("Waiting for controls to start"), - "controlsWaiting", cereal::SelfdriveState::AlertSize::MID, + a = {tr("openpilot Unavailable"), tr("Waiting to start"), + "selfdriveWaiting", cereal::SelfdriveState::AlertSize::MID, cereal::SelfdriveState::AlertStatus::NORMAL}; - } else if (controls_missing > CONTROLS_TIMEOUT && !Hardware::PC()) { - // car is started, but controls is lagging or died - if (cs.getEnabled() && (controls_missing - CONTROLS_TIMEOUT) < 10) { - a = {tr("TAKE CONTROL IMMEDIATELY"), tr("Controls Unresponsive"), - "controlsUnresponsive", cereal::SelfdriveState::AlertSize::FULL, + } else if (ss_missing > SELFDRIVE_STATE_TIMEOUT && !Hardware::PC()) { + // car is started, but selfdrive is lagging or died + if (ss.getEnabled() && (ss_missing - SELFDRIVE_STATE_TIMEOUT) < 10) { + a = {tr("TAKE CONTROL IMMEDIATELY"), tr("System Unresponsive"), + "selfdriveUnresponsive", cereal::SelfdriveState::AlertSize::FULL, cereal::SelfdriveState::AlertStatus::CRITICAL}; } else { - a = {tr("Controls Unresponsive"), tr("Reboot Device"), - "controlsUnresponsivePermanent", cereal::SelfdriveState::AlertSize::MID, + a = {tr("System Unresponsive"), tr("Reboot Device"), + "selfdriveUnresponsivePermanent", cereal::SelfdriveState::AlertSize::MID, cereal::SelfdriveState::AlertStatus::NORMAL}; } } diff --git a/selfdrive/ui/qt/onroad/annotated_camera.cc b/selfdrive/ui/qt/onroad/annotated_camera.cc index cc9940f275..b538f19dde 100644 --- a/selfdrive/ui/qt/onroad/annotated_camera.cc +++ b/selfdrive/ui/qt/onroad/annotated_camera.cc @@ -25,13 +25,13 @@ void AnnotatedCameraWidget::updateState(const UIState &s) { const int SET_SPEED_NA = 255; const SubMaster &sm = *(s.sm); - const bool cs_alive = sm.alive("controlsState"); + const bool cs_alive = sm.alive("carState"); const auto cs = sm["controlsState"].getControlsState(); const auto car_state = sm["carState"].getCarState(); is_metric = s.scene.is_metric; - // Handle older routes where vCruiseCluster is not set + // Handle older routes where vCruise was in controlsState float v_cruise = car_state.getVCruiseCluster() == 0.0 ? cs.getVCruiseDEPRECATED() : car_state.getVCruiseCluster(); setSpeed = cs_alive ? v_cruise : SET_SPEED_NA; is_cruise_set = setSpeed > 0 && (int)setSpeed != SET_SPEED_NA; diff --git a/selfdrive/ui/soundd.py b/selfdrive/ui/soundd.py index 4055fcfd35..3cd6ae5820 100644 --- a/selfdrive/ui/soundd.py +++ b/selfdrive/ui/soundd.py @@ -17,7 +17,7 @@ SAMPLE_RATE = 48000 SAMPLE_BUFFER = 4096 # (approx 100ms) MAX_VOLUME = 1.0 MIN_VOLUME = 0.1 -CONTROLS_TIMEOUT = 5 # 5 seconds +SELFDRIVE_STATE_TIMEOUT = 5 # 5 seconds FILTER_DT = 1. / (micd.SAMPLE_RATE / micd.FFT_SAMPLES) AMBIENT_DB = 30 # DB where MIN_VOLUME is applied @@ -40,11 +40,11 @@ sound_list: dict[int, tuple[str, int | None, float]] = { AudibleAlert.warningImmediate: ("warning_immediate.wav", None, MAX_VOLUME), } -def check_controls_timeout_alert(sm): - controls_missing = time.monotonic() - sm.recv_time['selfdriveState'] +def check_selfdrive_timeout_alert(sm): + ss_missing = time.monotonic() - sm.recv_time['selfdriveState'] - if controls_missing > CONTROLS_TIMEOUT: - if sm['selfdriveState'].enabled and (controls_missing - CONTROLS_TIMEOUT) < 10: + if ss_missing > SELFDRIVE_STATE_TIMEOUT: + if sm['selfdriveState'].enabled and (ss_missing - SELFDRIVE_STATE_TIMEOUT) < 10: return True return False @@ -58,7 +58,7 @@ class Soundd: self.current_volume = MIN_VOLUME self.current_sound_frame = 0 - self.controls_timeout_alert = False + self.selfdrive_timeout_alert = False self.spl_filter_weighted = FirstOrderFilter(0, 2.5, FILTER_DT, initialized=False) @@ -114,12 +114,12 @@ class Soundd: if sm.updated['selfdriveState']: new_alert = sm['selfdriveState'].alertSound.raw self.update_alert(new_alert) - elif check_controls_timeout_alert(sm): + elif check_selfdrive_timeout_alert(sm): self.update_alert(AudibleAlert.warningImmediate) - self.controls_timeout_alert = True - elif self.controls_timeout_alert: + self.selfdrive_timeout_alert = True + elif self.selfdrive_timeout_alert: self.update_alert(AudibleAlert.none) - self.controls_timeout_alert = False + self.selfdrive_timeout_alert = False def calculate_volume(self, weighted_db): volume = ((weighted_db - AMBIENT_DB) / DB_SCALE) * (MAX_VOLUME - MIN_VOLUME) + MIN_VOLUME diff --git a/selfdrive/ui/tests/test_soundd.py b/selfdrive/ui/tests/test_soundd.py index f40af8696a..a9da8455eb 100644 --- a/selfdrive/ui/tests/test_soundd.py +++ b/selfdrive/ui/tests/test_soundd.py @@ -1,7 +1,7 @@ from cereal import car from cereal import messaging from cereal.messaging import SubMaster, PubMaster -from openpilot.selfdrive.ui.soundd import CONTROLS_TIMEOUT, check_controls_timeout_alert +from openpilot.selfdrive.ui.soundd import SELFDRIVE_STATE_TIMEOUT, check_selfdrive_timeout_alert import time @@ -9,7 +9,7 @@ AudibleAlert = car.CarControl.HUDControl.AudibleAlert class TestSoundd: - def test_check_controls_timeout_alert(self): + def test_check_selfdrive_timeout_alert(self): sm = SubMaster(['selfdriveState']) pm = PubMaster(['selfdriveState']) @@ -23,13 +23,13 @@ class TestSoundd: sm.update(0) - assert not check_controls_timeout_alert(sm) + assert not check_selfdrive_timeout_alert(sm) - for _ in range(CONTROLS_TIMEOUT * 110): + for _ in range(SELFDRIVE_STATE_TIMEOUT * 110): sm.update(0) time.sleep(0.01) - assert check_controls_timeout_alert(sm) + assert check_selfdrive_timeout_alert(sm) # TODO: add test with micd for checking that soundd actually outputs sounds diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index 0116f3c152..ebfcd1ec0b 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -418,22 +418,22 @@ openpilot Unavailable openpilot غير متوفر - - Waiting for controls to start - في انتظار بدء عناصر التحكم - TAKE CONTROL IMMEDIATELY تحكم على الفور - - Controls Unresponsive - الضوابط غير مستجيبة - Reboot Device إعادة التشغيل + + Waiting to start + + + + System Unresponsive + + PairingPopup diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index 48180eef92..4e8bbe0a18 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -414,19 +414,19 @@ - Waiting for controls to start + TAKE CONTROL IMMEDIATELY - TAKE CONTROL IMMEDIATELY + Reboot Device - Controls Unresponsive + Waiting to start - Reboot Device + System Unresponsive diff --git a/selfdrive/ui/translations/main_es.ts b/selfdrive/ui/translations/main_es.ts index 150c00d117..083d2c25e1 100644 --- a/selfdrive/ui/translations/main_es.ts +++ b/selfdrive/ui/translations/main_es.ts @@ -414,22 +414,22 @@ openpilot Unavailable openpilot no disponible - - Waiting for controls to start - Esperando que los controles inicien - TAKE CONTROL IMMEDIATELY TOME CONTROL INMEDIATAMENTE - - Controls Unresponsive - Controles no responden - Reboot Device Reiniciar Dispositivo + + Waiting to start + + + + System Unresponsive + + PairingPopup diff --git a/selfdrive/ui/translations/main_fr.ts b/selfdrive/ui/translations/main_fr.ts index a678742f74..16adcaa081 100644 --- a/selfdrive/ui/translations/main_fr.ts +++ b/selfdrive/ui/translations/main_fr.ts @@ -415,19 +415,19 @@ - Waiting for controls to start + TAKE CONTROL IMMEDIATELY - TAKE CONTROL IMMEDIATELY + Reboot Device - Controls Unresponsive + Waiting to start - Reboot Device + System Unresponsive diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 096fa95091..daac99ce09 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -413,19 +413,19 @@ - Waiting for controls to start + TAKE CONTROL IMMEDIATELY - TAKE CONTROL IMMEDIATELY + Reboot Device - Controls Unresponsive + Waiting to start - Reboot Device + System Unresponsive diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index df012d3e85..9541067119 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -413,22 +413,22 @@ openpilot Unavailable 오픈파일럿을 사용할수없습니다 - - Waiting for controls to start - 프로세스가 준비중입니다 - TAKE CONTROL IMMEDIATELY 핸들을 잡아주세요 - - Controls Unresponsive - 프로세스가 응답하지않습니다 - Reboot Device 장치를 재부팅하세요 + + Waiting to start + + + + System Unresponsive + + PairingPopup diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 1500f07e63..e92e7748b3 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -414,22 +414,22 @@ openpilot Unavailable openpilot Indisponível - - Waiting for controls to start - Aguardando controles para iniciar - TAKE CONTROL IMMEDIATELY ASSUMA IMEDIATAMENTE - - Controls Unresponsive - Controles Não Respondem - Reboot Device Reinicie o Dispositivo + + Waiting to start + + + + System Unresponsive + + PairingPopup diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index bae326d532..d0dea811c6 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -413,22 +413,22 @@ openpilot Unavailable openpilot ไม่สามารถใช้งานได้ - - Waiting for controls to start - กำลังรอให้ controls เริ่มทำงาน - TAKE CONTROL IMMEDIATELY เข้าควบคุมรถเดี๋ยวนี้ - - Controls Unresponsive - Controls ไม่ตอบสนอง - Reboot Device รีบูตอุปกรณ์ + + Waiting to start + + + + System Unresponsive + + PairingPopup diff --git a/selfdrive/ui/translations/main_tr.ts b/selfdrive/ui/translations/main_tr.ts index 72148807d4..746425cb4e 100644 --- a/selfdrive/ui/translations/main_tr.ts +++ b/selfdrive/ui/translations/main_tr.ts @@ -413,19 +413,19 @@ - Waiting for controls to start + TAKE CONTROL IMMEDIATELY - TAKE CONTROL IMMEDIATELY + Reboot Device - Controls Unresponsive + Waiting to start - Reboot Device + System Unresponsive diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 976b58b31d..ec1884521b 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -413,22 +413,22 @@ openpilot Unavailable 无法使用 openpilot - - Waiting for controls to start - 等待控制服务啟動 - TAKE CONTROL IMMEDIATELY 立即接管 - - Controls Unresponsive - 控制服务无响应 - Reboot Device 重启设备 + + Waiting to start + + + + System Unresponsive + + PairingPopup diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index de8d3ff701..835a0af30f 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -413,22 +413,22 @@ openpilot Unavailable 無法使用 openpilot - - Waiting for controls to start - 等待操控服務開始 - TAKE CONTROL IMMEDIATELY 立即接管 - - Controls Unresponsive - 操控服務沒有反應 - Reboot Device 請重新啟裝置 + + Waiting to start + + + + System Unresponsive + + PairingPopup From e80c27ffdffacad06811b11a5af959eafe134166 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 6 Sep 2024 13:29:20 -0700 Subject: [PATCH 008/214] liveTracks: don't check carState for valid CAN (#33489) * no need to check CS.canValid * update refs --- selfdrive/car/card.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 541a7c44ae..d883ac1f21 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -233,7 +233,7 @@ class Car: if RD is not None: tracks_msg = messaging.new_message('liveTracks') - tracks_msg.valid = CS.canValid and len(RD.errors) == 0 + tracks_msg.valid = len(RD.errors) == 0 tracks_msg.liveTracks = convert_to_capnp(RD) self.pm.send('liveTracks', tracks_msg) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 1e3ef33c7e..3a90b7a5fb 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -2b842a259e15f4b8679f16a14de405b5df06ae1f \ No newline at end of file +7f9255ef41d0257f8665d441c666cb2721cdf3ee \ No newline at end of file From c45e2731ae9923c00cac2fc9850dc7f188b887b0 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 7 Sep 2024 04:38:38 +0800 Subject: [PATCH 009/214] CI: integrate pairing device and prime user widgets into UI report (#33486) add prime widgets --- .github/workflows/ui_preview.yaml | 4 ++++ selfdrive/ui/tests/test_ui/run.py | 30 +++++++++++++++++++++--------- 2 files changed, 25 insertions(+), 9 deletions(-) diff --git a/.github/workflows/ui_preview.yaml b/.github/workflows/ui_preview.yaml index c6d70e9ceb..d4dcce5f3f 100644 --- a/.github/workflows/ui_preview.yaml +++ b/.github/workflows/ui_preview.yaml @@ -82,6 +82,10 @@ jobs: + + + + diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index c8b14dad95..2bf30d7b90 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -12,7 +12,7 @@ import time from cereal import messaging, log from msgq.visionipc import VisionIpcServer, VisionStreamType -from cereal.messaging import SubMaster, PubMaster +from cereal.messaging import PubMaster from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params from openpilot.common.prefix import OpenpilotPrefix @@ -95,6 +95,7 @@ def setup_onroad_alert(click, pm: PubMaster, text1, text2, size, status=log.Self cs.alertStatus = status cs.alertType = "test_onroad_alert" pm.send('selfdriveState', dat) + time.sleep(UI_DELAY) def setup_onroad_alert_small(click, pm: PubMaster): setup_onroad_alert(click, pm, 'This is a small alert message', '', log.SelfdriveState.AlertSize.small) @@ -123,9 +124,14 @@ def setup_update_available(click, pm: PubMaster): setup_settings_device(click, pm) click(240, 216) +def setup_pair_device(click, pm: PubMaster): + click(1950, 435) + click(1800, 900) CASES = { "homescreen": setup_homescreen, + "prime": setup_homescreen, + "pair_device": setup_pair_device, "settings_device": setup_settings_device, "onroad": setup_onroad, "onroad_sidebar": setup_onroad_sidebar, @@ -152,13 +158,12 @@ class TestUI: sys.modules["mouseinfo"] = False def setup(self): - Params().put("DongleId", "123456789012345") - self.sm = SubMaster(["uiDebug"]) self.pm = PubMaster(list(DATA.keys())) - while not self.sm.valid["uiDebug"]: - self.sm.update(1) - time.sleep(UI_DELAY) # wait a bit more for the UI to start rendering - self.pm.send('deviceState', DATA['deviceState']) + DATA['deviceState'].deviceState.networkType = log.DeviceState.NetworkType.wifi + for _ in range(10): + self.pm.send('deviceState', DATA['deviceState']) + DATA['deviceState'].clear_write_flag() + time.sleep(0.05) try: self.ui = pywinctl.getWindowsWithTitle("ui")[0] except Exception as e: @@ -231,8 +236,15 @@ def create_screenshots(): t = TestUI() - with OpenpilotPrefix(): - for name, setup in CASES.items(): + for name, setup in CASES.items(): + with OpenpilotPrefix(): + params = Params() + params.put("DongleId", "123456789012345") + if name == 'prime': + params.put('PrimeType', '1') + elif name == 'pair_device': + params.put('ApiCache_Device', '{"is_paired":0, "prime_type":-1}') + t.test_ui(name, setup) if __name__ == "__main__": From 51ebf44f486ea9c26e9328c8d43fbd01ea68f53c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 7 Sep 2024 04:51:19 +0800 Subject: [PATCH 010/214] card: remove redundant CAN data conversion (#33488) * remove redundant CAN data conversion * 1 less % * rename --------- Co-authored-by: Shane Smiskol --- selfdrive/car/card.py | 7 ++++--- selfdrive/test/test_onroad.py | 2 +- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index d883ac1f21..6494074458 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -155,15 +155,16 @@ class Car: def state_update(self) -> tuple[car.CarState, structs.RadarData | None]: """carState update loop, driven by can""" - # Update carState from CAN can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) - CS = convert_to_capnp(self.CI.update(can_capnp_to_list(can_strs))) + can_list = can_capnp_to_list(can_strs) + # Update carState from CAN + CS = convert_to_capnp(self.CI.update(can_list)) if self.CP.carName == 'mock': CS = self.mock_carstate.update(CS) # Update radar tracks from CAN - RD: structs.RadarData | None = self.RI.update(can_capnp_to_list(can_strs)) + RD: structs.RadarData | None = self.RI.update(can_list) self.sm.update(0) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index b3e66444a7..7fe26b739f 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -36,7 +36,7 @@ MAX_TOTAL_CPU = 260. # total for all 8 cores PROCS = { # Baseline CPU usage by process "selfdrive.controls.controlsd": 32.0, - "selfdrive.car.card": 31.0, + "selfdrive.car.card": 30.0, "./loggerd": 14.0, "./encoderd": 17.0, "./camerad": 14.5, From e459cee1e71508404117cfc63a92a7461e56a686 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 6 Sep 2024 15:30:14 -0700 Subject: [PATCH 011/214] Setup driverAssistance service (#33495) * Move LDW and FCW to driverAssitance service * move ldw * cleanup --- cereal/log.capnp | 9 +++++++++ cereal/services.py | 1 + selfdrive/controls/controlsd.py | 19 +++++++------------ selfdrive/controls/plannerd.py | 15 ++++++++++----- selfdrive/test/process_replay/migration.py | 10 ++++++++++ .../test/process_replay/process_replay.py | 4 ++-- selfdrive/test/process_replay/ref_commit | 2 +- 7 files changed, 40 insertions(+), 20 deletions(-) diff --git a/cereal/log.capnp b/cereal/log.capnp index b715d14220..75ca7dd941 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -1096,6 +1096,14 @@ struct AndroidLogEntry { message @6 :Text; } +struct DriverAssistance { + # Lane Departure Warnings + leftLaneDeparture @0 :Bool; + rightLaneDeparture @1 :Bool; + + # FCW, AEB, etc. will go here +} + struct LongitudinalPlan @0xe00b5b3eba12876c { modelMonoTime @9 :UInt64; hasLead @7 :Bool; @@ -2342,6 +2350,7 @@ struct Event { carControl @23 :Car.CarControl; carOutput @127 :Car.CarOutput; longitudinalPlan @24 :LongitudinalPlan; + driverAssistance @132 :DriverAssistance; ubloxGnss @34 :UbloxGnss; ubloxRaw @39 :Data; qcomGnss @31 :QcomGnss; diff --git a/cereal/services.py b/cereal/services.py index b50e47be60..926461aec2 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -40,6 +40,7 @@ _services: dict[str, tuple] = { "carControl": (True, 100., 10), "carOutput": (True, 100., 10), "longitudinalPlan": (True, 20., 10), + "driverAssistance": (True, 20., 20), "procLog": (True, 0.5, 15), "gpsLocationExternal": (True, 10., 10), "gpsLocation": (True, 1., 1), diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 14ea9ebb0d..a7fac2a1ff 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -22,7 +22,6 @@ from openpilot.common.gps import get_gps_location_service from opendbc.car.car_helpers import get_car_interface from openpilot.selfdrive.controls.lib.alertmanager import AlertManager, set_offroad_alert from openpilot.selfdrive.controls.lib.drive_helpers import clip_curvature, get_startup_event -from openpilot.selfdrive.controls.lib.ldw import LaneDepartureWarning from openpilot.selfdrive.controls.lib.events import Events, ET from openpilot.selfdrive.controls.lib.latcontrol import LatControl, MIN_LATERAL_CONTROL_SPEED from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID @@ -95,7 +94,7 @@ class Controls: self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', - 'testJoystick'] + self.camera_packets + self.sensor_packets + self.gps_packets, + 'testJoystick', 'driverAssistance'] + self.camera_packets + self.sensor_packets + self.gps_packets, ignore_alive=ignore, ignore_avg_freq=ignore+['testJoystick'], ignore_valid=['testJoystick', ], frequency=int(1/DT_CTRL)) @@ -128,8 +127,6 @@ class Controls: self.LoC = LongControl(self.CP) self.VM = VehicleModel(self.CP) - self.ldw = LaneDepartureWarning() - self.LaC: LatControl if self.CP.steerControlType == car.CarParams.SteerControlType.angle: self.LaC = LatControlAngle(self.CP, self.CI) @@ -245,11 +242,9 @@ class Controls: self.events.add(EventName.calibrationInvalid) # Lane departure warning - if self.sm.valid['modelV2'] and CS.canValid: - self.ldw.update(self.sm.frame, self.sm['modelV2'], CS, self.CC_prev) - if self.is_ldw_enabled and self.sm['liveCalibration'].calStatus == log.LiveCalibrationData.Status.calibrated: - if self.ldw.warning: - self.events.add(EventName.ldw) + if self.is_ldw_enabled and self.sm.valid['driverAssistance']: + if self.sm['driverAssistance'].leftLaneDeparture or self.sm['driverAssistance'].rightLaneDeparture: + self.events.add(EventName.ldw) # Handle lane change if self.sm['modelV2'].meta.laneChangeState == LaneChangeState.preLaneChange: @@ -606,9 +601,9 @@ class Controls: hudControl.rightLaneVisible = True hudControl.leftLaneVisible = True - if self.sm.valid['modelV2'] and CS.canValid and self.is_ldw_enabled and self.sm['liveCalibration'].calStatus == log.LiveCalibrationData.Status.calibrated: - hudControl.leftLaneDepart = self.ldw.left - hudControl.rightLaneDepart = self.ldw.right + if self.is_ldw_enabled and self.sm.valid['driverAssistance']: + hudControl.leftLaneDepart = self.sm['driverAssistance'].leftLaneDeparture + hudControl.rightLaneDepart = self.sm['driverAssistance'].rightLaneDeparture if self.AM.current_alert: hudControl.visualAlert = self.AM.current_alert.visual_alert diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 9de70c767a..ae8301871d 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -3,11 +3,12 @@ from cereal import car from openpilot.common.params import Params from openpilot.common.realtime import Priority, config_realtime_process from openpilot.common.swaglog import cloudlog +from openpilot.selfdrive.controls.lib.ldw import LaneDepartureWarning from openpilot.selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner import cereal.messaging as messaging -def plannerd_thread(): +def main(): config_realtime_process(5, Priority.CTRL_LOW) cloudlog.info("plannerd is waiting for CarParams") @@ -15,8 +16,9 @@ def plannerd_thread(): CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) cloudlog.info("plannerd got CarParams: %s", CP.carName) + ldw = LaneDepartureWarning() longitudinal_planner = LongitudinalPlanner(CP) - pm = messaging.PubMaster(['longitudinalPlan']) + pm = messaging.PubMaster(['longitudinalPlan', 'driverAssistance']) sm = messaging.SubMaster(['carControl', 'carState', 'controlsState', 'radarState', 'modelV2', 'selfdriveState'], poll='modelV2', ignore_avg_freq=['radarState']) @@ -26,9 +28,12 @@ def plannerd_thread(): longitudinal_planner.update(sm) longitudinal_planner.publish(sm, pm) - -def main(): - plannerd_thread() + ldw.update(sm.frame, sm['modelV2'], sm['carState'], sm['carControl']) + msg = messaging.new_message('driverAssistance') + msg.valid = sm.all_checks(['carState', 'carControl', 'modelV2']) + msg.driverAssistance.leftLaneDeparture = ldw.left + msg.driverAssistance.rightLaneDeparture = ldw.right + pm.send('driverAssistance', msg) if __name__ == "__main__": diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index 723a9ff5b3..9c680ada9a 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -18,6 +18,7 @@ def migrate_all(lr, manager_states=False, panda_states=False, camera_states=Fals msgs = migrate_controlsState(msgs) msgs = migrate_liveLocationKalman(msgs) msgs = migrate_liveTracks(msgs) + msgs = migrate_driverAssistance(msgs) if manager_states: msgs = migrate_managerState(msgs) if panda_states: @@ -28,6 +29,15 @@ def migrate_all(lr, manager_states=False, panda_states=False, camera_states=Fals return msgs +def migrate_driverAssistance(lr): + all_msgs = [] + for msg in lr: + all_msgs.append(msg) + if msg.which() == 'longitudinalPlan': + all_msgs.append(messaging.new_message('driverAssistance', valid=True, logMonoTime=msg.logMonoTime).as_reader()) + if msg.which() == 'driverAssistance': + return lr + return all_msgs def migrate_liveTracks(lr): all_msgs = [] diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 78008ca909..39fec7b669 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -467,7 +467,7 @@ CONFIGS = [ "longitudinalPlan", "livePose", "liveParameters", "radarState", "modelV2", "driverCameraState", "roadCameraState", "wideRoadCameraState", "managerState", "testJoystick", "liveTorqueParameters", "accelerometer", "gyroscope", "carOutput", - "gpsLocationExternal", "gpsLocation", + "gpsLocationExternal", "gpsLocation", "driverAssistance" ], subs=["selfdriveState", "controlsState", "carControl", "onroadEvents"], ignore=["logMonoTime", "controlsState.cumLagMs"], @@ -499,7 +499,7 @@ CONFIGS = [ ProcessConfig( proc_name="plannerd", pubs=["modelV2", "carControl", "carState", "controlsState", "radarState", "selfdriveState"], - subs=["longitudinalPlan"], + subs=["longitudinalPlan", "driverAssistance"], ignore=["logMonoTime", "longitudinalPlan.processingDelay", "longitudinalPlan.solverExecutionTime"], init_callback=get_car_params_callback, should_recv_callback=FrequencyBasedRcvCallback("modelV2"), diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 3a90b7a5fb..9ff5403d3c 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -7f9255ef41d0257f8665d441c666cb2721cdf3ee \ No newline at end of file +fc1344b16b802cdb4ec542791f3b4d76a82da68b \ No newline at end of file From e04455cbaa2fc6679d44652835ec63b9939985da Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 6 Sep 2024 17:16:32 -0700 Subject: [PATCH 012/214] selfdrived: controlsd only does controls (#33485) * selfdrived * process replay * lil more * set the valids * rename that --- cereal/car.capnp | 4 +- cereal/log.capnp | 3 +- selfdrive/car/car_specific.py | 2 +- selfdrive/car/card.py | 4 +- selfdrive/controls/controlsd.py | 626 ++---------------- selfdrive/controls/lib/drive_helpers.py | 22 +- selfdrive/controls/tests/test_startup.py | 121 ---- selfdrive/debug/cycle_alerts.py | 4 +- selfdrive/monitoring/helpers.py | 2 +- .../lib => selfdrived}/alertmanager.py | 4 +- .../lib => selfdrived}/alerts_offroad.json | 0 .../{controls/lib => selfdrived}/events.py | 17 +- selfdrive/selfdrived/selfdrived.py | 518 +++++++++++++++ .../lib/selfdrive.py => selfdrived/state.py} | 2 +- .../tests/test_alertmanager.py | 4 +- .../tests/test_alerts.py | 6 +- .../tests/test_state_machine.py | 2 +- selfdrive/test/process_replay/compare_logs.py | 2 +- .../test/process_replay/process_replay.py | 29 +- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/process_replay/test_fuzzy.py | 2 +- .../test/process_replay/test_processes.py | 6 +- selfdrive/test/test_onroad.py | 6 +- selfdrive/test/test_time_to_onroad.py | 5 +- selfdrive/ui/qt/widgets/offroad_alerts.cc | 2 +- selfdrive/ui/tests/cycle_offroad_alerts.py | 4 +- selfdrive/ui/tests/test_ui/run.py | 2 +- selfdrive/ui/update_translations.py | 2 +- system/athena/registration.py | 2 +- system/camerad/snapshot/snapshot.py | 2 +- system/hardware/hardwared.py | 2 +- system/manager/process_config.py | 1 + system/updated/updated.py | 2 +- 33 files changed, 641 insertions(+), 771 deletions(-) delete mode 100644 selfdrive/controls/tests/test_startup.py rename selfdrive/{controls/lib => selfdrived}/alertmanager.py (91%) rename selfdrive/{controls/lib => selfdrived}/alerts_offroad.json (100%) rename selfdrive/{controls/lib => selfdrived}/events.py (98%) create mode 100755 selfdrive/selfdrived/selfdrived.py rename selfdrive/{controls/lib/selfdrive.py => selfdrived/state.py} (98%) rename selfdrive/{controls/lib => selfdrived}/tests/test_alertmanager.py (89%) rename selfdrive/{controls => selfdrived}/tests/test_alerts.py (94%) rename selfdrive/{controls => selfdrived}/tests/test_state_machine.py (97%) diff --git a/cereal/car.capnp b/cereal/car.capnp index 026aa7baa5..6da9c14c32 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -100,7 +100,7 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { cameraFrameRate @110; processNotRunning @95; dashcamMode @96; - controlsInitializing @98; + selfdriveInitializing @98; usbError @99; roadCameraError @100; driverCameraError @101; @@ -109,7 +109,7 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { cruiseMismatch @106; lkasDisabled @107; canBusMissing @111; - controlsdLagging @112; + selfdrivedLagging @112; resumeBlocked @113; steerTimeLimit @115; vehicleSensorsInvalid @116; diff --git a/cereal/log.capnp b/cereal/log.capnp index 75ca7dd941..258c1f7ab4 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -698,6 +698,7 @@ struct SelfdriveState { alertSize @6 :AlertSize; alertType @7 :Text; alertSound @8 :Car.CarControl.HUDControl.AudibleAlert; + alertHudVisual @12 :Car.CarControl.HUDControl.VisualAlert; # configurable driving settings experimentalMode @10 :Bool; @@ -726,7 +727,6 @@ struct SelfdriveState { } struct ControlsState @0x97ff69c53601abf1 { - cumLagMs @15 :Float32; longitudinalPlanMonoTime @28 :UInt64; lateralPlanMonoTime @50 :UInt64; @@ -880,6 +880,7 @@ struct ControlsState @0x97ff69c53601abf1 { vCruiseDEPRECATED @22 :Float32; # actual set speed vCruiseClusterDEPRECATED @63 :Float32; # set speed to display in the UI startMonoTimeDEPRECATED @48 :UInt64; + cumLagMsDEPRECATED @15 :Float32; } struct DrivingModelData { diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index 25a7defbbd..3984b66c63 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -5,7 +5,7 @@ from opendbc.car.interfaces import MAX_CTRL_SPEED, CarStateBase, CarControllerBa from opendbc.car.volkswagen.values import CarControllerParams as VWCarControllerParams from opendbc.car.hyundai.interface import ENABLE_BUTTONS as HYUNDAI_ENABLE_BUTTONS -from openpilot.selfdrive.controls.lib.events import Events +from openpilot.selfdrive.selfdrived.events import Events ButtonType = structs.CarState.ButtonEvent.Type GearShifter = structs.CarState.GearShifter diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 6494074458..62569f64f5 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -22,7 +22,7 @@ from openpilot.selfdrive.pandad import can_capnp_to_list, can_list_to_can_capnp from openpilot.selfdrive.car.cruise import VCruiseHelper from openpilot.selfdrive.car.car_specific import CarSpecificEvents, MockCarState from openpilot.selfdrive.car.helpers import convert_carControl, convert_to_capnp -from openpilot.selfdrive.controls.lib.events import Events, ET +from openpilot.selfdrive.selfdrived.events import Events, ET REPLAY = "REPLAY" in os.environ @@ -266,7 +266,7 @@ class Car: self.state_publish(CS, RD) - initialized = (not any(e.name == EventName.controlsInitializing for e in self.sm['onroadEvents']) and + initialized = (not any(e.name == EventName.selfdriveInitializing for e in self.sm['onroadEvents']) and self.sm.seen['onroadEvents']) if not self.CP.passive and initialized: self.controls_update(CS, self.sm['carControl']) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index a7fac2a1ff..4492b21b47 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -1,132 +1,53 @@ #!/usr/bin/env python3 -import os import math -import time -import threading from typing import SupportsFloat -import cereal.messaging as messaging - from cereal import car, log -from msgq.visionipc import VisionIpcClient, VisionStreamType - - +import cereal.messaging as messaging from openpilot.common.conversions import Conversions as CV -from openpilot.common.git import get_short_branch -from openpilot.common.numpy_fast import clip from openpilot.common.params import Params -from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper, DT_CTRL +from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper from openpilot.common.swaglog import cloudlog -from openpilot.common.gps import get_gps_location_service from opendbc.car.car_helpers import get_car_interface -from openpilot.selfdrive.controls.lib.alertmanager import AlertManager, set_offroad_alert -from openpilot.selfdrive.controls.lib.drive_helpers import clip_curvature, get_startup_event -from openpilot.selfdrive.controls.lib.events import Events, ET +from openpilot.selfdrive.controls.lib.drive_helpers import clip_curvature from openpilot.selfdrive.controls.lib.latcontrol import LatControl, MIN_LATERAL_CONTROL_SPEED from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle, STEER_ANGLE_SATURATION_THRESHOLD from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.longcontrol import LongControl from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel -from openpilot.selfdrive.controls.lib.selfdrive import StateMachine from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose -from openpilot.system.hardware import HARDWARE - -JOYSTICK_MAX_LAT_ACCEL = 2.5 # m/s^2 -REPLAY = "REPLAY" in os.environ -SIMULATION = "SIMULATION" in os.environ -TESTING_CLOSET = "TESTING_CLOSET" in os.environ -IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd"} - -ThermalStatus = log.DeviceState.ThermalStatus State = log.SelfdriveState.OpenpilotState -PandaType = log.PandaState.PandaType LaneChangeState = log.LaneChangeState LaneChangeDirection = log.LaneChangeDirection -EventName = car.OnroadEvent.EventName -ButtonType = car.CarState.ButtonEvent.Type -SafetyModel = car.CarParams.SafetyModel -IGNORED_SAFETY_MODES = (SafetyModel.silent, SafetyModel.noOutput) -CSID_MAP = {"1": EventName.roadCameraError, "2": EventName.wideRoadCameraError, "0": EventName.driverCameraError} ACTUATOR_FIELDS = tuple(car.CarControl.Actuators.schema.fields.keys()) - class Controls: - def __init__(self, CI=None): + def __init__(self) -> None: self.params = Params() + cloudlog.info("controlsd is waiting for CarParams") + self.CP = messaging.log_from_bytes(self.params.get("CarParams", block=True), car.CarParams) + cloudlog.info("controlsd got CarParams") - if CI is None: - cloudlog.info("controlsd is waiting for CarParams") - self.CP = messaging.log_from_bytes(self.params.get("CarParams", block=True), car.CarParams) - cloudlog.info("controlsd got CarParams") - - # Uses car interface helper functions, altering state won't be considered by card for actuation - self.CI = get_car_interface(self.CP) - else: - self.CI, self.CP = CI, CI.CP - - # Ensure the current branch is cached, otherwise the first iteration of controlsd lags - self.branch = get_short_branch() - - # Setup sockets - self.pm = messaging.PubMaster(['selfdriveState', 'controlsState', 'carControl', 'onroadEvents']) + self.CI = get_car_interface(self.CP) - self.gps_location_service = get_gps_location_service(self.params) - self.gps_packets = [self.gps_location_service] - self.sensor_packets = ["accelerometer", "gyroscope"] - self.camera_packets = ["roadCameraState", "driverCameraState", "wideRoadCameraState"] + self.sm = messaging.SubMaster(['liveParameters', 'liveTorqueParameters', 'modelV2', 'selfdriveState', + 'liveCalibration', 'livePose', 'longitudinalPlan', 'carState', 'carOutput', + 'driverMonitoringState', 'onroadEvents', 'driverAssistance'], poll='carState') + self.pm = messaging.PubMaster(['carControl', 'controlsState']) - self.log_sock = messaging.sub_sock('androidLog') - - # TODO: de-couple controlsd with card/conflate on carState without introducing controls mismatches - self.car_state_sock = messaging.sub_sock('carState', timeout=20) - - ignore = self.sensor_packets + self.gps_packets + ['testJoystick'] - if SIMULATION: - ignore += ['driverCameraState', 'managerState'] - if REPLAY: - # no vipc in replay will make them ignored anyways - ignore += ['roadCameraState', 'wideRoadCameraState'] - self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', - 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', - 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', - 'testJoystick', 'driverAssistance'] + self.camera_packets + self.sensor_packets + self.gps_packets, - ignore_alive=ignore, ignore_avg_freq=ignore+['testJoystick'], ignore_valid=['testJoystick', ], - frequency=int(1/DT_CTRL)) - - self.joystick_mode = self.params.get_bool("JoystickDebugMode") - - # read params - self.is_metric = self.params.get_bool("IsMetric") - self.is_ldw_enabled = self.params.get_bool("IsLdwEnabled") - - # detect sound card presence and ensure successful init - sounds_available = HARDWARE.get_sound_card_online() - - car_recognized = self.CP.carName != 'mock' - - # cleanup old params - if not self.CP.experimentalLongitudinalAvailable: - self.params.remove("ExperimentalLongitudinalEnabled") - if not self.CP.openpilotLongitudinalControl: - self.params.remove("ExperimentalMode") - - self.CS_prev = car.CarState.new_message() - self.CC_prev = car.CarControl.new_message() - self.lac_log_prev = None - self.AM = AlertManager() - self.events = Events() + self.steer_limited = False + self.desired_curvature = 0.0 self.pose_calibrator = PoseCalibrator() self.calibrated_pose: Pose|None = None self.LoC = LongControl(self.CP) self.VM = VehicleModel(self.CP) - self.LaC: LatControl if self.CP.steerControlType == car.CarParams.SteerControlType.angle: self.LaC = LatControlAngle(self.CP, self.CI) @@ -135,341 +56,16 @@ class Controls: elif self.CP.lateralTuning.which() == 'torque': self.LaC = LatControlTorque(self.CP, self.CI) - self.initialized = False - self.enabled = False - self.active = False - self.mismatch_counter = 0 - self.cruise_mismatch_counter = 0 - self.last_steering_pressed_frame = 0 - self.distance_traveled = 0 - self.last_functional_fan_frame = 0 - self.events_prev = [] - self.logged_comm_issue = None - self.not_running_prev = None - self.steer_limited = False - self.desired_curvature = 0.0 - self.experimental_mode = False - self.personality = self.read_personality_param() - self.recalibrating_seen = False - self.state_machine = StateMachine() - - self.can_log_mono_time = 0 - - self.startup_event = get_startup_event(car_recognized, not self.CP.passive, len(self.CP.carFw) > 0) - - if not sounds_available: - self.events.add(EventName.soundsUnavailable, static=True) - if not car_recognized: - self.events.add(EventName.carUnrecognized, static=True) - if len(self.CP.carFw) > 0: - set_offroad_alert("Offroad_CarUnrecognized", True) - else: - set_offroad_alert("Offroad_NoFirmware", True) - elif self.CP.passive: - self.events.add(EventName.dashcamMode, static=True) - - # controlsd is driven by carState, expected at 100Hz - self.rk = Ratekeeper(100, print_delay_threshold=None) - - def set_initial_state(self): - if REPLAY and any(ps.controlsAllowed for ps in self.sm['pandaStates']): - self.state_machine.state = State.enabled - - def update_events(self, CS): - """Compute onroadEvents from carState""" - - self.events.clear() - - # Add joystick event, static on cars, dynamic on nonCars - if self.joystick_mode: - self.events.add(EventName.joystickDebug) - self.startup_event = None - - # Add startup event - if self.startup_event is not None: - self.events.add(self.startup_event) - self.startup_event = None - - # Don't add any more events if not initialized - if not self.initialized: - self.events.add(EventName.controlsInitializing) - return - - # no more events while in dashcam mode - if self.CP.passive: - return - - # Block resume if cruise never previously enabled - resume_pressed = any(be.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for be in CS.buttonEvents) - if not self.CP.pcmCruise and CS.vCruise > 250 and resume_pressed: - self.events.add(EventName.resumeBlocked) - - if not self.CP.notCar: - self.events.add_from_msg(self.sm['driverMonitoringState'].events) - - # Add car events, ignore if CAN isn't valid - if CS.canValid: - self.events.add_from_msg(CS.events) - - # Create events for temperature, disk space, and memory - if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: - self.events.add(EventName.overheat) - if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: - self.events.add(EventName.outOfSpace) - if self.sm['deviceState'].memoryUsagePercent > 90 and not SIMULATION: - self.events.add(EventName.lowMemory) - - # Alert if fan isn't spinning for 5 seconds - if self.sm['peripheralState'].pandaType != log.PandaState.PandaType.unknown: - if self.sm['peripheralState'].fanSpeedRpm < 500 and self.sm['deviceState'].fanSpeedPercentDesired > 50: - # allow enough time for the fan controller in the panda to recover from stalls - if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 15.0: - self.events.add(EventName.fanMalfunction) - else: - self.last_functional_fan_frame = self.sm.frame - - # Handle calibration status - cal_status = self.sm['liveCalibration'].calStatus - if cal_status != log.LiveCalibrationData.Status.calibrated: - if cal_status == log.LiveCalibrationData.Status.uncalibrated: - self.events.add(EventName.calibrationIncomplete) - elif cal_status == log.LiveCalibrationData.Status.recalibrating: - if not self.recalibrating_seen: - set_offroad_alert("Offroad_Recalibration", True) - self.recalibrating_seen = True - self.events.add(EventName.calibrationRecalibrating) - else: - self.events.add(EventName.calibrationInvalid) - - # Lane departure warning - if self.is_ldw_enabled and self.sm.valid['driverAssistance']: - if self.sm['driverAssistance'].leftLaneDeparture or self.sm['driverAssistance'].rightLaneDeparture: - self.events.add(EventName.ldw) - - # Handle lane change - if self.sm['modelV2'].meta.laneChangeState == LaneChangeState.preLaneChange: - direction = self.sm['modelV2'].meta.laneChangeDirection - if (CS.leftBlindspot and direction == LaneChangeDirection.left) or \ - (CS.rightBlindspot and direction == LaneChangeDirection.right): - self.events.add(EventName.laneChangeBlocked) - else: - if direction == LaneChangeDirection.left: - self.events.add(EventName.preLaneChangeLeft) - else: - self.events.add(EventName.preLaneChangeRight) - elif self.sm['modelV2'].meta.laneChangeState in (LaneChangeState.laneChangeStarting, - LaneChangeState.laneChangeFinishing): - self.events.add(EventName.laneChange) - - for i, pandaState in enumerate(self.sm['pandaStates']): - # All pandas must match the list of safetyConfigs, and if outside this list, must be silent or noOutput - if i < len(self.CP.safetyConfigs): - safety_mismatch = pandaState.safetyModel != self.CP.safetyConfigs[i].safetyModel or \ - pandaState.safetyParam != self.CP.safetyConfigs[i].safetyParam or \ - pandaState.alternativeExperience != self.CP.alternativeExperience - else: - safety_mismatch = pandaState.safetyModel not in IGNORED_SAFETY_MODES - - # safety mismatch allows some time for pandad to set the safety mode and publish it back from panda - if (safety_mismatch and self.sm.frame*DT_CTRL > 10.) or pandaState.safetyRxChecksInvalid or self.mismatch_counter >= 200: - self.events.add(EventName.controlsMismatch) - - if log.PandaState.FaultType.relayMalfunction in pandaState.faults: - self.events.add(EventName.relayMalfunction) - - # Handle HW and system malfunctions - # Order is very intentional here. Be careful when modifying this. - # All events here should at least have NO_ENTRY and SOFT_DISABLE. - num_events = len(self.events) - - not_running = {p.name for p in self.sm['managerState'].processes if not p.running and p.shouldBeRunning} - if self.sm.recv_frame['managerState'] and (not_running - IGNORE_PROCESSES): - self.events.add(EventName.processNotRunning) - if not_running != self.not_running_prev: - cloudlog.event("process_not_running", not_running=not_running, error=True) - self.not_running_prev = not_running - else: - if not SIMULATION and not self.rk.lagging: - if not self.sm.all_alive(self.camera_packets): - self.events.add(EventName.cameraMalfunction) - elif not self.sm.all_freq_ok(self.camera_packets): - self.events.add(EventName.cameraFrameRate) - if not REPLAY and self.rk.lagging: - self.events.add(EventName.controlsdLagging) - if not self.sm.valid['radarState']: - self.events.add(EventName.radarFault) - if not self.sm.valid['pandaStates']: - self.events.add(EventName.usbError) - if CS.canTimeout: - self.events.add(EventName.canBusMissing) - elif not CS.canValid: - self.events.add(EventName.canError) - - # generic catch-all. ideally, a more specific event should be added above instead - has_disable_events = self.events.contains(ET.NO_ENTRY) and (self.events.contains(ET.SOFT_DISABLE) or self.events.contains(ET.IMMEDIATE_DISABLE)) - no_system_errors = (not has_disable_events) or (len(self.events) == num_events) - if not self.sm.all_checks() and no_system_errors: - if not self.sm.all_alive(): - self.events.add(EventName.commIssue) - elif not self.sm.all_freq_ok(): - self.events.add(EventName.commIssueAvgFreq) - else: - self.events.add(EventName.commIssue) - - logs = { - 'invalid': [s for s, valid in self.sm.valid.items() if not valid], - 'not_alive': [s for s, alive in self.sm.alive.items() if not alive], - 'not_freq_ok': [s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok], - } - if logs != self.logged_comm_issue: - cloudlog.event("commIssue", error=True, **logs) - self.logged_comm_issue = logs - else: - self.logged_comm_issue = None - - if not (self.CP.notCar and self.joystick_mode): - if not self.sm['livePose'].posenetOK: - self.events.add(EventName.posenetInvalid) - if not self.sm['livePose'].inputsOK: - self.events.add(EventName.locationdTemporaryError) - if not self.sm['liveParameters'].valid and not TESTING_CLOSET and (not SIMULATION or REPLAY): - self.events.add(EventName.paramsdTemporaryError) - - # conservative HW alert. if the data or frequency are off, locationd will throw an error - if any((self.sm.frame - self.sm.recv_frame[s])*DT_CTRL > 10. for s in self.sensor_packets): - self.events.add(EventName.sensorDataInvalid) - - if not REPLAY: - # Check for mismatch between openpilot and car's PCM - cruise_mismatch = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) - self.cruise_mismatch_counter = self.cruise_mismatch_counter + 1 if cruise_mismatch else 0 - if self.cruise_mismatch_counter > int(6. / DT_CTRL): - self.events.add(EventName.cruiseMismatch) - - # Send a "steering required alert" if saturation count has reached the limit - lac_log = self.lac_log_prev - if CS.steeringPressed: - self.last_steering_pressed_frame = self.sm.frame - recent_steer_pressed = (self.sm.frame - self.last_steering_pressed_frame)*DT_CTRL < 2.0 - if self.lac_log_prev is not None and self.lac_log_prev.active and not recent_steer_pressed and not self.CP.notCar: - lac_log = self.lac_log_prev - if self.CP.lateralTuning.which() == 'torque' and not self.joystick_mode: - undershooting = abs(lac_log.desiredLateralAccel) / abs(1e-3 + lac_log.actualLateralAccel) > 1.2 - turning = abs(lac_log.desiredLateralAccel) > 1.0 - good_speed = CS.vEgo > 5 - max_torque = abs(self.sm['carOutput'].actuatorsOutput.steer) > 0.99 - if undershooting and turning and good_speed and max_torque: - self.events.add(EventName.steerSaturated) - elif lac_log.saturated: - # TODO probably should not use dpath_points but curvature - dpath_points = self.sm['modelV2'].position.y - if len(dpath_points): - # Check if we deviated from the path - # TODO use desired vs actual curvature - if self.CP.steerControlType == car.CarParams.SteerControlType.angle: - steering_value = self.CC_prev.actuators.steeringAngleDeg - else: - steering_value = self.CC_prev.actuators.steer - - left_deviation = steering_value > 0 and dpath_points[0] < -0.20 - right_deviation = steering_value < 0 and dpath_points[0] > 0.20 - - if left_deviation or right_deviation: - self.events.add(EventName.steerSaturated) - - # Check for FCW - stock_long_is_braking = self.enabled and not self.CP.openpilotLongitudinalControl and CS.aEgo < -1.25 - model_fcw = self.sm['modelV2'].meta.hardBrakePredicted and not CS.brakePressed and not stock_long_is_braking - planner_fcw = self.sm['longitudinalPlan'].fcw and self.enabled - if (planner_fcw or model_fcw) and not (self.CP.notCar and self.joystick_mode): - self.events.add(EventName.fcw) - - for m in messaging.drain_sock(self.log_sock, wait_for_one=False): - try: - msg = m.androidLog.message - if any(err in msg for err in ("ERROR_CRC", "ERROR_ECC", "ERROR_STREAM_UNDERFLOW", "APPLY FAILED")): - csid = msg.split("CSID:")[-1].split(" ")[0] - evt = CSID_MAP.get(csid, None) - if evt is not None: - self.events.add(evt) - except UnicodeDecodeError: - pass - - # TODO: fix simulator - if not SIMULATION or REPLAY: - # Not show in first 1.5 km to allow for driving out of garage. This event shows after 5 minutes - gps_ok = self.sm.recv_frame[self.gps_location_service] > 0 and (self.sm.frame - self.sm.recv_frame[self.gps_location_service]) * DT_CTRL < 2.0 - if not gps_ok and self.sm['livePose'].inputsOK and (self.distance_traveled > 1500): - self.events.add(EventName.noGps) - if gps_ok: - self.distance_traveled = 0 - self.distance_traveled += CS.vEgo * DT_CTRL - - if self.sm['modelV2'].frameDropPerc > 20: - self.events.add(EventName.modeldLagging) - - # decrement personality on distance button press - if self.CP.openpilotLongitudinalControl: - if any(not be.pressed and be.type == ButtonType.gapAdjustCruise for be in CS.buttonEvents): - self.personality = (self.personality - 1) % 3 - self.params.put_nonblocking('LongitudinalPersonality', str(self.personality)) - self.events.add(EventName.personalityChanged) - - def data_sample(self): - """Receive data from sockets""" - - car_state = messaging.recv_one(self.car_state_sock) - CS = car_state.carState if car_state else self.CS_prev - - self.sm.update(0) - - if not self.initialized: - all_valid = CS.canValid and self.sm.all_checks() - timed_out = self.sm.frame * DT_CTRL > 6. - if all_valid or timed_out or (SIMULATION and not REPLAY): - available_streams = VisionIpcClient.available_streams("camerad", block=False) - if VisionStreamType.VISION_STREAM_ROAD not in available_streams: - self.sm.ignore_alive.append('roadCameraState') - if VisionStreamType.VISION_STREAM_WIDE_ROAD not in available_streams: - self.sm.ignore_alive.append('wideRoadCameraState') - - self.initialized = True - self.set_initial_state() - - cloudlog.event( - "controlsd.initialized", - dt=self.sm.frame*DT_CTRL, - timeout=timed_out, - canValid=CS.canValid, - invalid=[s for s, valid in self.sm.valid.items() if not valid], - not_alive=[s for s, alive in self.sm.alive.items() if not alive], - not_freq_ok=[s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok], - error=True, - ) - - # When the panda and controlsd do not agree on controls_allowed - # we want to disengage openpilot. However the status from the panda goes through - # another socket other than the CAN messages and one can arrive earlier than the other. - # Therefore we allow a mismatch for two samples, then we trigger the disengagement. - if not self.enabled: - self.mismatch_counter = 0 - - # All pandas not in silent mode must have controlsAllowed when openpilot is enabled - if self.enabled and any(not ps.controlsAllowed for ps in self.sm['pandaStates'] - if ps.safetyModel not in IGNORED_SAFETY_MODES): - self.mismatch_counter += 1 - - # calibrate the live pose and save it for later use + def update(self): + self.sm.update(15) if self.sm.updated["liveCalibration"]: self.pose_calibrator.feed_live_calib(self.sm['liveCalibration']) if self.sm.updated["livePose"]: device_pose = Pose.from_live_pose(self.sm['livePose']) self.calibrated_pose = self.pose_calibrator.build_calibrated_pose(device_pose) - return CS - - def state_control(self, CS): - """Given the state, this function returns a CarControl packet""" + def state_control(self): + CS = self.sm['carState'] # Update VehicleModel lp = self.sm['liveParameters'] @@ -488,13 +84,12 @@ class Controls: model_v2 = self.sm['modelV2'] CC = car.CarControl.new_message() - CC.enabled = self.enabled + CC.enabled = self.sm['selfdriveState'].enabled # Check which actuators can be enabled standstill = CS.vEgo <= max(self.CP.minSteerSpeed, MIN_LATERAL_CONTROL_SPEED) or CS.standstill - CC.latActive = self.active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \ - (not standstill or self.joystick_mode) - CC.longActive = self.enabled and not self.events.contains(ET.OVERRIDE_LONGITUDINAL) and self.CP.openpilotLongitudinalControl + CC.latActive = self.sm['selfdriveState'].active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and not standstill + CC.longActive = CC.enabled and not any(e.overrideLongitudinal for e in self.sm['onroadEvents']) and self.CP.openpilotLongitudinalControl actuators = CC.actuators actuators.longControlState = self.LoC.long_control_state @@ -504,51 +99,21 @@ class Controls: CC.leftBlinker = model_v2.meta.laneChangeDirection == LaneChangeDirection.left CC.rightBlinker = model_v2.meta.laneChangeDirection == LaneChangeDirection.right - if CS.leftBlinker or CS.rightBlinker: - self.last_blinker_frame = self.sm.frame - - # State specific actions - if not CC.latActive: self.LaC.reset() if not CC.longActive: self.LoC.reset() - if not self.joystick_mode: - # accel PID loop - pid_accel_limits = self.CI.get_pid_accel_limits(self.CP, CS.vEgo, CS.vCruise * CV.KPH_TO_MS) - actuators.accel = self.LoC.update(CC.longActive, CS, long_plan.aTarget, long_plan.shouldStop, pid_accel_limits) - - # Steering PID loop and lateral MPC - self.desired_curvature = clip_curvature(CS.vEgo, self.desired_curvature, model_v2.action.desiredCurvature) - actuators.curvature = self.desired_curvature - actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, - self.steer_limited, self.desired_curvature, - self.calibrated_pose) # TODO what if not available - else: - lac_log = log.ControlsState.LateralDebugState.new_message() - if self.sm.recv_frame['testJoystick'] > 0: - # reset joystick if it hasn't been received in a while - should_reset_joystick = (self.sm.frame - self.sm.recv_frame['testJoystick'])*DT_CTRL > 0.2 - if not should_reset_joystick: - joystick_axes = self.sm['testJoystick'].axes - else: - joystick_axes = [0.0, 0.0] - - if CC.longActive: - actuators.accel = 4.0*clip(joystick_axes[0], -1, 1) - - if CC.latActive: - max_curvature = JOYSTICK_MAX_LAT_ACCEL / max(CS.vEgo ** 2, 1) - max_angle = math.degrees(self.VM.get_steer_from_curvature(max_curvature, CS.vEgo, lp.roll)) - - steer = clip(joystick_axes[1], -1, 1) - actuators.steer, actuators.steeringAngleDeg, actuators.curvature = steer, steer * max_angle, steer * -max_curvature - - lac_log.active = self.active - lac_log.steeringAngleDeg = CS.steeringAngleDeg - lac_log.output = actuators.steer - lac_log.saturated = abs(actuators.steer) >= 0.9 + # accel PID loop + pid_accel_limits = self.CI.get_pid_accel_limits(self.CP, CS.vEgo, CS.vCruise * CV.KPH_TO_MS) + actuators.accel = self.LoC.update(CC.longActive, CS, long_plan.aTarget, long_plan.shouldStop, pid_accel_limits) + + # Steering PID loop and lateral MPC + self.desired_curvature = clip_curvature(CS.vEgo, self.desired_curvature, model_v2.action.desiredCurvature) + actuators.curvature = self.desired_curvature + actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, + self.steer_limited, self.desired_curvature, + self.calibrated_pose) # TODO what if not available # Ensure no NaNs/Infs for p in ACTUATOR_FIELDS: @@ -562,53 +127,37 @@ class Controls: return CC, lac_log - def update_alerts(self, CS): - clear_event_types = set() - if ET.WARNING not in self.state_machine.current_alert_types: - clear_event_types.add(ET.WARNING) - if self.enabled: - clear_event_types.add(ET.NO_ENTRY) + def publish(self, CC, lac_log): + CS = self.sm['carState'] - pers = {v: k for k, v in log.LongitudinalPersonality.schema.enumerants.items()}[self.personality] - alerts = self.events.create_alerts(self.state_machine.current_alert_types, [self.CP, CS, self.sm, self.is_metric, - self.state_machine.soft_disable_timer, pers]) - self.AM.add_many(self.sm.frame, alerts) - self.AM.process_alerts(self.sm.frame, clear_event_types) - - def publish_carControl(self, CS, CC, lac_log): # Orientation and angle rates can be useful for carcontroller # Only calibrated (car) frame is relevant for the carcontroller if self.calibrated_pose is not None: CC.orientationNED = self.calibrated_pose.orientation.xyz.tolist() CC.angularVelocity = self.calibrated_pose.angular_velocity.xyz.tolist() - CC.cruiseControl.override = self.enabled and not CC.longActive and self.CP.openpilotLongitudinalControl - CC.cruiseControl.cancel = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) - if self.joystick_mode and self.sm.recv_frame['testJoystick'] > 0 and self.sm['testJoystick'].buttons[0]: - CC.cruiseControl.cancel = True + CC.cruiseControl.override = CC.enabled and not CC.longActive and self.CP.openpilotLongitudinalControl + CC.cruiseControl.cancel = CS.cruiseState.enabled and (not CC.enabled or not self.CP.pcmCruise) speeds = self.sm['longitudinalPlan'].speeds if len(speeds): - CC.cruiseControl.resume = self.enabled and CS.cruiseState.standstill and speeds[-1] > 0.1 + CC.cruiseControl.resume = CC.enabled and CS.cruiseState.standstill and speeds[-1] > 0.1 hudControl = CC.hudControl hudControl.setSpeed = float(CS.vCruiseCluster * CV.KPH_TO_MS) - hudControl.speedVisible = self.enabled - hudControl.lanesVisible = self.enabled + hudControl.speedVisible = CC.enabled + hudControl.lanesVisible = CC.enabled hudControl.leadVisible = self.sm['longitudinalPlan'].hasLead - hudControl.leadDistanceBars = self.personality + 1 + hudControl.leadDistanceBars = self.sm['selfdriveState'].personality.raw + 1 + hudControl.visualAlert = self.sm['selfdriveState'].alertHudVisual hudControl.rightLaneVisible = True hudControl.leftLaneVisible = True - - if self.is_ldw_enabled and self.sm.valid['driverAssistance']: + if self.sm.valid['driverAssistance']: hudControl.leftLaneDepart = self.sm['driverAssistance'].leftLaneDeparture hudControl.rightLaneDepart = self.sm['driverAssistance'].rightLaneDeparture - if self.AM.current_alert: - hudControl.visualAlert = self.AM.current_alert.visual_alert - - if not self.CP.passive and self.initialized: + if self.sm['selfdriveState'].active: CO = self.sm['carOutput'] if self.CP.steerControlType == car.CarParams.SteerControlType.angle: self.steer_limited = abs(CC.actuators.steeringAngleDeg - CO.actuatorsOutput.steeringAngleDeg) > \ @@ -616,6 +165,8 @@ class Controls: else: self.steer_limited = abs(CC.actuators.steer - CO.actuatorsOutput.steer) > 1e-2 + # TODO: both controlsState and carControl valids should be set by + # sm.all_checks(), but this creates a circular dependency # controlsState dat = messaging.new_message('controlsState') @@ -633,14 +184,11 @@ class Controls: cs.upAccelCmd = float(self.LoC.pid.p) cs.uiAccelCmd = float(self.LoC.pid.i) cs.ufAccelCmd = float(self.LoC.pid.f) - cs.cumLagMs = -self.rk.remaining * 1000. cs.forceDecel = bool((self.sm['driverMonitoringState'].awarenessStatus < 0.) or - (self.state_machine.state == State.softDisabling)) + (self.sm['selfdriveState'].state == State.softDisabling)) lat_tuning = self.CP.lateralTuning.which() - if self.joystick_mode: - cs.lateralControlState.debugState = lac_log - elif self.CP.steerControlType == car.CarParams.SteerControlType.angle: + if self.CP.steerControlType == car.CarParams.SteerControlType.angle: cs.lateralControlState.angleState = lac_log elif lat_tuning == 'pid': cs.lateralControlState.pidState = lac_log @@ -655,84 +203,18 @@ class Controls: cc_send.carControl = CC self.pm.send('carControl', cc_send) - def publish_selfdriveState(self, CS): - # selfdriveState - ss_msg = messaging.new_message('selfdriveState') - ss_msg.valid = CS.canValid - ss = ss_msg.selfdriveState - if self.AM.current_alert: - ss.alertText1 = self.AM.current_alert.alert_text_1 - ss.alertText2 = self.AM.current_alert.alert_text_2 - ss.alertSize = self.AM.current_alert.alert_size - ss.alertStatus = self.AM.current_alert.alert_status - ss.alertType = self.AM.current_alert.alert_type - ss.alertSound = self.AM.current_alert.audible_alert - ss.enabled = self.enabled - ss.active = self.active - ss.state = self.state_machine.state - ss.engageable = not self.events.contains(ET.NO_ENTRY) - ss.experimentalMode = self.experimental_mode - ss.personality = self.personality - self.pm.send('selfdriveState', ss_msg) - - # onroadEvents - logged every second or on change - if (self.sm.frame % int(1. / DT_CTRL) == 0) or (self.events.names != self.events_prev): - ce_send = messaging.new_message('onroadEvents', len(self.events)) - ce_send.valid = True - ce_send.onroadEvents = self.events.to_msg() - self.pm.send('onroadEvents', ce_send) - self.events_prev = self.events.names.copy() - - def step(self): - CS = self.data_sample() - self.update_events(CS) - if not self.CP.passive and self.initialized: - self.enabled, self.active = self.state_machine.update(self.events) - self.update_alerts(CS) - - # Compute actuators (runs PID loops and lateral MPC) - CC, lac_log = self.state_control(CS) - - # Publish data - self.publish_carControl(CS, CC, lac_log) - self.publish_selfdriveState(CS) - - self.CS_prev = CS - self.CC_prev = CC - self.lac_log_prev = lac_log - - def read_personality_param(self): - try: - return int(self.params.get('LongitudinalPersonality')) - except (ValueError, TypeError): - return log.LongitudinalPersonality.standard - - def params_thread(self, evt): - while not evt.is_set(): - self.is_metric = self.params.get_bool("IsMetric") - self.experimental_mode = self.params.get_bool("ExperimentalMode") and self.CP.openpilotLongitudinalControl - self.personality = self.read_personality_param() - if self.CP.notCar: - self.joystick_mode = self.params.get_bool("JoystickDebugMode") - time.sleep(0.1) - - def controlsd_thread(self): - e = threading.Event() - t = threading.Thread(target=self.params_thread, args=(e, )) - try: - t.start() - while True: - self.step() - self.rk.monitor_time() - finally: - e.set() - t.join() - + def run(self): + rk = Ratekeeper(100, print_delay_threshold=None) + while True: + self.update() + CC, lac_log = self.state_control() + self.publish(CC, lac_log) + rk.keep_time() def main(): config_realtime_process(4, Priority.CTRL_HIGH) controls = Controls() - controls.controlsd_thread() + controls.run() if __name__ == "__main__": diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 35810c4832..64cbf473d6 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -1,9 +1,6 @@ -from cereal import car, log +from cereal import log from openpilot.common.numpy_fast import clip from openpilot.common.realtime import DT_CTRL -from openpilot.system.version import get_build_metadata - -EventName = car.OnroadEvent.EventName MIN_SPEED = 1.0 CONTROL_N = 17 @@ -29,20 +26,3 @@ def get_speed_error(modelV2: log.ModelDataV2, v_ego: float) -> float: vel_err = clip(modelV2.temporalPose.trans[0] - v_ego, -MAX_VEL_ERR, MAX_VEL_ERR) return float(vel_err) return 0.0 - - -def get_startup_event(car_recognized, controller_available, fw_seen): - build_metadata = get_build_metadata() - if build_metadata.openpilot.comma_remote and build_metadata.tested_channel: - event = EventName.startup - else: - event = EventName.startupMaster - - if not car_recognized: - if fw_seen: - event = EventName.startupNoCar - else: - event = EventName.startupNoFw - elif car_recognized and not controller_available: - event = EventName.startupNoControl - return event diff --git a/selfdrive/controls/tests/test_startup.py b/selfdrive/controls/tests/test_startup.py deleted file mode 100644 index 077d4ae93a..0000000000 --- a/selfdrive/controls/tests/test_startup.py +++ /dev/null @@ -1,121 +0,0 @@ -import os -from parameterized import parameterized - -from cereal import log, car -import cereal.messaging as messaging -from opendbc.car.fingerprints import _FINGERPRINTS -from opendbc.car.toyota.values import CAR as TOYOTA -from opendbc.car.mazda.values import CAR as MAZDA -from openpilot.common.params import Params -from openpilot.selfdrive.pandad.pandad_api_impl import can_list_to_can_capnp -from openpilot.selfdrive.controls.lib.events import EVENT_NAME -from openpilot.system.manager.process_config import managed_processes - -EventName = car.OnroadEvent.EventName -Ecu = car.CarParams.Ecu - -COROLLA_FW_VERSIONS = [ - (Ecu.engine, 0x7e0, None, b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.abs, 0x7b0, None, b'F152602190\x00\x00\x00\x00\x00\x00'), - (Ecu.eps, 0x7a1, None, b'8965B02181\x00\x00\x00\x00\x00\x00'), - (Ecu.fwdRadar, 0x750, 0xf, b'8821F4702100\x00\x00\x00\x00'), - (Ecu.fwdCamera, 0x750, 0x6d, b'8646F0201101\x00\x00\x00\x00'), - (Ecu.dsu, 0x791, None, b'881510201100\x00\x00\x00\x00'), -] -COROLLA_FW_VERSIONS_FUZZY = COROLLA_FW_VERSIONS[:-1] + [(Ecu.dsu, 0x791, None, b'xxxxxx')] -COROLLA_FW_VERSIONS_NO_DSU = COROLLA_FW_VERSIONS[:-1] - -CX5_FW_VERSIONS = [ - (Ecu.engine, 0x7e0, None, b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.abs, 0x760, None, b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.eps, 0x730, None, b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.fwdRadar, 0x764, None, b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.fwdCamera, 0x706, None, b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.transmission, 0x7e1, None, b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), -] - - -@parameterized.expand([ - # TODO: test EventName.startup for release branches - - # officially supported car - (EventName.startupMaster, TOYOTA.TOYOTA_COROLLA, COROLLA_FW_VERSIONS, "toyota"), - (EventName.startupMaster, TOYOTA.TOYOTA_COROLLA, COROLLA_FW_VERSIONS, "toyota"), - - # dashcamOnly car - (EventName.startupNoControl, MAZDA.MAZDA_CX5, CX5_FW_VERSIONS, "mazda"), - (EventName.startupNoControl, MAZDA.MAZDA_CX5, CX5_FW_VERSIONS, "mazda"), - - # unrecognized car with no fw - (EventName.startupNoFw, None, None, ""), - (EventName.startupNoFw, None, None, ""), - - # unrecognized car - (EventName.startupNoCar, None, COROLLA_FW_VERSIONS[:1], "toyota"), - (EventName.startupNoCar, None, COROLLA_FW_VERSIONS[:1], "toyota"), - - # fuzzy match - (EventName.startupMaster, TOYOTA.TOYOTA_COROLLA, COROLLA_FW_VERSIONS_FUZZY, "toyota"), - (EventName.startupMaster, TOYOTA.TOYOTA_COROLLA, COROLLA_FW_VERSIONS_FUZZY, "toyota"), -]) -def test_startup_alert(expected_event, car_model, fw_versions, brand): - controls_sock = messaging.sub_sock("selfdriveState") - pm = messaging.PubMaster(['can', 'pandaStates']) - - params = Params() - params.put_bool("OpenpilotEnabledToggle", True) - - # Build capnn version of FW array - if fw_versions is not None: - car_fw = [] - cp = car.CarParams.new_message() - for ecu, addr, subaddress, version in fw_versions: - f = car.CarParams.CarFw.new_message() - f.ecu = ecu - f.address = addr - f.fwVersion = version - f.brand = brand - - if subaddress is not None: - f.subAddress = subaddress - - car_fw.append(f) - cp.carVin = "1" * 17 - cp.carFw = car_fw - params.put("CarParamsCache", cp.to_bytes()) - else: - os.environ['SKIP_FW_QUERY'] = '1' - - managed_processes['controlsd'].start() - managed_processes['card'].start() - - assert pm.wait_for_readers_to_update('can', 5) - pm.send('can', can_list_to_can_capnp([[0, b"", 0]])) - - assert pm.wait_for_readers_to_update('pandaStates', 5) - msg = messaging.new_message('pandaStates', 1) - msg.pandaStates[0].pandaType = log.PandaState.PandaType.uno - pm.send('pandaStates', msg) - - # fingerprint - if (car_model is None) or (fw_versions is not None): - finger = {addr: 1 for addr in range(1, 100)} - else: - finger = _FINGERPRINTS[car_model][0] - - msgs = [[addr, b'\x00'*length, 0] for addr, length in finger.items()] - for _ in range(1000): - # card waits for pandad to echo back that it has changed the multiplexing mode - if not params.get_bool("ObdMultiplexingChanged"): - params.put_bool("ObdMultiplexingChanged", True) - - pm.send('can', can_list_to_can_capnp(msgs)) - assert pm.wait_for_readers_to_update('can', 5, dt=0.001), f"step: {_}" - - ctrls = messaging.drain_sock(controls_sock) - if len(ctrls): - event_name = ctrls[0].selfdriveState.alertType.split("/")[0] - assert EVENT_NAME[expected_event] == event_name, f"expected {EVENT_NAME[expected_event]} for '{car_model}', got {event_name}" - break - else: - raise Exception(f"failed to fingerprint {car_model}") diff --git a/selfdrive/debug/cycle_alerts.py b/selfdrive/debug/cycle_alerts.py index fbac65cac1..ec32306436 100755 --- a/selfdrive/debug/cycle_alerts.py +++ b/selfdrive/debug/cycle_alerts.py @@ -6,8 +6,8 @@ from cereal import car, log import cereal.messaging as messaging from opendbc.car.honda.interface import CarInterface from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.controls.lib.events import ET, Events -from openpilot.selfdrive.controls.lib.alertmanager import AlertManager +from openpilot.selfdrive.selfdrived.events import ET, Events +from openpilot.selfdrive.selfdrived.alertmanager import AlertManager from openpilot.system.manager.process_config import managed_processes EventName = car.OnroadEvent.EventName diff --git a/selfdrive/monitoring/helpers.py b/selfdrive/monitoring/helpers.py index f3dbbd5306..2a7979221a 100644 --- a/selfdrive/monitoring/helpers.py +++ b/selfdrive/monitoring/helpers.py @@ -2,7 +2,7 @@ from math import atan2 from cereal import car import cereal.messaging as messaging -from openpilot.selfdrive.controls.lib.events import Events +from openpilot.selfdrive.selfdrived.events import Events from openpilot.common.numpy_fast import interp from openpilot.common.realtime import DT_DMON from openpilot.common.filter_simple import FirstOrderFilter diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/selfdrived/alertmanager.py similarity index 91% rename from selfdrive/controls/lib/alertmanager.py rename to selfdrive/selfdrived/alertmanager.py index a3b8684871..47d7c29420 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/selfdrived/alertmanager.py @@ -6,10 +6,10 @@ from dataclasses import dataclass from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.events import Alert +from openpilot.selfdrive.selfdrived.events import Alert -with open(os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json")) as f: +with open(os.path.join(BASEDIR, "selfdrive/selfdrived/alerts_offroad.json")) as f: OFFROAD_ALERTS = json.load(f) diff --git a/selfdrive/controls/lib/alerts_offroad.json b/selfdrive/selfdrived/alerts_offroad.json similarity index 100% rename from selfdrive/controls/lib/alerts_offroad.json rename to selfdrive/selfdrived/alerts_offroad.json diff --git a/selfdrive/controls/lib/events.py b/selfdrive/selfdrived/events.py similarity index 98% rename from selfdrive/controls/lib/events.py rename to selfdrive/selfdrived/events.py index d27f02794b..b79a716097 100755 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/selfdrived/events.py @@ -318,10 +318,11 @@ def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: - axes = sm['testJoystick'].axes - gb, steer = list(axes)[:2] if len(axes) else (0., 0.) - vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" - return NormalPermanentAlert("Joystick Mode", vals) + # TODO: add some info back + #axes = sm['testJoystick'].axes + #gb, steer = list(axes)[:2] if len(axes) else (0., 0.) + #vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" + return NormalPermanentAlert("Joystick Mode", "") def personality_changed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: personality = str(personality).title() @@ -342,7 +343,7 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.PERMANENT: NormalPermanentAlert("Joystick Mode"), }, - EventName.controlsInitializing: { + EventName.selfdriveInitializing: { ET.NO_ENTRY: NoEntryAlert("System Initializing"), }, @@ -773,9 +774,9 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.NO_ENTRY: NoEntryAlert("Low Communication Rate Between Processes"), }, - EventName.controlsdLagging: { - ET.SOFT_DISABLE: soft_disable_alert("Controls Lagging"), - ET.NO_ENTRY: NoEntryAlert("Controls Process Lagging: Reboot Your Device"), + EventName.selfdrivedLagging: { + ET.SOFT_DISABLE: soft_disable_alert("System Lagging"), + ET.NO_ENTRY: NoEntryAlert("Selfdrive Process Lagging: Reboot Your Device"), }, # Thrown when manager detects a service exited unexpectedly while driving diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py new file mode 100755 index 0000000000..2abc87ceb9 --- /dev/null +++ b/selfdrive/selfdrived/selfdrived.py @@ -0,0 +1,518 @@ +#!/usr/bin/env python3 +import os +import time +import threading + +import cereal.messaging as messaging + +from cereal import car, log +from msgq.visionipc import VisionIpcClient, VisionStreamType + + +from openpilot.common.git import get_short_branch +from openpilot.common.params import Params +from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper, DT_CTRL +from openpilot.common.swaglog import cloudlog +from openpilot.common.gps import get_gps_location_service + +from openpilot.selfdrive.selfdrived.events import Events, ET +from openpilot.selfdrive.selfdrived.state import StateMachine +from openpilot.selfdrive.selfdrived.alertmanager import AlertManager, set_offroad_alert + +from openpilot.system.hardware import HARDWARE +from openpilot.system.version import get_build_metadata + +REPLAY = "REPLAY" in os.environ +SIMULATION = "SIMULATION" in os.environ +TESTING_CLOSET = "TESTING_CLOSET" in os.environ +IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd"} + +ThermalStatus = log.DeviceState.ThermalStatus +State = log.SelfdriveState.OpenpilotState +PandaType = log.PandaState.PandaType +LaneChangeState = log.LaneChangeState +LaneChangeDirection = log.LaneChangeDirection +EventName = car.OnroadEvent.EventName +ButtonType = car.CarState.ButtonEvent.Type +SafetyModel = car.CarParams.SafetyModel + +IGNORED_SAFETY_MODES = (SafetyModel.silent, SafetyModel.noOutput) +CSID_MAP = {"1": EventName.roadCameraError, "2": EventName.wideRoadCameraError, "0": EventName.driverCameraError} + +def get_startup_event(car_recognized, controller_available, fw_seen): + build_metadata = get_build_metadata() + if build_metadata.openpilot.comma_remote and build_metadata.tested_channel: + event = EventName.startup + else: + event = EventName.startupMaster + + if not car_recognized: + if fw_seen: + event = EventName.startupNoCar + else: + event = EventName.startupNoFw + elif car_recognized and not controller_available: + event = EventName.startupNoControl + return event + + +class SelfdriveD: + def __init__(self): + self.params = Params() + + # Ensure the current branch is cached, otherwise the first cycle lags + self.branch = get_short_branch() + + cloudlog.info("selfdrived is waiting for CarParams") + self.CP = messaging.log_from_bytes(self.params.get("CarParams", block=True), car.CarParams) + cloudlog.info("selfdrived got CarParams") + + # Setup sockets + self.pm = messaging.PubMaster(['selfdriveState', 'onroadEvents']) + + self.gps_location_service = get_gps_location_service(self.params) + self.gps_packets = [self.gps_location_service] + self.sensor_packets = ["accelerometer", "gyroscope"] + self.camera_packets = ["roadCameraState", "driverCameraState", "wideRoadCameraState"] + + self.log_sock = messaging.sub_sock('androidLog') + + # TODO: de-couple selfdrived with card/conflate on carState without introducing controls mismatches + self.car_state_sock = messaging.sub_sock('carState', timeout=20) + + ignore = self.sensor_packets + self.gps_packets + if SIMULATION: + ignore += ['driverCameraState', 'managerState'] + if REPLAY: + # no vipc in replay will make them ignored anyways + ignore += ['roadCameraState', 'wideRoadCameraState'] + self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', + 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', + 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', + 'controlsState', 'carControl', 'driverAssistance'] + \ + self.camera_packets + self.sensor_packets + self.gps_packets, + ignore_alive=ignore, ignore_avg_freq=ignore+['radarState',], + frequency=int(1/DT_CTRL)) + + # read params + self.is_metric = self.params.get_bool("IsMetric") + self.is_ldw_enabled = self.params.get_bool("IsLdwEnabled") + + # detect sound card presence and ensure successful init + sounds_available = HARDWARE.get_sound_card_online() + + car_recognized = self.CP.carName != 'mock' + + # cleanup old params + if not self.CP.experimentalLongitudinalAvailable: + self.params.remove("ExperimentalLongitudinalEnabled") + if not self.CP.openpilotLongitudinalControl: + self.params.remove("ExperimentalMode") + + self.CS_prev = car.CarState.new_message() + self.AM = AlertManager() + self.events = Events() + + self.initialized = False + self.enabled = False + self.active = False + self.mismatch_counter = 0 + self.cruise_mismatch_counter = 0 + self.last_steering_pressed_frame = 0 + self.distance_traveled = 0 + self.last_functional_fan_frame = 0 + self.events_prev = [] + self.logged_comm_issue = None + self.not_running_prev = None + self.experimental_mode = False + self.personality = self.read_personality_param() + self.recalibrating_seen = False + self.state_machine = StateMachine() + + self.startup_event = get_startup_event(car_recognized, not self.CP.passive, len(self.CP.carFw) > 0) + + if not sounds_available: + self.events.add(EventName.soundsUnavailable, static=True) + if not car_recognized: + self.events.add(EventName.carUnrecognized, static=True) + if len(self.CP.carFw) > 0: + set_offroad_alert("Offroad_CarUnrecognized", True) + else: + set_offroad_alert("Offroad_NoFirmware", True) + elif self.CP.passive: + self.events.add(EventName.dashcamMode, static=True) + + # selfdrived is driven by carState, expected at 100Hz + self.rk = Ratekeeper(100, print_delay_threshold=None) + + def set_initial_state(self): + if REPLAY and any(ps.controlsAllowed for ps in self.sm['pandaStates']): + self.state_machine.state = State.enabled + + def update_events(self, CS): + """Compute onroadEvents from carState""" + + self.events.clear() + + if self.sm['controlsState'].lateralControlState.which() == 'debugState': + self.events.add(EventName.joystickDebug) + self.startup_event = None + + # Add startup event + if self.startup_event is not None: + self.events.add(self.startup_event) + self.startup_event = None + + # Don't add any more events if not initialized + if not self.initialized: + self.events.add(EventName.selfdriveInitializing) + return + + # no more events while in dashcam mode + if self.CP.passive: + return + + # Block resume if cruise never previously enabled + resume_pressed = any(be.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for be in CS.buttonEvents) + if not self.CP.pcmCruise and CS.vCruise > 250 and resume_pressed: + self.events.add(EventName.resumeBlocked) + + if not self.CP.notCar: + self.events.add_from_msg(self.sm['driverMonitoringState'].events) + + # Add car events, ignore if CAN isn't valid + if CS.canValid: + self.events.add_from_msg(CS.events) + + # Create events for temperature, disk space, and memory + if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: + self.events.add(EventName.overheat) + if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: + self.events.add(EventName.outOfSpace) + if self.sm['deviceState'].memoryUsagePercent > 90 and not SIMULATION: + self.events.add(EventName.lowMemory) + + # Alert if fan isn't spinning for 5 seconds + if self.sm['peripheralState'].pandaType != log.PandaState.PandaType.unknown: + if self.sm['peripheralState'].fanSpeedRpm < 500 and self.sm['deviceState'].fanSpeedPercentDesired > 50: + # allow enough time for the fan controller in the panda to recover from stalls + if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 15.0: + self.events.add(EventName.fanMalfunction) + else: + self.last_functional_fan_frame = self.sm.frame + + # Handle calibration status + cal_status = self.sm['liveCalibration'].calStatus + if cal_status != log.LiveCalibrationData.Status.calibrated: + if cal_status == log.LiveCalibrationData.Status.uncalibrated: + self.events.add(EventName.calibrationIncomplete) + elif cal_status == log.LiveCalibrationData.Status.recalibrating: + if not self.recalibrating_seen: + set_offroad_alert("Offroad_Recalibration", True) + self.recalibrating_seen = True + self.events.add(EventName.calibrationRecalibrating) + else: + self.events.add(EventName.calibrationInvalid) + + # Lane departure warning + if self.is_ldw_enabled and self.sm.valid['driverAssistance']: + if self.sm['driverAssistance'].leftLaneDeparture or self.sm['driverAssistance'].rightLaneDeparture: + self.events.add(EventName.ldw) + + # Handle lane change + if self.sm['modelV2'].meta.laneChangeState == LaneChangeState.preLaneChange: + direction = self.sm['modelV2'].meta.laneChangeDirection + if (CS.leftBlindspot and direction == LaneChangeDirection.left) or \ + (CS.rightBlindspot and direction == LaneChangeDirection.right): + self.events.add(EventName.laneChangeBlocked) + else: + if direction == LaneChangeDirection.left: + self.events.add(EventName.preLaneChangeLeft) + else: + self.events.add(EventName.preLaneChangeRight) + elif self.sm['modelV2'].meta.laneChangeState in (LaneChangeState.laneChangeStarting, + LaneChangeState.laneChangeFinishing): + self.events.add(EventName.laneChange) + + for i, pandaState in enumerate(self.sm['pandaStates']): + # All pandas must match the list of safetyConfigs, and if outside this list, must be silent or noOutput + if i < len(self.CP.safetyConfigs): + safety_mismatch = pandaState.safetyModel != self.CP.safetyConfigs[i].safetyModel or \ + pandaState.safetyParam != self.CP.safetyConfigs[i].safetyParam or \ + pandaState.alternativeExperience != self.CP.alternativeExperience + else: + safety_mismatch = pandaState.safetyModel not in IGNORED_SAFETY_MODES + + # safety mismatch allows some time for pandad to set the safety mode and publish it back from panda + if (safety_mismatch and self.sm.frame*DT_CTRL > 10.) or pandaState.safetyRxChecksInvalid or self.mismatch_counter >= 200: + self.events.add(EventName.controlsMismatch) + + if log.PandaState.FaultType.relayMalfunction in pandaState.faults: + self.events.add(EventName.relayMalfunction) + + # Handle HW and system malfunctions + # Order is very intentional here. Be careful when modifying this. + # All events here should at least have NO_ENTRY and SOFT_DISABLE. + num_events = len(self.events) + + not_running = {p.name for p in self.sm['managerState'].processes if not p.running and p.shouldBeRunning} + if self.sm.recv_frame['managerState'] and (not_running - IGNORE_PROCESSES): + self.events.add(EventName.processNotRunning) + if not_running != self.not_running_prev: + cloudlog.event("process_not_running", not_running=not_running, error=True) + self.not_running_prev = not_running + else: + if not SIMULATION and not self.rk.lagging: + if not self.sm.all_alive(self.camera_packets): + self.events.add(EventName.cameraMalfunction) + elif not self.sm.all_freq_ok(self.camera_packets): + self.events.add(EventName.cameraFrameRate) + if not REPLAY and self.rk.lagging: + self.events.add(EventName.selfdrivedLagging) + if len(self.sm['radarState'].radarErrors) or ((not self.rk.lagging or REPLAY) and not self.sm.all_checks(['radarState'])): + self.events.add(EventName.radarFault) + if not self.sm.valid['pandaStates']: + self.events.add(EventName.usbError) + if CS.canTimeout: + self.events.add(EventName.canBusMissing) + elif not CS.canValid: + self.events.add(EventName.canError) + + # generic catch-all. ideally, a more specific event should be added above instead + has_disable_events = self.events.contains(ET.NO_ENTRY) and (self.events.contains(ET.SOFT_DISABLE) or self.events.contains(ET.IMMEDIATE_DISABLE)) + no_system_errors = (not has_disable_events) or (len(self.events) == num_events) + if not self.sm.all_checks() and no_system_errors: + if not self.sm.all_alive(): + self.events.add(EventName.commIssue) + elif not self.sm.all_freq_ok(): + self.events.add(EventName.commIssueAvgFreq) + else: + self.events.add(EventName.commIssue) + + logs = { + 'invalid': [s for s, valid in self.sm.valid.items() if not valid], + 'not_alive': [s for s, alive in self.sm.alive.items() if not alive], + 'not_freq_ok': [s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok], + } + if logs != self.logged_comm_issue: + cloudlog.event("commIssue", error=True, **logs) + self.logged_comm_issue = logs + else: + self.logged_comm_issue = None + + if not self.CP.notCar: + if not self.sm['livePose'].posenetOK: + self.events.add(EventName.posenetInvalid) + if not self.sm['livePose'].inputsOK: + self.events.add(EventName.locationdTemporaryError) + if not self.sm['liveParameters'].valid and not TESTING_CLOSET and (not SIMULATION or REPLAY): + self.events.add(EventName.paramsdTemporaryError) + + # conservative HW alert. if the data or frequency are off, locationd will throw an error + if any((self.sm.frame - self.sm.recv_frame[s])*DT_CTRL > 10. for s in self.sensor_packets): + self.events.add(EventName.sensorDataInvalid) + + if not REPLAY: + # Check for mismatch between openpilot and car's PCM + cruise_mismatch = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) + self.cruise_mismatch_counter = self.cruise_mismatch_counter + 1 if cruise_mismatch else 0 + if self.cruise_mismatch_counter > int(6. / DT_CTRL): + self.events.add(EventName.cruiseMismatch) + + # Send a "steering required alert" if saturation count has reached the limit + if CS.steeringPressed: + self.last_steering_pressed_frame = self.sm.frame + recent_steer_pressed = (self.sm.frame - self.last_steering_pressed_frame)*DT_CTRL < 2.0 + lac = getattr(self.sm['controlsState'].lateralControlState, self.sm['controlsState'].lateralControlState.which()) + if lac.active and not recent_steer_pressed and not self.CP.notCar: + if self.CP.lateralTuning.which() == 'torque': + undershooting = abs(lac.desiredLateralAccel) / abs(1e-3 + lac.actualLateralAccel) > 1.2 + turning = abs(lac.desiredLateralAccel) > 1.0 + good_speed = CS.vEgo > 5 + max_torque = abs(self.sm['carOutput'].actuatorsOutput.steer) > 0.99 + if undershooting and turning and good_speed and max_torque: + self.events.add(EventName.steerSaturated) + elif lac.saturated: + # TODO probably should not use dpath_points but curvature + dpath_points = self.sm['modelV2'].position.y + if len(dpath_points): + # Check if we deviated from the path + # TODO use desired vs actual curvature + if self.CP.steerControlType == car.CarParams.SteerControlType.angle: + steering_value = self.sm['carControl'].actuators.steeringAngleDeg + else: + steering_value = self.sm['carControl'].actuators.steer + + left_deviation = steering_value > 0 and dpath_points[0] < -0.20 + right_deviation = steering_value < 0 and dpath_points[0] > 0.20 + if left_deviation or right_deviation: + self.events.add(EventName.steerSaturated) + + # Check for FCW + stock_long_is_braking = self.enabled and not self.CP.openpilotLongitudinalControl and CS.aEgo < -1.25 + model_fcw = self.sm['modelV2'].meta.hardBrakePredicted and not CS.brakePressed and not stock_long_is_braking + planner_fcw = self.sm['longitudinalPlan'].fcw and self.enabled + if (planner_fcw or model_fcw) and not self.CP.notCar: + self.events.add(EventName.fcw) + + # Camera errors from the kernel + for m in messaging.drain_sock(self.log_sock, wait_for_one=False): + try: + msg = m.androidLog.message + if any(err in msg for err in ("ERROR_CRC", "ERROR_ECC", "ERROR_STREAM_UNDERFLOW", "APPLY FAILED")): + csid = msg.split("CSID:")[-1].split(" ")[0] + evt = CSID_MAP.get(csid, None) + if evt is not None: + self.events.add(evt) + except UnicodeDecodeError: + pass + + # TODO: fix simulator + if not SIMULATION or REPLAY: + # Not show in first 1.5 km to allow for driving out of garage. This event shows after 5 minutes + gps_ok = self.sm.recv_frame[self.gps_location_service] > 0 and (self.sm.frame - self.sm.recv_frame[self.gps_location_service]) * DT_CTRL < 2.0 + if not gps_ok and self.sm['livePose'].inputsOK and (self.distance_traveled > 1500): + self.events.add(EventName.noGps) + if gps_ok: + self.distance_traveled = 0 + self.distance_traveled += CS.vEgo * DT_CTRL + + if self.sm['modelV2'].frameDropPerc > 20: + self.events.add(EventName.modeldLagging) + + # decrement personality on distance button press + if self.CP.openpilotLongitudinalControl: + if any(not be.pressed and be.type == ButtonType.gapAdjustCruise for be in CS.buttonEvents): + self.personality = (self.personality - 1) % 3 + self.params.put_nonblocking('LongitudinalPersonality', str(self.personality)) + self.events.add(EventName.personalityChanged) + + def data_sample(self): + car_state = messaging.recv_one(self.car_state_sock) + CS = car_state.carState if car_state else self.CS_prev + + self.sm.update(0) + + if not self.initialized: + all_valid = CS.canValid and self.sm.all_checks() + timed_out = self.sm.frame * DT_CTRL > 6. + if all_valid or timed_out or (SIMULATION and not REPLAY): + available_streams = VisionIpcClient.available_streams("camerad", block=False) + if VisionStreamType.VISION_STREAM_ROAD not in available_streams: + self.sm.ignore_alive.append('roadCameraState') + if VisionStreamType.VISION_STREAM_WIDE_ROAD not in available_streams: + self.sm.ignore_alive.append('wideRoadCameraState') + + self.initialized = True + self.set_initial_state() + + cloudlog.event( + "selfdrived.initialized", + dt=self.sm.frame*DT_CTRL, + timeout=timed_out, + canValid=CS.canValid, + invalid=[s for s, valid in self.sm.valid.items() if not valid], + not_alive=[s for s, alive in self.sm.alive.items() if not alive], + not_freq_ok=[s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok], + error=True, + ) + + # When the panda and selfdrived do not agree on controls_allowed + # we want to disengage openpilot. However the status from the panda goes through + # another socket other than the CAN messages and one can arrive earlier than the other. + # Therefore we allow a mismatch for two samples, then we trigger the disengagement. + if not self.enabled: + self.mismatch_counter = 0 + + # All pandas not in silent mode must have controlsAllowed when openpilot is enabled + if self.enabled and any(not ps.controlsAllowed for ps in self.sm['pandaStates'] + if ps.safetyModel not in IGNORED_SAFETY_MODES): + self.mismatch_counter += 1 + + return CS + + def update_alerts(self, CS): + clear_event_types = set() + if ET.WARNING not in self.state_machine.current_alert_types: + clear_event_types.add(ET.WARNING) + if self.enabled: + clear_event_types.add(ET.NO_ENTRY) + + pers = {v: k for k, v in log.LongitudinalPersonality.schema.enumerants.items()}[self.personality] + alerts = self.events.create_alerts(self.state_machine.current_alert_types, [self.CP, CS, self.sm, self.is_metric, + self.state_machine.soft_disable_timer, pers]) + self.AM.add_many(self.sm.frame, alerts) + self.AM.process_alerts(self.sm.frame, clear_event_types) + + def publish_selfdriveState(self, CS): + # selfdriveState + ss_msg = messaging.new_message('selfdriveState') + ss_msg.valid = True + ss = ss_msg.selfdriveState + if self.AM.current_alert: + ss.alertText1 = self.AM.current_alert.alert_text_1 + ss.alertText2 = self.AM.current_alert.alert_text_2 + ss.alertSize = self.AM.current_alert.alert_size + ss.alertStatus = self.AM.current_alert.alert_status + ss.alertType = self.AM.current_alert.alert_type + ss.alertSound = self.AM.current_alert.audible_alert + ss.enabled = self.enabled + ss.active = self.active + ss.state = self.state_machine.state + ss.engageable = not self.events.contains(ET.NO_ENTRY) + ss.experimentalMode = self.experimental_mode + ss.personality = self.personality + self.pm.send('selfdriveState', ss_msg) + + # onroadEvents - logged every second or on change + if (self.sm.frame % int(1. / DT_CTRL) == 0) or (self.events.names != self.events_prev): + ce_send = messaging.new_message('onroadEvents', len(self.events)) + ce_send.valid = True + ce_send.onroadEvents = self.events.to_msg() + self.pm.send('onroadEvents', ce_send) + self.events_prev = self.events.names.copy() + + def step(self): + CS = self.data_sample() + self.update_events(CS) + if not self.CP.passive and self.initialized: + self.enabled, self.active = self.state_machine.update(self.events) + self.update_alerts(CS) + + self.publish_selfdriveState(CS) + + self.CS_prev = CS + + def read_personality_param(self): + try: + return int(self.params.get('LongitudinalPersonality')) + except (ValueError, TypeError): + return log.LongitudinalPersonality.standard + + def params_thread(self, evt): + while not evt.is_set(): + self.is_metric = self.params.get_bool("IsMetric") + self.experimental_mode = self.params.get_bool("ExperimentalMode") and self.CP.openpilotLongitudinalControl + self.personality = self.read_personality_param() + time.sleep(0.1) + + def run(self): + e = threading.Event() + t = threading.Thread(target=self.params_thread, args=(e, )) + try: + t.start() + while True: + self.step() + self.rk.monitor_time() + finally: + e.set() + t.join() + + +def main(): + config_realtime_process(4, Priority.CTRL_HIGH) + s = SelfdriveD() + s.run() + +if __name__ == "__main__": + main() diff --git a/selfdrive/controls/lib/selfdrive.py b/selfdrive/selfdrived/state.py similarity index 98% rename from selfdrive/controls/lib/selfdrive.py rename to selfdrive/selfdrived/state.py index adbcd1d926..073ddb56eb 100644 --- a/selfdrive/controls/lib/selfdrive.py +++ b/selfdrive/selfdrived/state.py @@ -1,5 +1,5 @@ from cereal import log -from openpilot.selfdrive.controls.lib.events import Events, ET +from openpilot.selfdrive.selfdrived.events import Events, ET from openpilot.common.realtime import DT_CTRL State = log.SelfdriveState.OpenpilotState diff --git a/selfdrive/controls/lib/tests/test_alertmanager.py b/selfdrive/selfdrived/tests/test_alertmanager.py similarity index 89% rename from selfdrive/controls/lib/tests/test_alertmanager.py rename to selfdrive/selfdrived/tests/test_alertmanager.py index bc0da0da8c..20bf4e8903 100644 --- a/selfdrive/controls/lib/tests/test_alertmanager.py +++ b/selfdrive/selfdrived/tests/test_alertmanager.py @@ -1,7 +1,7 @@ import random -from openpilot.selfdrive.controls.lib.events import Alert, EVENTS -from openpilot.selfdrive.controls.lib.alertmanager import AlertManager +from openpilot.selfdrive.selfdrived.events import Alert, EVENTS +from openpilot.selfdrive.selfdrived.alertmanager import AlertManager class TestAlertManager: diff --git a/selfdrive/controls/tests/test_alerts.py b/selfdrive/selfdrived/tests/test_alerts.py similarity index 94% rename from selfdrive/controls/tests/test_alerts.py rename to selfdrive/selfdrived/tests/test_alerts.py index 52d71dc22d..a5249cc03f 100644 --- a/selfdrive/controls/tests/test_alerts.py +++ b/selfdrive/selfdrived/tests/test_alerts.py @@ -8,13 +8,13 @@ from cereal import log, car from cereal.messaging import SubMaster from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.events import Alert, EVENTS, ET -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.events import Alert, EVENTS, ET +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS AlertSize = log.SelfdriveState.AlertSize -OFFROAD_ALERTS_PATH = os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json") +OFFROAD_ALERTS_PATH = os.path.join(BASEDIR, "selfdrive/selfdrived/alerts_offroad.json") # TODO: add callback alerts ALERTS = [] diff --git a/selfdrive/controls/tests/test_state_machine.py b/selfdrive/selfdrived/tests/test_state_machine.py similarity index 97% rename from selfdrive/controls/tests/test_state_machine.py rename to selfdrive/selfdrived/tests/test_state_machine.py index d2117b3342..4274ba9f67 100644 --- a/selfdrive/controls/tests/test_state_machine.py +++ b/selfdrive/selfdrived/tests/test_state_machine.py @@ -1,7 +1,7 @@ from cereal import log from openpilot.common.realtime import DT_CTRL from openpilot.selfdrive.controls.lib.selfdrive import StateMachine, SOFT_DISABLE_TIME -from openpilot.selfdrive.controls.lib.events import Events, ET, EVENTS, NormalPermanentAlert +from openpilot.selfdrive.selfdrived.events import Events, ET, EVENTS, NormalPermanentAlert State = log.SelfdriveState.OpenpilotState diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py index 14af9672d0..13d51a636f 100755 --- a/selfdrive/test/process_replay/compare_logs.py +++ b/selfdrive/test/process_replay/compare_logs.py @@ -141,7 +141,7 @@ def format_diff(results, log_paths, ref_commit): if __name__ == "__main__": log1 = list(LogReader(sys.argv[1])) log2 = list(LogReader(sys.argv[2])) - ignore_fields = sys.argv[3:] or ["logMonoTime", "controlsState.cumLagMs"] + ignore_fields = sys.argv[3:] or ["logMonoTime"] results = {"segment": {"proc": compare_logs(log1, log2, ignore_fields)}} log_paths = {"segment": {"proc": {"ref": sys.argv[1], "new": sys.argv[2]}}} diff_short, diff_long, failed = format_diff(results, log_paths, None) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 39fec7b669..a2ba4a5787 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -373,7 +373,7 @@ def get_car_params_callback(rc, pm, msgs, fingerprint): params.put("CarParams", convert_to_capnp(CP).to_bytes()) -def controlsd_rcv_callback(msg, cfg, frame): +def selfdrived_rcv_callback(msg, cfg, frame): return (frame - 1) == 0 or msg.which() == 'carState' @@ -452,7 +452,7 @@ class FrequencyBasedRcvCallback: return bool(len(resp_sockets)) -def controlsd_config_callback(params, cfg, lr): +def selfdrived_config_callback(params, cfg, lr): ublox = params.get_bool("UbloxAvailable") sub_keys = ({"gpsLocation", } if ublox else {"gpsLocationExternal", }) @@ -461,22 +461,33 @@ def controlsd_config_callback(params, cfg, lr): CONFIGS = [ ProcessConfig( - proc_name="controlsd", + proc_name="selfdrived", pubs=[ "carState", "deviceState", "pandaStates", "peripheralState", "liveCalibration", "driverMonitoringState", "longitudinalPlan", "livePose", "liveParameters", "radarState", "modelV2", "driverCameraState", "roadCameraState", "wideRoadCameraState", "managerState", - "testJoystick", "liveTorqueParameters", "accelerometer", "gyroscope", "carOutput", - "gpsLocationExternal", "gpsLocation", "driverAssistance" + "liveTorqueParameters", "accelerometer", "gyroscope", "carOutput", + "gpsLocationExternal", "gpsLocation", "controlsState", "carControl", "driverAssistance", ], - subs=["selfdriveState", "controlsState", "carControl", "onroadEvents"], - ignore=["logMonoTime", "controlsState.cumLagMs"], - config_callback=controlsd_config_callback, + subs=["selfdriveState", "onroadEvents"], + ignore=["logMonoTime"], + config_callback=selfdrived_config_callback, init_callback=get_car_params_callback, - should_recv_callback=controlsd_rcv_callback, + should_recv_callback=selfdrived_rcv_callback, tolerance=NUMPY_TOLERANCE, processing_time=0.004, ), + ProcessConfig( + proc_name="controlsd", + pubs=["liveParameters", "liveTorqueParameters", "modelV2", "selfdriveState", + "liveCalibration", "livePose", "longitudinalPlan", "carState", "carOutput", + "driverMonitoringState", "onroadEvents", "driverAssistance"], + subs=["carControl", "controlsState"], + ignore=["logMonoTime", ], + init_callback=get_car_params_callback, + should_recv_callback=MessageBasedRcvCallback("carState"), + tolerance=NUMPY_TOLERANCE, + ), ProcessConfig( proc_name="card", pubs=["pandaStates", "carControl", "onroadEvents", "can"], diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 9ff5403d3c..b866e015ac 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -fc1344b16b802cdb4ec542791f3b4d76a82da68b \ No newline at end of file +eac137f456f25bf138677315b7c4907e2fe9971b \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_fuzzy.py b/selfdrive/test/process_replay/test_fuzzy.py index d938839039..39e3bfb94a 100644 --- a/selfdrive/test/process_replay/test_fuzzy.py +++ b/selfdrive/test/process_replay/test_fuzzy.py @@ -11,7 +11,7 @@ import openpilot.selfdrive.test.process_replay.process_replay as pr # These processes currently fail because of unrealistic data breaking assumptions # that openpilot makes causing error with NaN, inf, int size, array indexing ... # TODO: Make each one testable -NOT_TESTED = ['controlsd', 'card', 'plannerd', 'calibrationd', 'dmonitoringd', 'paramsd', 'dmonitoringmodeld', 'modeld'] +NOT_TESTED = ['selfdrived', 'controlsd', 'card', 'plannerd', 'calibrationd', 'dmonitoringd', 'paramsd', 'dmonitoringmodeld', 'modeld'] TEST_CASES = [(cfg.proc_name, copy.deepcopy(cfg)) for cfg in pr.CONFIGS if cfg.proc_name not in NOT_TESTED] diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 702de4f7d1..50c34a190f 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -12,7 +12,7 @@ from openpilot.common.git import get_commit from openpilot.tools.lib.openpilotci import get_url, upload_file from openpilot.selfdrive.test.process_replay.compare_logs import compare_logs, format_diff from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS, PROC_REPLAY_DIR, FAKEDATA, replay_process, \ - check_openpilot_enabled, check_most_messages_valid + check_most_messages_valid from openpilot.tools.lib.filereader import FileReader from openpilot.tools.lib.logreader import LogReader, save_log @@ -103,10 +103,6 @@ def test_process(cfg, lr, segment, ref_log_path, new_log_path, ignore_fields=Non except Exception as e: raise Exception("failed on segment: " + segment) from e - # check to make sure openpilot is engaged in the route - if cfg.proc_name == "controlsd": - if not check_openpilot_enabled(log_msgs): - return f"Route did not enable at all or for long enough: {new_log_path}", log_msgs if not check_most_messages_valid(log_msgs): return f"Route did not have enough valid messages: {new_log_path}", log_msgs diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 7fe26b739f..d4ec3c2fff 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -19,7 +19,7 @@ from cereal.services import SERVICE_LIST from openpilot.common.basedir import BASEDIR from openpilot.common.timeout import Timeout from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.events import EVENTS, ET +from openpilot.selfdrive.selfdrived.events import EVENTS, ET from openpilot.selfdrive.test.helpers import set_params_enabled, release_only from openpilot.system.hardware import HARDWARE from openpilot.system.hardware.hw import Paths @@ -35,7 +35,8 @@ CPU usage budget MAX_TOTAL_CPU = 260. # total for all 8 cores PROCS = { # Baseline CPU usage by process - "selfdrive.controls.controlsd": 32.0, + "selfdrive.controls.controlsd": 18.0, + "selfdrive.selfdrived.selfdrived": 21.0, "selfdrive.car.card": 30.0, "./loggerd": 14.0, "./encoderd": 17.0, @@ -87,6 +88,7 @@ TIMINGS = { "carControl": [2.5, 0.35], "controlsState": [2.5, 0.35], "longitudinalPlan": [2.5, 0.5], + "driverAssistance": [2.5, 0.5], "roadCameraState": [2.5, 0.35], "driverCameraState": [2.5, 0.35], "modelV2": [2.5, 0.35], diff --git a/selfdrive/test/test_time_to_onroad.py b/selfdrive/test/test_time_to_onroad.py index 58e6cc3ccf..d3692eabe2 100644 --- a/selfdrive/test/test_time_to_onroad.py +++ b/selfdrive/test/test_time_to_onroad.py @@ -20,7 +20,7 @@ def test_time_to_onroad(): proc = subprocess.Popen(["python", manager_path]) start_time = time.monotonic() - sm = messaging.SubMaster(['selfdriveState', 'controlsState', 'deviceState', 'onroadEvents']) + sm = messaging.SubMaster(['selfdriveState', 'deviceState', 'onroadEvents']) try: # wait for onroad. timeout assumes panda is up to date with Timeout(10, "timed out waiting to go onroad"): @@ -34,7 +34,7 @@ def test_time_to_onroad(): while True: sm.update(100) - if sm.seen['onroadEvents'] and not any(EventName.controlsInitializing == e.name for e in sm['onroadEvents']): + if sm.seen['onroadEvents'] and not any(EventName.selfdriveInitializing == e.name for e in sm['onroadEvents']): initialized = True if initialized: @@ -51,7 +51,6 @@ def test_time_to_onroad(): sm.update(100) assert sm.all_alive(), sm.alive assert sm['selfdriveState'].engageable, f"events: {sm['onroadEvents']}" - assert sm['controlsState'].cumLagMs < 10. finally: proc.terminate() if proc.wait(20) is None: diff --git a/selfdrive/ui/qt/widgets/offroad_alerts.cc b/selfdrive/ui/qt/widgets/offroad_alerts.cc index 74ece36d15..f630875978 100644 --- a/selfdrive/ui/qt/widgets/offroad_alerts.cc +++ b/selfdrive/ui/qt/widgets/offroad_alerts.cc @@ -70,7 +70,7 @@ AbstractAlert::AbstractAlert(bool hasRebootBtn, QWidget *parent) : QFrame(parent int OffroadAlert::refresh() { // build widgets for each offroad alert on first refresh if (alerts.empty()) { - QString json = util::read_file("../controls/lib/alerts_offroad.json").c_str(); + QString json = util::read_file("../selfdrived/alerts_offroad.json").c_str(); QJsonObject obj = QJsonDocument::fromJson(json.toUtf8()).object(); // descending sort labels by severity diff --git a/selfdrive/ui/tests/cycle_offroad_alerts.py b/selfdrive/ui/tests/cycle_offroad_alerts.py index 75b19ceb90..e468d88e0e 100755 --- a/selfdrive/ui/tests/cycle_offroad_alerts.py +++ b/selfdrive/ui/tests/cycle_offroad_alerts.py @@ -6,12 +6,12 @@ import json from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert if __name__ == "__main__": params = Params() - with open(os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json")) as f: + with open(os.path.join(BASEDIR, "selfdrive/selfdrived/alerts_offroad.json")) as f: offroad_alerts = json.load(f) t = 10 if len(sys.argv) < 2 else int(sys.argv[1]) diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 2bf30d7b90..5050adfd98 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -17,7 +17,7 @@ from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params from openpilot.common.prefix import OpenpilotPrefix from openpilot.common.transformations.camera import CameraConfig, DEVICE_CAMERAS -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.selfdrive.test.helpers import with_processes from openpilot.selfdrive.test.process_replay.migration import migrate_controlsState from openpilot.tools.lib.logreader import LogReader diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py index f13c65fdae..65880bdad9 100755 --- a/selfdrive/ui/update_translations.py +++ b/selfdrive/ui/update_translations.py @@ -16,7 +16,7 @@ def generate_translations_include(): # offroad alerts # TODO translate events from openpilot.selfdrive/controls/lib/events.py content = "// THIS IS AN AUTOGENERATED FILE, PLEASE EDIT alerts_offroad.json\n" - with open(os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json")) as f: + with open(os.path.join(BASEDIR, "selfdrive/selfdrived/alerts_offroad.json")) as f: for alert in json.load(f).values(): content += f'QT_TRANSLATE_NOOP("OffroadAlert", R"({alert["text"]})");\n' diff --git a/system/athena/registration.py b/system/athena/registration.py index 06ecd0b9d4..a1e8605a9d 100755 --- a/system/athena/registration.py +++ b/system/athena/registration.py @@ -8,7 +8,7 @@ from datetime import datetime, timedelta, UTC from openpilot.common.api import api_get from openpilot.common.params import Params from openpilot.common.spinner import Spinner -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.system.hardware import HARDWARE, PC from openpilot.system.hardware.hw import Paths from openpilot.common.swaglog import cloudlog diff --git a/system/camerad/snapshot/snapshot.py b/system/camerad/snapshot/snapshot.py index 4ba38c1df4..b3369891d7 100755 --- a/system/camerad/snapshot/snapshot.py +++ b/system/camerad/snapshot/snapshot.py @@ -10,7 +10,7 @@ from msgq.visionipc import VisionIpcClient, VisionStreamType from openpilot.common.params import Params from openpilot.common.realtime import DT_MDL from openpilot.system.hardware import PC -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.system.manager.process_config import managed_processes diff --git a/system/hardware/hardwared.py b/system/hardware/hardwared.py index 34e58315d0..9ebb9c9d54 100755 --- a/system/hardware/hardwared.py +++ b/system/hardware/hardwared.py @@ -16,7 +16,7 @@ from openpilot.common.dict_helpers import strip_deprecated_keys from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.params import Params from openpilot.common.realtime import DT_HW -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.system.hardware import HARDWARE, TICI, AGNOS from openpilot.system.loggerd.config import get_available_percent from openpilot.system.statsd import statlog diff --git a/system/manager/process_config.py b/system/manager/process_config.py index 4688951620..8af376c624 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -64,6 +64,7 @@ procs = [ PythonProcess("calibrationd", "selfdrive.locationd.calibrationd", only_onroad), PythonProcess("torqued", "selfdrive.locationd.torqued", only_onroad), PythonProcess("controlsd", "selfdrive.controls.controlsd", only_onroad), + PythonProcess("selfdrived", "selfdrive.selfdrived.selfdrived", only_onroad), PythonProcess("card", "selfdrive.car.card", only_onroad), PythonProcess("deleter", "system.loggerd.deleter", always_run), PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", driverview, enabled=(not PC or WEBCAM)), diff --git a/system/updated/updated.py b/system/updated/updated.py index 005c52bc8b..6f9fe173d8 100755 --- a/system/updated/updated.py +++ b/system/updated/updated.py @@ -17,7 +17,7 @@ from openpilot.common.params import Params from openpilot.common.time import system_time_valid from openpilot.common.markdown import parse_markdown from openpilot.common.swaglog import cloudlog -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.system.hardware import AGNOS, HARDWARE from openpilot.system.version import get_build_metadata From 590e217368c159589c7f768d4226bb22f7a59a94 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 6 Sep 2024 18:21:41 -0700 Subject: [PATCH 013/214] selfdrived cleanup (#33497) * selfdrived cleanup * lil more * always alert * bring this back --- cereal/car.capnp | 10 ++-- selfdrive/selfdrived/alertmanager.py | 7 ++- selfdrive/selfdrived/alerts_offroad.json | 4 -- selfdrive/selfdrived/events.py | 34 +---------- selfdrive/selfdrived/selfdrived.py | 74 +++++++----------------- selfdrive/ui/translations/main_ar.ts | 4 -- selfdrive/ui/translations/main_de.ts | 4 -- selfdrive/ui/translations/main_es.ts | 4 -- selfdrive/ui/translations/main_fr.ts | 4 -- selfdrive/ui/translations/main_ja.ts | 4 -- selfdrive/ui/translations/main_ko.ts | 4 -- selfdrive/ui/translations/main_pt-BR.ts | 4 -- selfdrive/ui/translations/main_th.ts | 4 -- selfdrive/ui/translations/main_tr.ts | 4 -- selfdrive/ui/translations/main_zh-CHS.ts | 4 -- selfdrive/ui/translations/main_zh-CHT.ts | 4 -- 16 files changed, 31 insertions(+), 142 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index 6da9c14c32..cfaa2238c8 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -87,7 +87,6 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { startupNoCar @76; startupNoControl @77; startupMaster @78; - startupNoFw @104; fcw @79; steerSaturated @80; belowEngageSpeed @84; @@ -102,10 +101,6 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { dashcamMode @96; selfdriveInitializing @98; usbError @99; - roadCameraError @100; - driverCameraError @101; - wideRoadCameraError @102; - highCpuUsage @105; cruiseMismatch @106; lkasDisabled @107; canBusMissing @111; @@ -147,6 +142,11 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { brakeUnavailableDEPRECATED @2; plannerErrorDEPRECATED @32; gpsMalfunctionDEPRECATED @94; + roadCameraErrorDEPRECATED @100; + driverCameraErrorDEPRECATED @101; + wideRoadCameraErrorDEPRECATED @102; + highCpuUsageDEPRECATED @105; + startupNoFwDEPRECATED @104; } } diff --git a/selfdrive/selfdrived/alertmanager.py b/selfdrive/selfdrived/alertmanager.py index 47d7c29420..4a406d3962 100644 --- a/selfdrive/selfdrived/alertmanager.py +++ b/selfdrive/selfdrived/alertmanager.py @@ -6,7 +6,7 @@ from dataclasses import dataclass from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params -from openpilot.selfdrive.selfdrived.events import Alert +from openpilot.selfdrive.selfdrived.events import Alert, EmptyAlert with open(os.path.join(BASEDIR, "selfdrive/selfdrived/alerts_offroad.json")) as f: @@ -31,10 +31,11 @@ class AlertEntry: def active(self, frame: int) -> bool: return frame <= self.end_frame + class AlertManager: def __init__(self): self.alerts: dict[str, AlertEntry] = defaultdict(AlertEntry) - self.current_alert: Alert | None = None + self.current_alert = EmptyAlert def add_many(self, frame: int, alerts: list[Alert]) -> None: for alert in alerts: @@ -59,4 +60,4 @@ class AlertManager: if v.active(frame) and greater: ae = v - self.current_alert = ae.alert + self.current_alert = ae.alert if ae.alert is not None else EmptyAlert diff --git a/selfdrive/selfdrived/alerts_offroad.json b/selfdrive/selfdrived/alerts_offroad.json index 6fb6c569b0..86e07d3213 100644 --- a/selfdrive/selfdrived/alerts_offroad.json +++ b/selfdrive/selfdrived/alerts_offroad.json @@ -41,10 +41,6 @@ "text": "openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai.", "severity": 0 }, - "Offroad_NoFirmware": { - "text": "openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai.", - "severity": 0 - }, "Offroad_Recalibration": { "text": "openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield.", "severity": 0 diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index b79a716097..9128f1acd8 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -141,6 +141,8 @@ class Alert: return False return self.priority > alert2.priority +EmptyAlert = Alert("" , "", AlertStatus.normal, AlertSize.none, Priority.LOWEST, + VisualAlert.none, AudibleAlert.none, 0) class NoEntryAlert(Alert): def __init__(self, alert_text_2: str, @@ -355,23 +357,15 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.PERMANENT: startup_master_alert, }, - # Car is recognized, but marked as dashcam only EventName.startupNoControl: { ET.PERMANENT: StartupAlert("Dashcam mode"), ET.NO_ENTRY: NoEntryAlert("Dashcam mode"), }, - # Car is not recognized EventName.startupNoCar: { ET.PERMANENT: StartupAlert("Dashcam mode for unsupported car"), }, - EventName.startupNoFw: { - ET.PERMANENT: StartupAlert("Car Unrecognized", - "Check comma power connections", - alert_status=AlertStatus.userPrompt), - }, - EventName.dashcamMode: { ET.PERMANENT: NormalPermanentAlert("Dashcam Mode", priority=Priority.LOWEST), @@ -822,12 +816,6 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.NO_ENTRY: NoEntryAlert("Low Memory: Reboot Your Device"), }, - EventName.highCpuUsage: { - #ET.SOFT_DISABLE: soft_disable_alert("System Malfunction: Reboot Your Device"), - #ET.PERMANENT: NormalPermanentAlert("System Malfunction", "Reboot your Device"), - ET.NO_ENTRY: high_cpu_usage_alert, - }, - EventName.accFaulted: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Cruise Fault: Restart the Car"), ET.PERMANENT: NormalPermanentAlert("Cruise Fault: Restart the car to engage"), @@ -844,24 +832,6 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.NO_ENTRY: NoEntryAlert("Controls Mismatch"), }, - EventName.roadCameraError: { - ET.PERMANENT: NormalPermanentAlert("Camera CRC Error - Road", - duration=1., - creation_delay=30.), - }, - - EventName.wideRoadCameraError: { - ET.PERMANENT: NormalPermanentAlert("Camera CRC Error - Road Fisheye", - duration=1., - creation_delay=30.), - }, - - EventName.driverCameraError: { - ET.PERMANENT: NormalPermanentAlert("Camera CRC Error - Driver", - duration=1., - creation_delay=30.), - }, - # Sometimes the USB stack on the device can get into a bad state # causing the connection to the panda to be lost EventName.usbError: { diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 2abc87ceb9..545688c60b 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -9,7 +9,6 @@ from cereal import car, log from msgq.visionipc import VisionIpcClient, VisionStreamType -from openpilot.common.git import get_short_branch from openpilot.common.params import Params from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper, DT_CTRL from openpilot.common.swaglog import cloudlog @@ -37,23 +36,6 @@ ButtonType = car.CarState.ButtonEvent.Type SafetyModel = car.CarParams.SafetyModel IGNORED_SAFETY_MODES = (SafetyModel.silent, SafetyModel.noOutput) -CSID_MAP = {"1": EventName.roadCameraError, "2": EventName.wideRoadCameraError, "0": EventName.driverCameraError} - -def get_startup_event(car_recognized, controller_available, fw_seen): - build_metadata = get_build_metadata() - if build_metadata.openpilot.comma_remote and build_metadata.tested_channel: - event = EventName.startup - else: - event = EventName.startupMaster - - if not car_recognized: - if fw_seen: - event = EventName.startupNoCar - else: - event = EventName.startupNoFw - elif car_recognized and not controller_available: - event = EventName.startupNoControl - return event class SelfdriveD: @@ -61,7 +43,7 @@ class SelfdriveD: self.params = Params() # Ensure the current branch is cached, otherwise the first cycle lags - self.branch = get_short_branch() + build_metadata = get_build_metadata() cloudlog.info("selfdrived is waiting for CarParams") self.CP = messaging.log_from_bytes(self.params.get("CarParams", block=True), car.CarParams) @@ -75,8 +57,6 @@ class SelfdriveD: self.sensor_packets = ["accelerometer", "gyroscope"] self.camera_packets = ["roadCameraState", "driverCameraState", "wideRoadCameraState"] - self.log_sock = messaging.sub_sock('androidLog') - # TODO: de-couple selfdrived with card/conflate on carState without introducing controls mismatches self.car_state_sock = messaging.sub_sock('carState', timeout=20) @@ -128,27 +108,23 @@ class SelfdriveD: self.personality = self.read_personality_param() self.recalibrating_seen = False self.state_machine = StateMachine() + self.rk = Ratekeeper(100, print_delay_threshold=None) - self.startup_event = get_startup_event(car_recognized, not self.CP.passive, len(self.CP.carFw) > 0) + # Determine startup event + self.startup_event = EventName.startup if build_metadata.openpilot.comma_remote and build_metadata.tested_channel else EventName.startupMaster + if not car_recognized: + self.startup_event = EventName.startupNoCar + elif car_recognized and self.CP.passive: + self.startup_event = EventName.startupNoControl if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) if not car_recognized: self.events.add(EventName.carUnrecognized, static=True) - if len(self.CP.carFw) > 0: - set_offroad_alert("Offroad_CarUnrecognized", True) - else: - set_offroad_alert("Offroad_NoFirmware", True) + set_offroad_alert("Offroad_CarUnrecognized", True) elif self.CP.passive: self.events.add(EventName.dashcamMode, static=True) - # selfdrived is driven by carState, expected at 100Hz - self.rk = Ratekeeper(100, print_delay_threshold=None) - - def set_initial_state(self): - if REPLAY and any(ps.controlsAllowed for ps in self.sm['pandaStates']): - self.state_machine.state = State.enabled - def update_events(self, CS): """Compute onroadEvents from carState""" @@ -355,18 +331,6 @@ class SelfdriveD: if (planner_fcw or model_fcw) and not self.CP.notCar: self.events.add(EventName.fcw) - # Camera errors from the kernel - for m in messaging.drain_sock(self.log_sock, wait_for_one=False): - try: - msg = m.androidLog.message - if any(err in msg for err in ("ERROR_CRC", "ERROR_ECC", "ERROR_STREAM_UNDERFLOW", "APPLY FAILED")): - csid = msg.split("CSID:")[-1].split(" ")[0] - evt = CSID_MAP.get(csid, None) - if evt is not None: - self.events.add(evt) - except UnicodeDecodeError: - pass - # TODO: fix simulator if not SIMULATION or REPLAY: # Not show in first 1.5 km to allow for driving out of garage. This event shows after 5 minutes @@ -403,9 +367,10 @@ class SelfdriveD: if VisionStreamType.VISION_STREAM_WIDE_ROAD not in available_streams: self.sm.ignore_alive.append('wideRoadCameraState') - self.initialized = True - self.set_initial_state() + if REPLAY and any(ps.controlsAllowed for ps in self.sm['pandaStates']): + self.state_machine.state = State.enabled + self.initialized = True cloudlog.event( "selfdrived.initialized", dt=self.sm.frame*DT_CTRL, @@ -449,19 +414,20 @@ class SelfdriveD: ss_msg = messaging.new_message('selfdriveState') ss_msg.valid = True ss = ss_msg.selfdriveState - if self.AM.current_alert: - ss.alertText1 = self.AM.current_alert.alert_text_1 - ss.alertText2 = self.AM.current_alert.alert_text_2 - ss.alertSize = self.AM.current_alert.alert_size - ss.alertStatus = self.AM.current_alert.alert_status - ss.alertType = self.AM.current_alert.alert_type - ss.alertSound = self.AM.current_alert.audible_alert ss.enabled = self.enabled ss.active = self.active ss.state = self.state_machine.state ss.engageable = not self.events.contains(ET.NO_ENTRY) ss.experimentalMode = self.experimental_mode ss.personality = self.personality + + ss.alertText1 = self.AM.current_alert.alert_text_1 + ss.alertText2 = self.AM.current_alert.alert_text_2 + ss.alertSize = self.AM.current_alert.alert_size + ss.alertStatus = self.AM.current_alert.alert_status + ss.alertType = self.AM.current_alert.alert_type + ss.alertSound = self.AM.current_alert.audible_alert + self.pm.send('selfdriveState', ss_msg) # onroadEvents - logged every second or on change diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index ebfcd1ec0b..d73a5771fd 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -388,10 +388,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. لم يكن openpilot قادراً على تحديد سيارتك. إما أن تكون سيارتك غير مدعومة أو أنه لم يتم التعرف على وحدة التحكم الإلكتروني (ECUs) فيها. يرجى تقديم طلب سحب من أجل إضافة نسخ برمجيات ثابتة إلى السيارة المناسبة. هل تحتاج إلى أي مساعدة؟ لا تتردد في التواصل مع doscord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - لم يتمكن openpilot من تحديد سيارتك. تحقق من سلامة الكابلات وتأكد من تأمين جميع الوصلات، لا سيما أنه قد تم إدخال طاقة الفاصلة بالكامل في منفذ OBD-II في السيارة. هل تريد أي مساعدة؟ لا تتردد في الانضمام إلى discord.comma.ai. - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. لقد اكتشف openpilot تغييراً في موقع تركيب الجهاز. تأكد من تثبيت الجهاز بشكل كامل في موقعه وتثبيته بإحكام على الزجاج الأمامي. diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index 4e8bbe0a18..8ad55be666 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -379,10 +379,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. diff --git a/selfdrive/ui/translations/main_es.ts b/selfdrive/ui/translations/main_es.ts index 083d2c25e1..39a13fb026 100644 --- a/selfdrive/ui/translations/main_es.ts +++ b/selfdrive/ui/translations/main_es.ts @@ -384,10 +384,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot no pudo identificar su automóvil. Su automóvil no es compatible o no se reconocen sus ECU. Por favor haga un pull request para agregar las versiones de firmware del vehículo adecuado. ¿Necesita ayuda? Únase a discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot no pudo identificar su automóvil. Verifique la integridad de los cables y asegúrese de que todas las conexiones estén seguras, en particular que el comma power esté completamente insertado en el puerto OBD-II del vehículo. ¿Necesita ayuda? Únase discord.comma.ai. - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot detectó un cambio en la posición de montaje del dispositivo. Asegúrese de que el dispositivo esté completamente asentado en el soporte y que el soporte esté firmemente asegurado al parabrisas. diff --git a/selfdrive/ui/translations/main_fr.ts b/selfdrive/ui/translations/main_fr.ts index 16adcaa081..80cca809e0 100644 --- a/selfdrive/ui/translations/main_fr.ts +++ b/selfdrive/ui/translations/main_fr.ts @@ -384,10 +384,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot n'a pas pu identifier votre voiture. Votre voiture n'est pas supportée ou ses ECUs ne sont pas reconnues. Veuillez soumettre un pull request pour ajouter les versions de firmware au véhicule approprié. Besoin d'aide ? Rejoignez discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot n'a pas pu identifier votre voiture. Vérifiez l'intégrité des câbles et assurez-vous que toutes les connexions sont correctes, en particulier l'alimentation du comma est totalement insérée dans le port OBD-II du véhicule. Besoin d'aide ? Rejoignez discord.comma.ai. - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot a détecté un changement dans la position de montage de l'appareil. Assurez-vous que l'appareil est totalement inséré dans le support et que le support est fermement fixé au pare-brise. diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index daac99ce09..2b8f7d2429 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -378,10 +378,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 9541067119..ee04810904 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -379,10 +379,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot이 차량을 식별할 수 없었습니다. 지원되지 않는 차량이거나 ECU가 인식되지 않습니다. 해당 차량에 맞는 펌웨어 버전을 추가하려면 PR을 제출하세요. 도움이 필요하시면 discord.comma.ai에 가입하세요. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot이 차량을 식별할 수 없었습니다. 케이블의 무결성을 점검하고 모든 연결부, 특히 comma power가 차량의 OBD-II 포트에 제대로 삽입되었는지 확인하세요. 도움이 필요하시면 discord.comma.ai에 가입하세요. - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot 장치의 장착 위치가 변경되었습니다. 장치가 마운트에 완전히 장착되고 마운트가 앞유리에 단단히 고정되었는지 확인하세요. diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index e92e7748b3..648dc3e384 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -380,10 +380,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. O openpilot não conseguiu identificar o seu carro. Seu carro não é suportado ou seus ECUs não são reconhecidos. Envie um pull request para adicionar as versões de firmware ao veículo adequado. Precisa de ajuda? Junte-se discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - O openpilot não conseguiu identificar o seu carro. Verifique a integridade dos cabos e certifique-se de que todas as conexões estejam seguras, especialmente se o comma power está totalmente inserido na porta OBD-II do veículo. Precisa de ajuda? Junte-se discord.comma.ai. - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. O openpilot detectou uma mudança na posição de montagem do dispositivo. Verifique se o dispositivo está totalmente encaixado no suporte e se o suporte está firmemente preso ao para-brisa. diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index d0dea811c6..06841222cc 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -383,10 +383,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot ไม่สามารถระบุรถยนต์ของคุณได้ ระบบอาจไม่รองรับรถยนต์ของคุณหรือไม่รู้จัก ECU กรุณาส่ง pull request เพื่อเพิ่มรุ่นของเฟิร์มแวร์ให้กับรถยนต์ที่เหมาะสม หากต้องการความช่วยเหลือให้เข้าร่วม discord.comma.ai - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot ไม่สามารถระบุรถยนต์ของคุณได้ กรุณาตรวจสอบสายเคเบิ้ลและจุดเชื่อมต่อทั้งหมดว่าแน่นหนา โดยเฉพาะ comma power ว่าได้ดันเข้าไปยังพอร์ต OBD II ของรถยนต์จนสุด หากต้องการความช่วยเหลือให้เข้าร่วม discord.comma.ai - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot ตรวจพบการเปลี่ยนแปลงของตำแหน่งที่ติดตั้ง กรุณาตรวจสอบว่าได้เลื่อนอุปกรณ์เข้ากับจุดติดตั้งจนสุดแล้ว และจุดติดตั้งได้ยึดติดกับกระจกหน้าอย่างแน่นหนา diff --git a/selfdrive/ui/translations/main_tr.ts b/selfdrive/ui/translations/main_tr.ts index 746425cb4e..f934b9d9cc 100644 --- a/selfdrive/ui/translations/main_tr.ts +++ b/selfdrive/ui/translations/main_tr.ts @@ -382,10 +382,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index ec1884521b..5fe66104d1 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -379,10 +379,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot 无法识别您的车辆。您的车辆可能未被支持,或是其电控单元 (ECU) 未被识别。请提交一个 Pull Request 为您的车辆添加正确的固件版本。需要帮助吗?请加入 discord.comma.ai。 - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot 无法识别您的车辆。请检查线路是否正确安装并确保所有的连接都牢固,特别是确保 comma power 完全插入车辆的 OBD-II 接口。需要帮助吗?请加入 discord.comma.ai。 - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot 检测到设备的安装位置发生变化。请确保设备完全安装在支架上,并确保支架牢固地固定在挡风玻璃上。 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 835a0af30f..b7d2eb2bde 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -379,10 +379,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot 無法識別您的車輛。您的車輛可能未被支援,或是其電控單元 (ECU) 未被識別。請提交一個 Pull Request 為您的車輛添加正確的韌體版本。需要幫助嗎?請加入 discord.comma.ai 。 - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot 無法識別您的車輛。請檢查線路是否正確的安裝並確保所有的連接都牢固,特別是確保 comma power 完全插入車輛的 OBD-II 介面。需要幫助嗎?請加入 discord.comma.ai 。 - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot 偵測到裝置的安裝位置發生變化。請確保裝置完全安裝在支架上,並確保支架牢固地固定在擋風玻璃上。 From de0ac299606407dc1a363a99a62c0c9b9115681c Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Fri, 6 Sep 2024 20:55:43 -0700 Subject: [PATCH 014/214] ci: ui preview with diff (#33498) * diff * not for now --- .github/workflows/selfdrive_tests.yaml | 3 +- .github/workflows/ui_preview.yaml | 161 ++++++++++++++++--------- 2 files changed, 106 insertions(+), 58 deletions(-) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index b2831118f6..09ac537845 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -337,7 +337,6 @@ jobs: # This job name needs to be the same as UI_JOB_NAME in ui_preview.yaml name: Create UI Report runs-on: ubuntu-latest - if: github.event_name == 'pull_request' steps: - uses: actions/checkout@v4 with: @@ -353,5 +352,5 @@ jobs: - name: Upload Test Report uses: actions/upload-artifact@v4 with: - name: report-${{ github.event.number }} + name: report-${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && 'master' || github.event.number }} path: selfdrive/ui/tests/test_ui/report_1/screenshots diff --git a/.github/workflows/ui_preview.yaml b/.github/workflows/ui_preview.yaml index d4dcce5f3f..9a7bb68f0d 100644 --- a/.github/workflows/ui_preview.yaml +++ b/.github/workflows/ui_preview.yaml @@ -1,5 +1,8 @@ name: "ui preview" on: + push: + branches: + - master pull_request_target: types: [assigned, opened, synchronize, reopened, edited] branches: @@ -10,6 +13,9 @@ on: env: UI_JOB_NAME: "Create UI Report" + REPORT_NAME: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && 'master' || github.event.number }} + SHA: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && github.sha || github.event.pull_request.head.sha }} + BRANCH_NAME: "openpilot/pr-${{ github.event.number }}" jobs: preview: @@ -22,91 +28,134 @@ jobs: pull-requests: write actions: read steps: - - name: Waiting for ui test to start + - name: Waiting for ui generation to start run: sleep 30 - - name: Wait for ui report + - name: Waiting for ui generation to end uses: lewagon/wait-on-check-action@v1.3.4 with: - ref: ${{ github.event.pull_request.head.sha }} + ref: ${{ env.SHA }} check-name: ${{ env.UI_JOB_NAME }} repo-token: ${{ secrets.GITHUB_TOKEN }} allowed-conclusions: success wait-interval: 20 - - name: Get workflow run ID + - name: Getting workflow run ID id: get_run_id run: | - echo "run_id=$(curl https://api.github.com/repos/${{ github.repository }}/commits/${{ github.event.pull_request.head.sha }}/check-runs | jq -r '.check_runs[] | select(.name == "${{ env.UI_JOB_NAME }}") | .html_url | capture("(?[0-9]+)") | .number')" >> $GITHUB_OUTPUT + echo "run_id=$(curl https://api.github.com/repos/${{ github.repository }}/commits/${{ env.SHA }}/check-runs | jq -r '.check_runs[] | select(.name == "${{ env.UI_JOB_NAME }}") | .html_url | capture("(?[0-9]+)") | .number')" >> $GITHUB_OUTPUT - - name: Checkout ci-artifacts - uses: actions/checkout@v4 - with: - repository: commaai/ci-artifacts - ssh-key: ${{ secrets.CI_ARTIFACTS_DEPLOY_KEY }} - path: ${{ github.workspace }}/ci-artifacts - ref: master - - - name: Download artifact + - name: Getting proposed ui id: download-artifact uses: dawidd6/action-download-artifact@v6 with: github_token: ${{ secrets.GITHUB_TOKEN }} run_id: ${{ steps.get_run_id.outputs.run_id }} search_artifacts: true - name: report-${{ github.event.number }} - path: ${{ github.workspace }}/ci-artifacts + name: report-${{ env.REPORT_NAME }} + path: ${{ github.workspace }}/pr_ui + + - name: Getting master ui + uses: actions/checkout@v4 + with: + repository: commaai/ci-artifacts + ssh-key: ${{ secrets.CI_ARTIFACTS_DEPLOY_KEY }} + path: ${{ github.workspace }}/master_ui + ref: openpilot_master_ui + + - name: Saving new master ui + if: github.ref == 'refs/heads/master' && github.event_name == 'push' + working-directory: ${{ github.workspace }}/master_ui + run: | + git checkout --orphan=new_master_ui + git rm -rf * + git branch -D openpilot_master_ui + git branch -m openpilot_master_ui + git config user.name "GitHub Actions Bot" + git config user.email "<>" + mv ${{ github.workspace }}/pr_ui/*.png . + git add . + git commit -m "screenshots for commit ${{ env.SHA }}" + git push origin openpilot_master_ui --force + + - name: Finding diff + if: github.event_name == 'pull_request_target' + id: find_diff + run: >- + sudo apt-get install -y imagemagick + + scenes="homescreen settings_device offroad_alert update_available prime onroad onroad_sidebar onroad_wide onroad_wide_sidebar onroad_alert_small onroad_alert_mid onroad_alert_full driver_camera body" + A=($scenes) + + DIFF="" + TABLE="
" + TABLE="${TABLE}All Screenshots" + TABLE="${TABLE}" + + for ((i=0; i<${#A[*]}; i=i+1)); + do + + if ! compare -fuzz 2% -highlight-color DeepSkyBlue1 -lowlight-color Black -compose Src ${{ github.workspace }}/master_ui/${A[$i]}.png ${{ github.workspace }}/pr_ui/${A[$i]}.png ${{ github.workspace }}/pr_ui/${A[$i]}_diff.png; then + convert ${{ github.workspace }}/pr_ui/${A[$i]}_diff.png -transparent black mask.png + composite mask.png ${{ github.workspace }}/master_ui/${A[$i]}.png composite_diff.png + convert -delay 20 ${{ github.workspace }}/master_ui/${A[$i]}.png composite_diff.png -loop 0 ${{ github.workspace }}/pr_ui/${A[$i]}_diff.gif + + DIFF="${DIFF}
" + DIFF="${DIFF}${A[$i]} : \$\${\\color{red}\\text{DIFFERENT}}\$\$" + DIFF="${DIFF}
" + + DIFF="${DIFF}" + DIFF="${DIFF} " + DIFF="${DIFF} " + DIFF="${DIFF}" + + DIFF="${DIFF}" + DIFF="${DIFF} " + DIFF="${DIFF} " + DIFF="${DIFF}" + + DIFF="${DIFF}
master proposed
diff composite diff
" + DIFF="${DIFF}
" + else + rm -f ${{ github.workspace }}/pr_ui/${A[$i]}_diff.png + fi + + INDEX=$(($i % 2)) + if [[ $INDEX -eq 0 ]]; then + TABLE="${TABLE}" + fi + TABLE="${TABLE} " + if [[ $INDEX -eq 1 || $(($i + 1)) -eq ${#A[*]} ]]; then + TABLE="${TABLE}" + fi + done + + TABLE="${TABLE}" + TABLE="${TABLE}" + + echo "DIFF=$DIFF$TABLE" >> "$GITHUB_OUTPUT" - - name: Push Screenshots - working-directory: ${{ github.workspace }}/ci-artifacts + - name: Saving proposed ui + if: github.event_name == 'pull_request_target' + working-directory: ${{ github.workspace }}/master_ui run: | - git checkout -b openpilot/pr-${{ github.event.number }} git config user.name "GitHub Actions Bot" git config user.email "<>" - git add ${{ github.workspace }}/ci-artifacts/* + git checkout --orphan=${{ env.BRANCH_NAME }} + git rm -rf * + mv ${{ github.workspace }}/pr_ui/* . + git add . git commit -m "screenshots for PR #${{ github.event.number }}" - git push origin openpilot/pr-${{ github.event.number }} --force + git push origin ${{ env.BRANCH_NAME }} --force - name: Comment Screenshots on PR + if: github.event_name == 'pull_request_target' uses: thollander/actions-comment-pull-request@v2 with: message: | - ## UI Screenshots - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
+ ## UI Preview + ${{ steps.find_diff.outputs.DIFF }} comment_tag: run_id_screenshots pr_number: ${{ github.event.number }} GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} From 68257da3d5b4625b201643cc459b048aae711dae Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Sat, 7 Sep 2024 13:02:29 +0900 Subject: [PATCH 015/214] Multilang: kor translation update (#33499) --- selfdrive/ui/translations/main_ko.ts | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index ee04810904..935342d546 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -419,11 +419,11 @@
Waiting to start - + 시작을 기다리는중 System Unresponsive - + 시스템이 응답하지않습니다
@@ -484,7 +484,7 @@ Remote snapshots - + 원격 스냅샷 @@ -1036,15 +1036,15 @@ This may take up to a minute. The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner. - + 운전 시각화는 일부 회전을 더 잘 보여주기 위해 저속에서 도로를 향한 광각 카메라로 전환됩니다. 실험 모드 로고도 우측 상단에 표시됩니다. Always-On Driver Monitoring - + 상시 운전자 모니터링 Enable driver monitoring even when openpilot is not engaged. - + Openpilot이 활성화되지 않은 경우에도 드라이버 모니터링을 활성화합니다. From eecac1069e27060ff187d5b90eca2ed4354ce6d5 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 6 Sep 2024 21:06:34 -0700 Subject: [PATCH 016/214] joystickd: mapping for PC (#33500) work on PC --- tools/joystick/joystickd.py | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index 982af9767f..09cc16d337 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -8,6 +8,7 @@ import cereal.messaging as messaging from openpilot.common.realtime import Ratekeeper from openpilot.common.numpy_fast import interp, clip from openpilot.common.params import Params +from openpilot.system.hardware import HARDWARE from openpilot.tools.lib.kbhit import KBHit JS_EXPO = 0.4 @@ -43,12 +44,17 @@ class Joystick: def __init__(self): # This class supports a PlayStation 5 DualSense controller on the comma 3X # TODO: find a way to get this from API or detect gamepad/PC, perhaps "inputs" doesn't support it - # TODO: the mapping can also be wrong on PC depending on the driver self.cancel_button = 'BTN_NORTH' # BTN_NORTH=X/triangle - accel_axis = 'ABS_RX' - steer_axis = 'ABS_Z' - # TODO: once the longcontrol API is finalized, we can replace this with outputting gas/brake and steering - self.flip_map = {'ABS_RY': accel_axis} + if HARDWARE.get_device_type() == 'pc': + accel_axis = 'ABS_Z' + steer_axis = 'ABS_RX' + # TODO: once the longcontrol API is finalized, we can replace this with outputting gas/brake and steering + self.flip_map = {'ABS_RZ': accel_axis} + else: + accel_axis = 'ABS_RX' + steer_axis = 'ABS_Z' + self.flip_map = {'ABS_RY': accel_axis} + self.min_axis_value = {accel_axis: 0., steer_axis: 0.} self.max_axis_value = {accel_axis: 255., steer_axis: 255.} self.axes_values = {accel_axis: 0., steer_axis: 0.} From 415391c3fc855b885355cfec7db864a6542b16c2 Mon Sep 17 00:00:00 2001 From: Joshua Mack Date: Sat, 7 Sep 2024 00:28:44 -0400 Subject: [PATCH 017/214] Multilang: Spanish translation update (#33502) Update main_es.ts --- selfdrive/ui/translations/main_es.ts | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/translations/main_es.ts b/selfdrive/ui/translations/main_es.ts index 39a13fb026..510a2d98e0 100644 --- a/selfdrive/ui/translations/main_es.ts +++ b/selfdrive/ui/translations/main_es.ts @@ -420,11 +420,11 @@ Waiting to start - + Esperando para iniciar System Unresponsive - + Systema no responde From 374246845c0c3c3c7c9ef8764f4a21e30a920bee Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 6 Sep 2024 21:58:45 -0700 Subject: [PATCH 018/214] joystickd is a real process (#33490) * true joystickd * temp params hack, manager clears all on start * implement main, assume js * works * fix enable * clean up * like a real controlsd * clean up * fix mypy * clean up * update refs * clean up --- selfdrive/selfdrived/events.py | 9 ++-- selfdrive/test/process_replay/ref_commit | 2 +- system/manager/process_config.py | 9 +++- tools/joystick/joystickd.py | 63 ++++++++++++++++++++---- 4 files changed, 66 insertions(+), 17 deletions(-) diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index 9128f1acd8..d9c922bb90 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -320,11 +320,10 @@ def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: - # TODO: add some info back - #axes = sm['testJoystick'].axes - #gb, steer = list(axes)[:2] if len(axes) else (0., 0.) - #vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" - return NormalPermanentAlert("Joystick Mode", "") + gb = sm['carControl'].actuators.accel / 4. + steer = sm['carControl'].actuators.steer + vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" + return NormalPermanentAlert("Joystick Mode", vals) def personality_changed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: personality = str(personality).title() diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b866e015ac..d0e5317124 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -eac137f456f25bf138677315b7c4907e2fe9971b \ No newline at end of file +78eb5f832bb1a53b33d952edc586b986a8e31089 \ No newline at end of file diff --git a/system/manager/process_config.py b/system/manager/process_config.py index 8af376c624..a85bfd1f46 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -29,6 +29,12 @@ def ublox(started, params, CP: car.CarParams) -> bool: params.put_bool("UbloxAvailable", use_ublox) return started and use_ublox +def joystick(started: bool, params, CP: car.CarParams) -> bool: + return started and params.get_bool("JoystickDebugMode") + +def not_joystick(started: bool, params, CP: car.CarParams) -> bool: + return started and not params.get_bool("JoystickDebugMode") + def qcomgps(started, params, CP: car.CarParams) -> bool: return started and not ublox_available() @@ -63,7 +69,8 @@ procs = [ NativeProcess("pandad", "selfdrive/pandad", ["./pandad"], always_run, enabled=False), PythonProcess("calibrationd", "selfdrive.locationd.calibrationd", only_onroad), PythonProcess("torqued", "selfdrive.locationd.torqued", only_onroad), - PythonProcess("controlsd", "selfdrive.controls.controlsd", only_onroad), + PythonProcess("controlsd", "selfdrive.controls.controlsd", not_joystick), + PythonProcess("joystickd", "tools.joystick.joystickd", joystick), PythonProcess("selfdrived", "selfdrive.selfdrived.selfdrived", only_onroad), PythonProcess("card", "selfdrive.car.card", only_onroad), PythonProcess("deleter", "system.loggerd.deleter", always_run), diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index 09cc16d337..52460031a5 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -3,15 +3,19 @@ import os import argparse import threading from inputs import get_gamepad +import math -import cereal.messaging as messaging -from openpilot.common.realtime import Ratekeeper +from cereal import messaging, car +from openpilot.common.realtime import DT_CTRL, Ratekeeper from openpilot.common.numpy_fast import interp, clip from openpilot.common.params import Params +from openpilot.common.swaglog import cloudlog +from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel from openpilot.system.hardware import HARDWARE from openpilot.tools.lib.kbhit import KBHit -JS_EXPO = 0.4 +EXPO = 0.4 +MAX_LAT_ACCEL = 2.5 class Keyboard: @@ -80,21 +84,56 @@ class Joystick: norm = -interp(event[1], [self.min_axis_value[event[0]], self.max_axis_value[event[0]]], [-1., 1.]) norm = norm if abs(norm) > 0.03 else 0. # center can be noisy, deadzone of 3% - self.axes_values[event[0]] = JS_EXPO * norm ** 3 + (1 - JS_EXPO) * norm # less action near center for fine control + self.axes_values[event[0]] = EXPO * norm ** 3 + (1 - EXPO) * norm # less action near center for fine control else: return False return True def send_thread(joystick): - joystick_sock = messaging.pub_sock('testJoystick') + params = Params() + cloudlog.info("joystickd is waiting for CarParams") + CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) + VM = VehicleModel(CP) + + sm = messaging.SubMaster(['carState', 'onroadEvents', 'liveParameters', 'selfdriveState'], frequency=1. / DT_CTRL) + pm = messaging.PubMaster(['carControl', 'controlsState']) + rk = Ratekeeper(100, print_delay_threshold=None) while 1: - dat = messaging.new_message('testJoystick') - dat.testJoystick.axes = [joystick.axes_values[a] for a in joystick.axes_order] - dat.testJoystick.buttons = [joystick.cancel] - joystick_sock.send(dat.to_bytes()) - print('\n' + ', '.join(f'{name}: {round(v, 3)}' for name, v in joystick.axes_values.items())) + sm.update(0) + + joystick_axes = [joystick.axes_values[a] for a in joystick.axes_order] + if rk.frame % 20 == 0: + print('\n' + ', '.join(f'{name}: {round(v, 3)}' for name, v in joystick.axes_values.items())) + + cc_msg = messaging.new_message('carControl') + cc_msg.valid = True + CC = cc_msg.carControl + CC.enabled = sm['selfdriveState'].enabled + CC.latActive = sm['selfdriveState'].active and not sm['carState'].steerFaultTemporary and not sm['carState'].steerFaultPermanent + CC.longActive = CC.enabled and not any(e.overrideLongitudinal for e in sm['onroadEvents']) and CP.openpilotLongitudinalControl + + actuators = CC.actuators + + if CC.longActive: + actuators.accel = 4.0 * clip(joystick_axes[0], -1, 1) + + if CC.latActive: + max_curvature = MAX_LAT_ACCEL / max(sm['carState'].vEgo ** 2, 5) + max_angle = math.degrees(VM.get_steer_from_curvature(max_curvature, sm['carState'].vEgo, sm['liveParameters'].roll)) + + actuators.steer = clip(joystick_axes[1], -1, 1) + actuators.steeringAngleDeg, actuators.curvature = actuators.steer * max_angle, actuators.steer * -max_curvature + + pm.send('carControl', cc_msg) + + cs_msg = messaging.new_message('controlsState') + cs_msg.valid = True + controlsState = cs_msg.controlsState + controlsState.lateralControlState.init('debugState') + pm.send('controlsState', cs_msg) + rk.keep_time() @@ -105,6 +144,10 @@ def joystick_thread(joystick): joystick.update() +def main(): + joystick_thread(Joystick()) + + if __name__ == '__main__': parser = argparse.ArgumentParser(description='Publishes events from your joystick to control your car.\n' + 'openpilot must be offroad before starting joystickd. This tool supports ' + From 9e09f42ccb9189994549bb95b917e10945154497 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 7 Sep 2024 12:59:06 +0800 Subject: [PATCH 019/214] ui: fix texture deletion (#33480) fix texture deletion --- selfdrive/ui/qt/widgets/cameraview.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 914b04b654..b43f8c4322 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -115,7 +115,7 @@ CameraWidget::~CameraWidget() { glDeleteVertexArrays(1, &frame_vao); glDeleteBuffers(1, &frame_vbo); glDeleteBuffers(1, &frame_ibo); - glDeleteBuffers(2, textures); + glDeleteTextures(2, textures); } doneCurrent(); } From 1a9504cc7362390e8510a84244da5effee8f2e2f Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Fri, 6 Sep 2024 22:32:25 -0700 Subject: [PATCH 020/214] ci: ui_preview: save master ref (#33503) ref --- .github/workflows/ui_preview.yaml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ui_preview.yaml b/.github/workflows/ui_preview.yaml index 9a7bb68f0d..98eadc36c2 100644 --- a/.github/workflows/ui_preview.yaml +++ b/.github/workflows/ui_preview.yaml @@ -100,12 +100,14 @@ jobs: composite mask.png ${{ github.workspace }}/master_ui/${A[$i]}.png composite_diff.png convert -delay 20 ${{ github.workspace }}/master_ui/${A[$i]}.png composite_diff.png -loop 0 ${{ github.workspace }}/pr_ui/${A[$i]}_diff.gif + mv ${{ github.workspace }}/master_ui/${A[$i]}.png ${{ github.workspace }}/pr_ui/${A[$i]}_master_ref.png + DIFF="${DIFF}
" DIFF="${DIFF}${A[$i]} : \$\${\\color{red}\\text{DIFFERENT}}\$\$" DIFF="${DIFF}" DIFF="${DIFF}" - DIFF="${DIFF} " + DIFF="${DIFF} " DIFF="${DIFF} " DIFF="${DIFF}" From 870214c90913f97d9d474636a8967e742b3b1f64 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 8 Sep 2024 00:27:44 +0800 Subject: [PATCH 021/214] ci: add a 0.5-second delay before taking screenshots of the onroad widgets (#33504) Add a 0.5-second delay before taking screenshots of the onroad widgets --- selfdrive/ui/tests/test_ui/run.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 5050adfd98..578d9d7e10 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -46,7 +46,7 @@ def setup_onroad(click, pm: PubMaster): vipc_server.create_buffers(stream_type, 5, False, cam.width, cam.height) vipc_server.start_listener() - for packet_id in range(20): + for packet_id in range(30): for service, data in DATA.items(): if data: data.clear_write_flag() From c8465e3a21a06a8f55c44c71cb2a38a43180a4c9 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 7 Sep 2024 09:28:16 -0700 Subject: [PATCH 022/214] Revert "joystickd is a real process (#33490)" This reverts commit 374246845c0c3c3c7c9ef8764f4a21e30a920bee. --- selfdrive/selfdrived/events.py | 9 ++-- selfdrive/test/process_replay/ref_commit | 2 +- system/manager/process_config.py | 9 +--- tools/joystick/joystickd.py | 63 ++++-------------------- 4 files changed, 17 insertions(+), 66 deletions(-) diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index d9c922bb90..9128f1acd8 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -320,10 +320,11 @@ def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: - gb = sm['carControl'].actuators.accel / 4. - steer = sm['carControl'].actuators.steer - vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" - return NormalPermanentAlert("Joystick Mode", vals) + # TODO: add some info back + #axes = sm['testJoystick'].axes + #gb, steer = list(axes)[:2] if len(axes) else (0., 0.) + #vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" + return NormalPermanentAlert("Joystick Mode", "") def personality_changed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: personality = str(personality).title() diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index d0e5317124..b866e015ac 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -78eb5f832bb1a53b33d952edc586b986a8e31089 \ No newline at end of file +eac137f456f25bf138677315b7c4907e2fe9971b \ No newline at end of file diff --git a/system/manager/process_config.py b/system/manager/process_config.py index a85bfd1f46..8af376c624 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -29,12 +29,6 @@ def ublox(started, params, CP: car.CarParams) -> bool: params.put_bool("UbloxAvailable", use_ublox) return started and use_ublox -def joystick(started: bool, params, CP: car.CarParams) -> bool: - return started and params.get_bool("JoystickDebugMode") - -def not_joystick(started: bool, params, CP: car.CarParams) -> bool: - return started and not params.get_bool("JoystickDebugMode") - def qcomgps(started, params, CP: car.CarParams) -> bool: return started and not ublox_available() @@ -69,8 +63,7 @@ procs = [ NativeProcess("pandad", "selfdrive/pandad", ["./pandad"], always_run, enabled=False), PythonProcess("calibrationd", "selfdrive.locationd.calibrationd", only_onroad), PythonProcess("torqued", "selfdrive.locationd.torqued", only_onroad), - PythonProcess("controlsd", "selfdrive.controls.controlsd", not_joystick), - PythonProcess("joystickd", "tools.joystick.joystickd", joystick), + PythonProcess("controlsd", "selfdrive.controls.controlsd", only_onroad), PythonProcess("selfdrived", "selfdrive.selfdrived.selfdrived", only_onroad), PythonProcess("card", "selfdrive.car.card", only_onroad), PythonProcess("deleter", "system.loggerd.deleter", always_run), diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index 52460031a5..09cc16d337 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -3,19 +3,15 @@ import os import argparse import threading from inputs import get_gamepad -import math -from cereal import messaging, car -from openpilot.common.realtime import DT_CTRL, Ratekeeper +import cereal.messaging as messaging +from openpilot.common.realtime import Ratekeeper from openpilot.common.numpy_fast import interp, clip from openpilot.common.params import Params -from openpilot.common.swaglog import cloudlog -from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel from openpilot.system.hardware import HARDWARE from openpilot.tools.lib.kbhit import KBHit -EXPO = 0.4 -MAX_LAT_ACCEL = 2.5 +JS_EXPO = 0.4 class Keyboard: @@ -84,56 +80,21 @@ class Joystick: norm = -interp(event[1], [self.min_axis_value[event[0]], self.max_axis_value[event[0]]], [-1., 1.]) norm = norm if abs(norm) > 0.03 else 0. # center can be noisy, deadzone of 3% - self.axes_values[event[0]] = EXPO * norm ** 3 + (1 - EXPO) * norm # less action near center for fine control + self.axes_values[event[0]] = JS_EXPO * norm ** 3 + (1 - JS_EXPO) * norm # less action near center for fine control else: return False return True def send_thread(joystick): - params = Params() - cloudlog.info("joystickd is waiting for CarParams") - CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) - VM = VehicleModel(CP) - - sm = messaging.SubMaster(['carState', 'onroadEvents', 'liveParameters', 'selfdriveState'], frequency=1. / DT_CTRL) - pm = messaging.PubMaster(['carControl', 'controlsState']) - + joystick_sock = messaging.pub_sock('testJoystick') rk = Ratekeeper(100, print_delay_threshold=None) while 1: - sm.update(0) - - joystick_axes = [joystick.axes_values[a] for a in joystick.axes_order] - if rk.frame % 20 == 0: - print('\n' + ', '.join(f'{name}: {round(v, 3)}' for name, v in joystick.axes_values.items())) - - cc_msg = messaging.new_message('carControl') - cc_msg.valid = True - CC = cc_msg.carControl - CC.enabled = sm['selfdriveState'].enabled - CC.latActive = sm['selfdriveState'].active and not sm['carState'].steerFaultTemporary and not sm['carState'].steerFaultPermanent - CC.longActive = CC.enabled and not any(e.overrideLongitudinal for e in sm['onroadEvents']) and CP.openpilotLongitudinalControl - - actuators = CC.actuators - - if CC.longActive: - actuators.accel = 4.0 * clip(joystick_axes[0], -1, 1) - - if CC.latActive: - max_curvature = MAX_LAT_ACCEL / max(sm['carState'].vEgo ** 2, 5) - max_angle = math.degrees(VM.get_steer_from_curvature(max_curvature, sm['carState'].vEgo, sm['liveParameters'].roll)) - - actuators.steer = clip(joystick_axes[1], -1, 1) - actuators.steeringAngleDeg, actuators.curvature = actuators.steer * max_angle, actuators.steer * -max_curvature - - pm.send('carControl', cc_msg) - - cs_msg = messaging.new_message('controlsState') - cs_msg.valid = True - controlsState = cs_msg.controlsState - controlsState.lateralControlState.init('debugState') - pm.send('controlsState', cs_msg) - + dat = messaging.new_message('testJoystick') + dat.testJoystick.axes = [joystick.axes_values[a] for a in joystick.axes_order] + dat.testJoystick.buttons = [joystick.cancel] + joystick_sock.send(dat.to_bytes()) + print('\n' + ', '.join(f'{name}: {round(v, 3)}' for name, v in joystick.axes_values.items())) rk.keep_time() @@ -144,10 +105,6 @@ def joystick_thread(joystick): joystick.update() -def main(): - joystick_thread(Joystick()) - - if __name__ == '__main__': parser = argparse.ArgumentParser(description='Publishes events from your joystick to control your car.\n' + 'openpilot must be offroad before starting joystickd. This tool supports ' + From b720fe1bfefddc241f65cdb2ba9d4e059ff12ff1 Mon Sep 17 00:00:00 2001 From: ugtthis <142481257+ugtthis@users.noreply.github.com> Date: Sat, 7 Sep 2024 13:51:49 -0700 Subject: [PATCH 023/214] create_badges.py: Changed to higher contrast colors (#33509) Changed color badge - clearer difference --- selfdrive/ui/translations/create_badges.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/translations/create_badges.py b/selfdrive/ui/translations/create_badges.py index f56f894111..3e14c33255 100755 --- a/selfdrive/ui/translations/create_badges.py +++ b/selfdrive/ui/translations/create_badges.py @@ -31,7 +31,7 @@ if __name__ == "__main__": unfinished_translations += 1 percent_finished = int(100 - (unfinished_translations / total_translations * 100.)) - color = "green" if percent_finished == 100 else "orange" if percent_finished > 90 else "red" + color = f"rgb{(94, 188, 0) if percent_finished == 100 else (248, 255, 50) if percent_finished > 90 else (204, 55, 27)}" # Download badge badge_label = f"LANGUAGE {name}" From 0317f292d0bce28c8b466c7d4ad0b56e592e3e91 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 8 Sep 2024 04:57:54 +0800 Subject: [PATCH 024/214] selfdrived: define and reuse longitudinal personality mapping (#33507) define and reuse longitudinal personality mapping --- selfdrive/selfdrived/selfdrived.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 545688c60b..6a4f33c566 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -25,6 +25,7 @@ REPLAY = "REPLAY" in os.environ SIMULATION = "SIMULATION" in os.environ TESTING_CLOSET = "TESTING_CLOSET" in os.environ IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd"} +LONGITUDINAL_PERSONALITY_MAP = {v: k for k, v in log.LongitudinalPersonality.schema.enumerants.items()} ThermalStatus = log.DeviceState.ThermalStatus State = log.SelfdriveState.OpenpilotState @@ -403,7 +404,7 @@ class SelfdriveD: if self.enabled: clear_event_types.add(ET.NO_ENTRY) - pers = {v: k for k, v in log.LongitudinalPersonality.schema.enumerants.items()}[self.personality] + pers = LONGITUDINAL_PERSONALITY_MAP[self.personality] alerts = self.events.create_alerts(self.state_machine.current_alert_types, [self.CP, CS, self.sm, self.is_metric, self.state_machine.soft_disable_timer, pers]) self.AM.add_many(self.sm.frame, alerts) From b4bcaf6f02f76a30862a8d7859eaf9158b8ce4e0 Mon Sep 17 00:00:00 2001 From: Alexandre Nobuharu Sato <66435071+AlexandreSato@users.noreply.github.com> Date: Sat, 7 Sep 2024 18:26:46 -0300 Subject: [PATCH 025/214] Multilang: update pt-BR translation (#33510) Update main_pt-BR.ts --- selfdrive/ui/translations/main_pt-BR.ts | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 648dc3e384..1c1ebff15b 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -420,11 +420,11 @@ Waiting to start - + Aguardando para iniciar System Unresponsive - + Sistema sem Resposta From 584eb373cdf3e841d6c92b82470b28b3bedcf34b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 7 Sep 2024 15:57:30 -0700 Subject: [PATCH 026/214] CI: remove 20.04 job --- .github/workflows/tools_tests.yaml | 31 ------------------------------ 1 file changed, 31 deletions(-) diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml index 271e4bda17..1bdde2a59a 100644 --- a/.github/workflows/tools_tests.yaml +++ b/.github/workflows/tools_tests.yaml @@ -43,37 +43,6 @@ jobs: source selfdrive/test/setup_vsound.sh && \ CI=1 pytest tools/sim/tests/test_metadrive_bridge.py" - test_compatibility: - name: test 20.04 + 3.11 - runs-on: ubuntu-20.04 - steps: - - uses: actions/checkout@v4 - with: - submodules: true - - name: Installing ubuntu dependencies - run: INSTALL_EXTRA_PACKAGES=no tools/install_ubuntu_dependencies.sh - - name: Installing python - uses: actions/setup-python@v5 - with: - python-version: '3.11.4' - - name: Installing pip - run: pip install pip==24.0 - - name: Installing uv - run: pip install uv - - name: git LFS - run: git lfs pull - - run: echo "CACHE_COMMIT_DATE=$(git log -1 --pretty='format:%cd' --date=format:'%Y-%m-%d-%H:%M')" >> $GITHUB_ENV - - name: Getting scons cache - uses: 'actions/cache@v4' - with: - path: /tmp/scons_cache - key: scons-${{ runner.arch }}-ubuntu2004-${{ env.CACHE_COMMIT_DATE }}-${{ github.sha }} - restore-keys: | - scons-${{ runner.arch }}-ubuntu2004-${{ env.CACHE_COMMIT_DATE }} - scons-${{ runner.arch }}-ubuntu2004 - - name: Building openpilot - run: uv run scons -u -j$(nproc) - devcontainer: name: devcontainer runs-on: ubuntu-latest From e3f05db3e07d8cc725d4833d68693f7524cb13e7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 7 Sep 2024 16:31:49 -0700 Subject: [PATCH 027/214] SubMaster: init services as invalid (#33513) * SubMaster: init services as invalid * fix sim * update refs * cpp too * update refs * model ref --- cereal/messaging/__init__.py | 2 +- cereal/messaging/socketmaster.cc | 2 +- selfdrive/selfdrived/selfdrived.py | 4 +++- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 5 files changed, 7 insertions(+), 5 deletions(-) diff --git a/cereal/messaging/__init__.py b/cereal/messaging/__init__.py index 32b7a6553f..0c420e94e0 100644 --- a/cereal/messaging/__init__.py +++ b/cereal/messaging/__init__.py @@ -174,7 +174,7 @@ class SubMaster: self.data[s] = getattr(data.as_reader(), s) self.logMonoTime[s] = 0 - self.valid[s] = True # FIXME: this should default to False + self.valid[s] = False self.freq_tracker[s] = FrequencyTracker(SERVICE_LIST[s].frequency, self.update_freq, s == poll) def __getitem__(self, s: str) -> capnp.lib.capnp._DynamicStructReader: diff --git a/cereal/messaging/socketmaster.cc b/cereal/messaging/socketmaster.cc index 38b9842414..1a7a48980e 100644 --- a/cereal/messaging/socketmaster.cc +++ b/cereal/messaging/socketmaster.cc @@ -34,7 +34,7 @@ struct SubMaster::SubMessage { std::string name; SubSocket *socket = nullptr; int freq = 0; - bool updated = false, alive = false, valid = true, ignore_alive; + bool updated = false, alive = false, valid = false, ignore_alive; uint64_t rcv_time = 0, rcv_frame = 0; void *allocated_msg_reader = nullptr; bool is_polled = false; diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 6a4f33c566..255ce080df 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -73,7 +73,7 @@ class SelfdriveD: 'controlsState', 'carControl', 'driverAssistance'] + \ self.camera_packets + self.sensor_packets + self.gps_packets, ignore_alive=ignore, ignore_avg_freq=ignore+['radarState',], - frequency=int(1/DT_CTRL)) + ignore_valid=ignore, frequency=int(1/DT_CTRL)) # read params self.is_metric = self.params.get_bool("IsMetric") @@ -365,8 +365,10 @@ class SelfdriveD: available_streams = VisionIpcClient.available_streams("camerad", block=False) if VisionStreamType.VISION_STREAM_ROAD not in available_streams: self.sm.ignore_alive.append('roadCameraState') + self.sm.ignore_valid.append('roadCameraState') if VisionStreamType.VISION_STREAM_WIDE_ROAD not in available_streams: self.sm.ignore_alive.append('wideRoadCameraState') + self.sm.ignore_valid.append('wideRoadCameraState') if REPLAY and any(ps.controlsAllowed for ps in self.sm['pandaStates']): self.state_machine.state = State.enabled diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 237713622b..66971ebde1 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -8726813f978d6baf519055f3105350cd071741f3 \ No newline at end of file +32fe8cf4a0daa8d10a689c9ae2e51a879151c87c diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b866e015ac..be74e5cfc9 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -eac137f456f25bf138677315b7c4907e2fe9971b \ No newline at end of file +fa642b559758928289d8092f30bb9787eb9ebcf2 From ee6d7aeb537c37e70af83c0e4cb2a454d37f3e52 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 8 Sep 2024 07:38:44 +0800 Subject: [PATCH 028/214] pandad: add log_once_ to prevent repeated logging (#33505) add log_once_ flag --- selfdrive/pandad/panda_safety.cc | 8 ++++++-- selfdrive/pandad/pandad.h | 1 + 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/selfdrive/pandad/panda_safety.cc b/selfdrive/pandad/panda_safety.cc index 1d0f72f223..0a14894677 100644 --- a/selfdrive/pandad/panda_safety.cc +++ b/selfdrive/pandad/panda_safety.cc @@ -17,6 +17,7 @@ void PandaSafety::configureSafetyMode() { } else if (!is_onroad) { initialized_ = false; safety_configured_ = false; + log_once_ = false; } } @@ -46,9 +47,12 @@ std::string PandaSafety::fetchCarParams() { if (!params_.getBool("FirmwareQueryDone")) { return {}; } - LOGW("Finished FW query"); - LOGW("Waiting for params to set safety model"); + if (!log_once_) { + LOGW("Finished FW query, Waiting for params to set safety model"); + log_once_ = true; + } + if (!params_.getBool("ControlsReady")) { return {}; } diff --git a/selfdrive/pandad/pandad.h b/selfdrive/pandad/pandad.h index 14d97551f4..dedd8ae79a 100644 --- a/selfdrive/pandad/pandad.h +++ b/selfdrive/pandad/pandad.h @@ -19,6 +19,7 @@ private: void setSafetyMode(const std::string ¶ms_string); bool initialized_ = false; + bool log_once_ = false; bool safety_configured_ = false; bool prev_obd_multiplexing_ = false; std::vector pandas_; From 606943010efc84266ab649f3e7b1dae039f88d07 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 7 Sep 2024 17:03:22 -0700 Subject: [PATCH 029/214] Reapply "joystickd is a real process (#33490)" (#33514) * Reapply "joystickd is a real process (#33490)" This reverts commit c8465e3a21a06a8f55c44c71cb2a38a43180a4c9. * catch this * reset to 0 when unplugged * catch this too * pytest capturing breaks stdin (pytest -s) fixes --- selfdrive/selfdrived/events.py | 9 ++- selfdrive/test/process_replay/ref_commit | 2 +- system/manager/process_config.py | 9 ++- tools/joystick/joystickd.py | 72 ++++++++++++++++++++---- tools/lib/kbhit.py | 8 +-- 5 files changed, 77 insertions(+), 23 deletions(-) diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index 9128f1acd8..d9c922bb90 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -320,11 +320,10 @@ def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: - # TODO: add some info back - #axes = sm['testJoystick'].axes - #gb, steer = list(axes)[:2] if len(axes) else (0., 0.) - #vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" - return NormalPermanentAlert("Joystick Mode", "") + gb = sm['carControl'].actuators.accel / 4. + steer = sm['carControl'].actuators.steer + vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" + return NormalPermanentAlert("Joystick Mode", vals) def personality_changed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: personality = str(personality).title() diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index be74e5cfc9..cfdddb0965 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -fa642b559758928289d8092f30bb9787eb9ebcf2 +849fcc369f7afa78606cba636fe7c73e540e6df8 \ No newline at end of file diff --git a/system/manager/process_config.py b/system/manager/process_config.py index 8af376c624..a85bfd1f46 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -29,6 +29,12 @@ def ublox(started, params, CP: car.CarParams) -> bool: params.put_bool("UbloxAvailable", use_ublox) return started and use_ublox +def joystick(started: bool, params, CP: car.CarParams) -> bool: + return started and params.get_bool("JoystickDebugMode") + +def not_joystick(started: bool, params, CP: car.CarParams) -> bool: + return started and not params.get_bool("JoystickDebugMode") + def qcomgps(started, params, CP: car.CarParams) -> bool: return started and not ublox_available() @@ -63,7 +69,8 @@ procs = [ NativeProcess("pandad", "selfdrive/pandad", ["./pandad"], always_run, enabled=False), PythonProcess("calibrationd", "selfdrive.locationd.calibrationd", only_onroad), PythonProcess("torqued", "selfdrive.locationd.torqued", only_onroad), - PythonProcess("controlsd", "selfdrive.controls.controlsd", only_onroad), + PythonProcess("controlsd", "selfdrive.controls.controlsd", not_joystick), + PythonProcess("joystickd", "tools.joystick.joystickd", joystick), PythonProcess("selfdrived", "selfdrive.selfdrived.selfdrived", only_onroad), PythonProcess("card", "selfdrive.car.card", only_onroad), PythonProcess("deleter", "system.loggerd.deleter", always_run), diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index 09cc16d337..f39dec7d4b 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -2,16 +2,20 @@ import os import argparse import threading -from inputs import get_gamepad +from inputs import UnpluggedError, get_gamepad +import math -import cereal.messaging as messaging -from openpilot.common.realtime import Ratekeeper +from cereal import messaging, car +from openpilot.common.realtime import DT_CTRL, Ratekeeper from openpilot.common.numpy_fast import interp, clip from openpilot.common.params import Params +from openpilot.common.swaglog import cloudlog +from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel from openpilot.system.hardware import HARDWARE from openpilot.tools.lib.kbhit import KBHit -JS_EXPO = 0.4 +EXPO = 0.4 +MAX_LAT_ACCEL = 2.5 class Keyboard: @@ -62,7 +66,12 @@ class Joystick: self.cancel = False def update(self): - joystick_event = get_gamepad()[0] + try: + joystick_event = get_gamepad()[0] + except (OSError, UnpluggedError): + self.axes_values = {ax: 0. for ax in self.axes_values} + return False + event = (joystick_event.code, joystick_event.state) # flip left trigger to negative accel @@ -80,21 +89,56 @@ class Joystick: norm = -interp(event[1], [self.min_axis_value[event[0]], self.max_axis_value[event[0]]], [-1., 1.]) norm = norm if abs(norm) > 0.03 else 0. # center can be noisy, deadzone of 3% - self.axes_values[event[0]] = JS_EXPO * norm ** 3 + (1 - JS_EXPO) * norm # less action near center for fine control + self.axes_values[event[0]] = EXPO * norm ** 3 + (1 - EXPO) * norm # less action near center for fine control else: return False return True def send_thread(joystick): - joystick_sock = messaging.pub_sock('testJoystick') + params = Params() + cloudlog.info("joystickd is waiting for CarParams") + CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) + VM = VehicleModel(CP) + + sm = messaging.SubMaster(['carState', 'onroadEvents', 'liveParameters', 'selfdriveState'], frequency=1. / DT_CTRL) + pm = messaging.PubMaster(['carControl', 'controlsState']) + rk = Ratekeeper(100, print_delay_threshold=None) while 1: - dat = messaging.new_message('testJoystick') - dat.testJoystick.axes = [joystick.axes_values[a] for a in joystick.axes_order] - dat.testJoystick.buttons = [joystick.cancel] - joystick_sock.send(dat.to_bytes()) - print('\n' + ', '.join(f'{name}: {round(v, 3)}' for name, v in joystick.axes_values.items())) + sm.update(0) + + joystick_axes = [joystick.axes_values[a] for a in joystick.axes_order] + if rk.frame % 20 == 0: + print('\n' + ', '.join(f'{name}: {round(v, 3)}' for name, v in joystick.axes_values.items())) + + cc_msg = messaging.new_message('carControl') + cc_msg.valid = True + CC = cc_msg.carControl + CC.enabled = sm['selfdriveState'].enabled + CC.latActive = sm['selfdriveState'].active and not sm['carState'].steerFaultTemporary and not sm['carState'].steerFaultPermanent + CC.longActive = CC.enabled and not any(e.overrideLongitudinal for e in sm['onroadEvents']) and CP.openpilotLongitudinalControl + + actuators = CC.actuators + + if CC.longActive: + actuators.accel = 4.0 * clip(joystick_axes[0], -1, 1) + + if CC.latActive: + max_curvature = MAX_LAT_ACCEL / max(sm['carState'].vEgo ** 2, 5) + max_angle = math.degrees(VM.get_steer_from_curvature(max_curvature, sm['carState'].vEgo, sm['liveParameters'].roll)) + + actuators.steer = clip(joystick_axes[1], -1, 1) + actuators.steeringAngleDeg, actuators.curvature = actuators.steer * max_angle, actuators.steer * -max_curvature + + pm.send('carControl', cc_msg) + + cs_msg = messaging.new_message('controlsState') + cs_msg.valid = True + controlsState = cs_msg.controlsState + controlsState.lateralControlState.init('debugState') + pm.send('controlsState', cs_msg) + rk.keep_time() @@ -105,6 +149,10 @@ def joystick_thread(joystick): joystick.update() +def main(): + joystick_thread(Joystick()) + + if __name__ == '__main__': parser = argparse.ArgumentParser(description='Publishes events from your joystick to control your car.\n' + 'openpilot must be offroad before starting joystickd. This tool supports ' + diff --git a/tools/lib/kbhit.py b/tools/lib/kbhit.py index 3881ee7d18..c6365cdfec 100755 --- a/tools/lib/kbhit.py +++ b/tools/lib/kbhit.py @@ -4,13 +4,13 @@ import termios import atexit from select import select -STDIN_FD = sys.stdin.fileno() class KBHit: def __init__(self) -> None: ''' Creates a KBHit object that you can call to do various keyboard things. ''' + self.stdin_fd = sys.stdin.fileno() self.set_kbhit_terminal() def set_kbhit_terminal(self) -> None: @@ -18,12 +18,12 @@ class KBHit: ''' # Save the terminal settings - self.old_term = termios.tcgetattr(STDIN_FD) + self.old_term = termios.tcgetattr(self.stdin_fd) self.new_term = self.old_term.copy() # New terminal setting unbuffered self.new_term[3] &= ~(termios.ICANON | termios.ECHO) - termios.tcsetattr(STDIN_FD, termios.TCSAFLUSH, self.new_term) + termios.tcsetattr(self.stdin_fd, termios.TCSAFLUSH, self.new_term) # Support normal-terminal reset at exit atexit.register(self.set_normal_term) @@ -32,7 +32,7 @@ class KBHit: ''' Resets to normal terminal. On Windows this is a no-op. ''' - termios.tcsetattr(STDIN_FD, termios.TCSAFLUSH, self.old_term) + termios.tcsetattr(self.stdin_fd, termios.TCSAFLUSH, self.old_term) @staticmethod def getch() -> str: From b286a2f0e5206077b3ad80273b0bb5404f53deeb Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 8 Sep 2024 08:06:57 +0800 Subject: [PATCH 030/214] transformations: standardize parameter passing by reference (#33469) pass parameters by reference --- common/transformations/coordinates.cc | 18 ++++++------ common/transformations/coordinates.hpp | 24 +++++++-------- common/transformations/orientation.cc | 22 +++++++------- common/transformations/orientation.hpp | 16 +++++----- common/transformations/transformations.pxd | 34 +++++++++++----------- 5 files changed, 57 insertions(+), 57 deletions(-) diff --git a/common/transformations/coordinates.cc b/common/transformations/coordinates.cc index 5b00b53a4f..f3f10e547f 100644 --- a/common/transformations/coordinates.cc +++ b/common/transformations/coordinates.cc @@ -25,8 +25,8 @@ static Geodetic to_radians(Geodetic geodetic){ } -ECEF geodetic2ecef(Geodetic g){ - g = to_radians(g); +ECEF geodetic2ecef(const Geodetic &geodetic) { + auto g = to_radians(geodetic); double xi = sqrt(1.0 - esq * pow(sin(g.lat), 2)); double x = (a / xi + g.alt) * cos(g.lat) * cos(g.lon); double y = (a / xi + g.alt) * cos(g.lat) * sin(g.lon); @@ -34,7 +34,7 @@ ECEF geodetic2ecef(Geodetic g){ return {x, y, z}; } -Geodetic ecef2geodetic(ECEF e){ +Geodetic ecef2geodetic(const ECEF &e) { // Convert from ECEF to geodetic using Ferrari's methods // https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#Ferrari.27s_solution double x = e.x; @@ -61,10 +61,10 @@ Geodetic ecef2geodetic(ECEF e){ return to_degrees({lat, lon, h}); } -LocalCoord::LocalCoord(Geodetic g, ECEF e){ +LocalCoord::LocalCoord(const Geodetic &geodetic, const ECEF &e) { init_ecef << e.x, e.y, e.z; - g = to_radians(g); + auto g = to_radians(geodetic); ned2ecef_matrix << -sin(g.lat)*cos(g.lon), -sin(g.lon), -cos(g.lat)*cos(g.lon), @@ -73,7 +73,7 @@ LocalCoord::LocalCoord(Geodetic g, ECEF e){ ecef2ned_matrix = ned2ecef_matrix.transpose(); } -NED LocalCoord::ecef2ned(ECEF e) { +NED LocalCoord::ecef2ned(const ECEF &e) { Eigen::Vector3d ecef; ecef << e.x, e.y, e.z; @@ -81,7 +81,7 @@ NED LocalCoord::ecef2ned(ECEF e) { return {ned[0], ned[1], ned[2]}; } -ECEF LocalCoord::ned2ecef(NED n) { +ECEF LocalCoord::ned2ecef(const NED &n) { Eigen::Vector3d ned; ned << n.n, n.e, n.d; @@ -89,12 +89,12 @@ ECEF LocalCoord::ned2ecef(NED n) { return {ecef[0], ecef[1], ecef[2]}; } -NED LocalCoord::geodetic2ned(Geodetic g) { +NED LocalCoord::geodetic2ned(const Geodetic &g) { ECEF e = ::geodetic2ecef(g); return ecef2ned(e); } -Geodetic LocalCoord::ned2geodetic(NED n){ +Geodetic LocalCoord::ned2geodetic(const NED &n) { ECEF e = ned2ecef(n); return ::ecef2geodetic(e); } diff --git a/common/transformations/coordinates.hpp b/common/transformations/coordinates.hpp index 32ec2ff66e..dc8ff7a4b6 100644 --- a/common/transformations/coordinates.hpp +++ b/common/transformations/coordinates.hpp @@ -7,14 +7,14 @@ struct ECEF { double x, y, z; - Eigen::Vector3d to_vector(){ + Eigen::Vector3d to_vector() const { return Eigen::Vector3d(x, y, z); } }; struct NED { double n, e, d; - Eigen::Vector3d to_vector(){ + Eigen::Vector3d to_vector() const { return Eigen::Vector3d(n, e, d); } }; @@ -24,20 +24,20 @@ struct Geodetic { bool radians=false; }; -ECEF geodetic2ecef(Geodetic g); -Geodetic ecef2geodetic(ECEF e); +ECEF geodetic2ecef(const Geodetic &g); +Geodetic ecef2geodetic(const ECEF &e); class LocalCoord { public: Eigen::Matrix3d ned2ecef_matrix; Eigen::Matrix3d ecef2ned_matrix; Eigen::Vector3d init_ecef; - LocalCoord(Geodetic g, ECEF e); - LocalCoord(Geodetic g) : LocalCoord(g, ::geodetic2ecef(g)) {} - LocalCoord(ECEF e) : LocalCoord(::ecef2geodetic(e), e) {} - - NED ecef2ned(ECEF e); - ECEF ned2ecef(NED n); - NED geodetic2ned(Geodetic g); - Geodetic ned2geodetic(NED n); + LocalCoord(const Geodetic &g, const ECEF &e); + LocalCoord(const Geodetic &g) : LocalCoord(g, ::geodetic2ecef(g)) {} + LocalCoord(const ECEF &e) : LocalCoord(::ecef2geodetic(e), e) {} + + NED ecef2ned(const ECEF &e); + ECEF ned2ecef(const NED &n); + NED geodetic2ned(const Geodetic &g); + Geodetic ned2geodetic(const NED &n); }; diff --git a/common/transformations/orientation.cc b/common/transformations/orientation.cc index 00888c3a92..fb5e47a86a 100644 --- a/common/transformations/orientation.cc +++ b/common/transformations/orientation.cc @@ -7,7 +7,7 @@ #include "common/transformations/orientation.hpp" #include "common/transformations/coordinates.hpp" -Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat){ +Eigen::Quaterniond ensure_unique(const Eigen::Quaterniond &quat) { if (quat.w() > 0){ return quat; } else { @@ -15,7 +15,7 @@ Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat){ } } -Eigen::Quaterniond euler2quat(Eigen::Vector3d euler){ +Eigen::Quaterniond euler2quat(const Eigen::Vector3d &euler) { Eigen::Quaterniond q; q = Eigen::AngleAxisd(euler(2), Eigen::Vector3d::UnitZ()) @@ -25,7 +25,7 @@ Eigen::Quaterniond euler2quat(Eigen::Vector3d euler){ } -Eigen::Vector3d quat2euler(Eigen::Quaterniond quat){ +Eigen::Vector3d quat2euler(const Eigen::Quaterniond &quat) { // TODO: switch to eigen implementation if the range of the Euler angles doesn't matter anymore // Eigen::Vector3d euler = quat.toRotationMatrix().eulerAngles(2, 1, 0); // return {euler(2), euler(1), euler(0)}; @@ -36,34 +36,34 @@ Eigen::Vector3d quat2euler(Eigen::Quaterniond quat){ return {gamma, theta, psi}; } -Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat){ +Eigen::Matrix3d quat2rot(const Eigen::Quaterniond &quat) { return quat.toRotationMatrix(); } -Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot){ +Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot) { return ensure_unique(Eigen::Quaterniond(rot)); } -Eigen::Matrix3d euler2rot(Eigen::Vector3d euler){ +Eigen::Matrix3d euler2rot(const Eigen::Vector3d &euler) { return quat2rot(euler2quat(euler)); } -Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot){ +Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot) { return quat2euler(rot2quat(rot)); } -Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw){ +Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw) { return euler2rot({roll, pitch, yaw}); } -Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle){ +Eigen::Matrix3d rot(const Eigen::Vector3d &axis, double angle) { Eigen::Quaterniond q; q = Eigen::AngleAxisd(angle, axis); return q.toRotationMatrix(); } -Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose) { +Eigen::Vector3d ecef_euler_from_ned(const ECEF &ecef_init, const Eigen::Vector3d &ned_pose) { /* Using Rotations to Build Aerospace Coordinate Systems Don Koks @@ -103,7 +103,7 @@ Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose) { return {phi, theta, psi}; } -Eigen::Vector3d ned_euler_from_ecef(ECEF ecef_init, Eigen::Vector3d ecef_pose){ +Eigen::Vector3d ned_euler_from_ecef(const ECEF &ecef_init, const Eigen::Vector3d &ecef_pose) { /* Using Rotations to Build Aerospace Coordinate Systems Don Koks diff --git a/common/transformations/orientation.hpp b/common/transformations/orientation.hpp index 150b12cade..0874a0a814 100644 --- a/common/transformations/orientation.hpp +++ b/common/transformations/orientation.hpp @@ -3,15 +3,15 @@ #include "common/transformations/coordinates.hpp" -Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat); +Eigen::Quaterniond ensure_unique(const Eigen::Quaterniond &quat); -Eigen::Quaterniond euler2quat(Eigen::Vector3d euler); -Eigen::Vector3d quat2euler(Eigen::Quaterniond quat); -Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat); +Eigen::Quaterniond euler2quat(const Eigen::Vector3d &euler); +Eigen::Vector3d quat2euler(const Eigen::Quaterniond &quat); +Eigen::Matrix3d quat2rot(const Eigen::Quaterniond &quat); Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot); -Eigen::Matrix3d euler2rot(Eigen::Vector3d euler); +Eigen::Matrix3d euler2rot(const Eigen::Vector3d &euler); Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot); Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw); -Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle); -Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose); -Eigen::Vector3d ned_euler_from_ecef(ECEF ecef_init, Eigen::Vector3d ecef_pose); +Eigen::Matrix3d rot(const Eigen::Vector3d &axis, double angle); +Eigen::Vector3d ecef_euler_from_ned(const ECEF &ecef_init, const Eigen::Vector3d &ned_pose); +Eigen::Vector3d ned_euler_from_ecef(const ECEF &ecef_init, const Eigen::Vector3d &ecef_pose); diff --git a/common/transformations/transformations.pxd b/common/transformations/transformations.pxd index 964adf06ec..fe32e18dea 100644 --- a/common/transformations/transformations.pxd +++ b/common/transformations/transformations.pxd @@ -24,15 +24,15 @@ cdef extern from "orientation.hpp": double operator()(int, int) - Quaternion euler2quat(Vector3) - Vector3 quat2euler(Quaternion) - Matrix3 quat2rot(Quaternion) - Quaternion rot2quat(Matrix3) - Vector3 rot2euler(Matrix3) - Matrix3 euler2rot(Vector3) + Quaternion euler2quat(const Vector3 &) + Vector3 quat2euler(const Quaternion &) + Matrix3 quat2rot(const Quaternion &) + Quaternion rot2quat(const Matrix3 &) + Vector3 rot2euler(const Matrix3 &) + Matrix3 euler2rot(const Vector3 &) Matrix3 rot_matrix(double, double, double) - Vector3 ecef_euler_from_ned(ECEF, Vector3) - Vector3 ned_euler_from_ecef(ECEF, Vector3) + Vector3 ecef_euler_from_ned(const ECEF &, const Vector3 &) + Vector3 ned_euler_from_ecef(const ECEF &, const Vector3 &) cdef extern from "coordinates.cc": @@ -52,21 +52,21 @@ cdef extern from "coordinates.cc": double alt bool radians - ECEF geodetic2ecef(Geodetic) - Geodetic ecef2geodetic(ECEF) + ECEF geodetic2ecef(const Geodetic &) + Geodetic ecef2geodetic(const ECEF &) cdef cppclass LocalCoord_c "LocalCoord": Matrix3 ned2ecef_matrix Matrix3 ecef2ned_matrix - LocalCoord_c(Geodetic, ECEF) - LocalCoord_c(Geodetic) - LocalCoord_c(ECEF) + LocalCoord_c(const Geodetic &, const ECEF &) + LocalCoord_c(const Geodetic &) + LocalCoord_c(const ECEF &) - NED ecef2ned(ECEF) - ECEF ned2ecef(NED) - NED geodetic2ned(Geodetic) - Geodetic ned2geodetic(NED) + NED ecef2ned(const ECEF &) + ECEF ned2ecef(const NED &) + NED geodetic2ned(const Geodetic &) + Geodetic ned2geodetic(const NED &) cdef extern from "coordinates.hpp": pass From 762492b9bef44d21452b518629f2d3f4b74831f5 Mon Sep 17 00:00:00 2001 From: commaci-public <60409688+commaci-public@users.noreply.github.com> Date: Mon, 9 Sep 2024 09:58:26 -0700 Subject: [PATCH 031/214] [bot] Update Python packages (#33518) Update Python packages Co-authored-by: Vehicle Researcher --- opendbc_repo | 2 +- panda | 2 +- uv.lock | 369 ++++++++++++++++++++++++++------------------------- 3 files changed, 190 insertions(+), 183 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index c0a9ab5c39..ef7102a8ae 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit c0a9ab5c39197d48cc920a818a85610e526f9e73 +Subproject commit ef7102a8ae2334d77ff4b0be512c073e81b01d18 diff --git a/panda b/panda index aac60b8a79..fcccbb3a13 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit aac60b8a7938d4d32c0c02608058022e4d876156 +Subproject commit fcccbb3a131cc8f60025fc7da9b9fdb7a4e3acf7 diff --git a/uv.lock b/uv.lock index 141cf78797..fb10566645 100644 --- a/uv.lock +++ b/uv.lock @@ -241,47 +241,47 @@ wheels = [ [[package]] name = "cffi" -version = "1.17.0" +version = "1.17.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "pycparser" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/1e/bf/82c351342972702867359cfeba5693927efe0a8dd568165490144f554b18/cffi-1.17.0.tar.gz", hash = "sha256:f3157624b7558b914cb039fd1af735e5e8049a87c817cc215109ad1c8779df76", size = 516073 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/53/cc/9298fb6235522e00e47d78d6aa7f395332ef4e5f6fe124f9a03aa60600f7/cffi-1.17.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c5d97162c196ce54af6700949ddf9409e9833ef1003b4741c2b39ef46f1d9720", size = 181912 }, - { url = "https://files.pythonhosted.org/packages/e7/79/dc5334fbe60635d0846c56597a8d2af078a543ff22bc48d36551a0de62c2/cffi-1.17.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:5ba5c243f4004c750836f81606a9fcb7841f8874ad8f3bf204ff5e56332b72b9", size = 178297 }, - { url = "https://files.pythonhosted.org/packages/39/d7/ef1b6b16b51ccbabaced90ff0d821c6c23567fc4b2e4a445aea25d3ceb92/cffi-1.17.0-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bb9333f58fc3a2296fb1d54576138d4cf5d496a2cc118422bd77835e6ae0b9cb", size = 444909 }, - { url = "https://files.pythonhosted.org/packages/29/b8/6e3c61885537d985c78ef7dd779b68109ba256263d74a2f615c40f44548d/cffi-1.17.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:435a22d00ec7d7ea533db494da8581b05977f9c37338c80bc86314bec2619424", size = 468854 }, - { url = "https://files.pythonhosted.org/packages/0b/49/adad1228e19b931e523c2731e6984717d5f9e33a2f9971794ab42815b29b/cffi-1.17.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d1df34588123fcc88c872f5acb6f74ae59e9d182a2707097f9e28275ec26a12d", size = 476890 }, - { url = "https://files.pythonhosted.org/packages/76/54/c00f075c3e7fd14d9011713bcdb5b4f105ad044c5ad948db7b1a0a7e4e78/cffi-1.17.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:df8bb0010fdd0a743b7542589223a2816bdde4d94bb5ad67884348fa2c1c67e8", size = 459374 }, - { url = "https://files.pythonhosted.org/packages/f3/b9/f163bb3fa4fbc636ee1f2a6a4598c096cdef279823ddfaa5734e556dd206/cffi-1.17.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a8b5b9712783415695663bd463990e2f00c6750562e6ad1d28e072a611c5f2a6", size = 466891 }, - { url = "https://files.pythonhosted.org/packages/31/52/72bbc95f6d06ff2e88a6fa13786be4043e542cb24748e1351aba864cb0a7/cffi-1.17.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ffef8fd58a36fb5f1196919638f73dd3ae0db1a878982b27a9a5a176ede4ba91", size = 477658 }, - { url = "https://files.pythonhosted.org/packages/67/20/d694811457eeae0c7663fa1a7ca201ce495533b646c1180d4ac25684c69c/cffi-1.17.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:4e67d26532bfd8b7f7c05d5a766d6f437b362c1bf203a3a5ce3593a645e870b8", size = 453890 }, - { url = "https://files.pythonhosted.org/packages/dc/79/40cbf5739eb4f694833db5a27ce7f63e30a9b25b4a836c4f25fb7272aacc/cffi-1.17.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:45f7cd36186db767d803b1473b3c659d57a23b5fa491ad83c6d40f2af58e4dbb", size = 478254 }, - { url = "https://files.pythonhosted.org/packages/e9/eb/2c384c385cca5cae67ca10ac4ef685277680b8c552b99aedecf4ea23ff7e/cffi-1.17.0-cp311-cp311-win32.whl", hash = "sha256:a9015f5b8af1bb6837a3fcb0cdf3b874fe3385ff6274e8b7925d81ccaec3c5c9", size = 171285 }, - { url = "https://files.pythonhosted.org/packages/ca/42/74cb1e0f1b79cb64672f3cb46245b506239c1297a20c0d9c3aeb3929cb0c/cffi-1.17.0-cp311-cp311-win_amd64.whl", hash = "sha256:b50aaac7d05c2c26dfd50c3321199f019ba76bb650e346a6ef3616306eed67b0", size = 180842 }, - { url = "https://files.pythonhosted.org/packages/1a/1f/7862231350cc959a3138889d2c8d33da7042b22e923457dfd4cd487d772a/cffi-1.17.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:aec510255ce690d240f7cb23d7114f6b351c733a74c279a84def763660a2c3bc", size = 182826 }, - { url = "https://files.pythonhosted.org/packages/8b/8c/26119bf8b79e05a1c39812064e1ee7981e1f8a5372205ba5698ea4dd958d/cffi-1.17.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2770bb0d5e3cc0e31e7318db06efcbcdb7b31bcb1a70086d3177692a02256f59", size = 178494 }, - { url = "https://files.pythonhosted.org/packages/61/94/4882c47d3ad396d91f0eda6ef16d45be3d752a332663b7361933039ed66a/cffi-1.17.0-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:db9a30ec064129d605d0f1aedc93e00894b9334ec74ba9c6bdd08147434b33eb", size = 454459 }, - { url = "https://files.pythonhosted.org/packages/0f/7c/a6beb119ad515058c5ee1829742d96b25b2b9204ff920746f6e13bf574eb/cffi-1.17.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a47eef975d2b8b721775a0fa286f50eab535b9d56c70a6e62842134cf7841195", size = 478502 }, - { url = "https://files.pythonhosted.org/packages/61/8a/2575cd01a90e1eca96a30aec4b1ac101a6fae06c49d490ac2704fa9bc8ba/cffi-1.17.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f3e0992f23bbb0be00a921eae5363329253c3b86287db27092461c887b791e5e", size = 485381 }, - { url = "https://files.pythonhosted.org/packages/cd/66/85899f5a9f152db49646e0c77427173e1b77a1046de0191ab3b0b9a5e6e3/cffi-1.17.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:6107e445faf057c118d5050560695e46d272e5301feffda3c41849641222a828", size = 470907 }, - { url = "https://files.pythonhosted.org/packages/00/13/150924609bf377140abe6e934ce0a57f3fc48f1fd956ec1f578ce97a4624/cffi-1.17.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eb862356ee9391dc5a0b3cbc00f416b48c1b9a52d252d898e5b7696a5f9fe150", size = 479074 }, - { url = "https://files.pythonhosted.org/packages/17/fd/7d73d7110155c036303b0a6462c56250e9bc2f4119d7591d27417329b4d1/cffi-1.17.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:c1c13185b90bbd3f8b5963cd8ce7ad4ff441924c31e23c975cb150e27c2bf67a", size = 484225 }, - { url = "https://files.pythonhosted.org/packages/fc/83/8353e5c9b01bb46332dac3dfb18e6c597a04ceb085c19c814c2f78a8c0d0/cffi-1.17.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:17c6d6d3260c7f2d94f657e6872591fe8733872a86ed1345bda872cfc8c74885", size = 488388 }, - { url = "https://files.pythonhosted.org/packages/73/0c/f9d5ca9a095b1fc88ef77d1f8b85d11151c374144e4606da33874e17b65b/cffi-1.17.0-cp312-cp312-win32.whl", hash = "sha256:c3b8bd3133cd50f6b637bb4322822c94c5ce4bf0d724ed5ae70afce62187c492", size = 172096 }, - { url = "https://files.pythonhosted.org/packages/72/21/8c5d285fe20a6e31d29325f1287bb0e55f7d93630a5a44cafdafb5922495/cffi-1.17.0-cp312-cp312-win_amd64.whl", hash = "sha256:dca802c8db0720ce1c49cce1149ff7b06e91ba15fa84b1d59144fef1a1bc7ac2", size = 181478 }, - { url = "https://files.pythonhosted.org/packages/17/8f/581f2f3c3464d5f7cf87c2f7a5ba9acc6976253e02d73804240964243ec2/cffi-1.17.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:6ce01337d23884b21c03869d2f68c5523d43174d4fc405490eb0091057943118", size = 182638 }, - { url = "https://files.pythonhosted.org/packages/8d/1c/c9afa66684b7039f48018eb11b229b659dfb32b7a16b88251bac106dd1ff/cffi-1.17.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:cab2eba3830bf4f6d91e2d6718e0e1c14a2f5ad1af68a89d24ace0c6b17cced7", size = 178453 }, - { url = "https://files.pythonhosted.org/packages/cc/b6/1a134d479d3a5a1ff2fabbee551d1d3f1dd70f453e081b5f70d604aae4c0/cffi-1.17.0-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:14b9cbc8f7ac98a739558eb86fabc283d4d564dafed50216e7f7ee62d0d25377", size = 454441 }, - { url = "https://files.pythonhosted.org/packages/b1/b4/e1569475d63aad8042b0935dbf62ae2a54d1e9142424e2b0e924d2d4a529/cffi-1.17.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b00e7bcd71caa0282cbe3c90966f738e2db91e64092a877c3ff7f19a1628fdcb", size = 478543 }, - { url = "https://files.pythonhosted.org/packages/d2/40/a9ad03fbd64309dec5bb70bc803a9a6772602de0ee164d7b9a6ca5a89249/cffi-1.17.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:41f4915e09218744d8bae14759f983e466ab69b178de38066f7579892ff2a555", size = 485463 }, - { url = "https://files.pythonhosted.org/packages/a6/1a/f10be60e006dd9242a24bcc2b1cd55c34c578380100f742d8c610f7a5d26/cffi-1.17.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e4760a68cab57bfaa628938e9c2971137e05ce48e762a9cb53b76c9b569f1204", size = 470854 }, - { url = "https://files.pythonhosted.org/packages/cc/b3/c035ed21aa3d39432bd749fe331ee90e4bc83ea2dbed1f71c4bc26c41084/cffi-1.17.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:011aff3524d578a9412c8b3cfaa50f2c0bd78e03eb7af7aa5e0df59b158efb2f", size = 479096 }, - { url = "https://files.pythonhosted.org/packages/00/cb/6f7edde01131de9382c89430b8e253b8c8754d66b63a62059663ceafeab2/cffi-1.17.0-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:a003ac9edc22d99ae1286b0875c460351f4e101f8c9d9d2576e78d7e048f64e0", size = 484013 }, - { url = "https://files.pythonhosted.org/packages/b9/83/8e4e8c211ea940210d293e951bf06b1bfb90f2eeee590e9778e99b4a8676/cffi-1.17.0-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:ef9528915df81b8f4c7612b19b8628214c65c9b7f74db2e34a646a0a2a0da2d4", size = 488119 }, - { url = "https://files.pythonhosted.org/packages/5e/52/3f7cfbc4f444cb4f73ff17b28690d12436dde665f67d68f1e1687908ab6c/cffi-1.17.0-cp313-cp313-win32.whl", hash = "sha256:70d2aa9fb00cf52034feac4b913181a6e10356019b18ef89bc7c12a283bf5f5a", size = 172122 }, - { url = "https://files.pythonhosted.org/packages/94/19/cf5baa07ee0f0e55eab7382459fbddaba0fdb0ba45973dd92556ae0d02db/cffi-1.17.0-cp313-cp313-win_amd64.whl", hash = "sha256:b7b6ea9e36d32582cda3465f54c4b454f62f23cb083ebc7a94e2ca6ef011c3a7", size = 181504 }, +sdist = { url = "https://files.pythonhosted.org/packages/fc/97/c783634659c2920c3fc70419e3af40972dbaf758daa229a7d6ea6135c90d/cffi-1.17.1.tar.gz", hash = "sha256:1c39c6016c32bc48dd54561950ebd6836e1670f2ae46128f67cf49e789c52824", size = 516621 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/6b/f4/927e3a8899e52a27fa57a48607ff7dc91a9ebe97399b357b85a0c7892e00/cffi-1.17.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:a45e3c6913c5b87b3ff120dcdc03f6131fa0065027d0ed7ee6190736a74cd401", size = 182264 }, + { url = "https://files.pythonhosted.org/packages/6c/f5/6c3a8efe5f503175aaddcbea6ad0d2c96dad6f5abb205750d1b3df44ef29/cffi-1.17.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:30c5e0cb5ae493c04c8b42916e52ca38079f1b235c2f8ae5f4527b963c401caf", size = 178651 }, + { url = "https://files.pythonhosted.org/packages/94/dd/a3f0118e688d1b1a57553da23b16bdade96d2f9bcda4d32e7d2838047ff7/cffi-1.17.1-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f75c7ab1f9e4aca5414ed4d8e5c0e303a34f4421f8a0d47a4d019ceff0ab6af4", size = 445259 }, + { url = "https://files.pythonhosted.org/packages/2e/ea/70ce63780f096e16ce8588efe039d3c4f91deb1dc01e9c73a287939c79a6/cffi-1.17.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a1ed2dd2972641495a3ec98445e09766f077aee98a1c896dcb4ad0d303628e41", size = 469200 }, + { url = "https://files.pythonhosted.org/packages/1c/a0/a4fa9f4f781bda074c3ddd57a572b060fa0df7655d2a4247bbe277200146/cffi-1.17.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:46bf43160c1a35f7ec506d254e5c890f3c03648a4dbac12d624e4490a7046cd1", size = 477235 }, + { url = "https://files.pythonhosted.org/packages/62/12/ce8710b5b8affbcdd5c6e367217c242524ad17a02fe5beec3ee339f69f85/cffi-1.17.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a24ed04c8ffd54b0729c07cee15a81d964e6fee0e3d4d342a27b020d22959dc6", size = 459721 }, + { url = "https://files.pythonhosted.org/packages/ff/6b/d45873c5e0242196f042d555526f92aa9e0c32355a1be1ff8c27f077fd37/cffi-1.17.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:610faea79c43e44c71e1ec53a554553fa22321b65fae24889706c0a84d4ad86d", size = 467242 }, + { url = "https://files.pythonhosted.org/packages/1a/52/d9a0e523a572fbccf2955f5abe883cfa8bcc570d7faeee06336fbd50c9fc/cffi-1.17.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:a9b15d491f3ad5d692e11f6b71f7857e7835eb677955c00cc0aefcd0669adaf6", size = 477999 }, + { url = "https://files.pythonhosted.org/packages/44/74/f2a2460684a1a2d00ca799ad880d54652841a780c4c97b87754f660c7603/cffi-1.17.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:de2ea4b5833625383e464549fec1bc395c1bdeeb5f25c4a3a82b5a8c756ec22f", size = 454242 }, + { url = "https://files.pythonhosted.org/packages/f8/4a/34599cac7dfcd888ff54e801afe06a19c17787dfd94495ab0c8d35fe99fb/cffi-1.17.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:fc48c783f9c87e60831201f2cce7f3b2e4846bf4d8728eabe54d60700b318a0b", size = 478604 }, + { url = "https://files.pythonhosted.org/packages/34/33/e1b8a1ba29025adbdcda5fb3a36f94c03d771c1b7b12f726ff7fef2ebe36/cffi-1.17.1-cp311-cp311-win32.whl", hash = "sha256:85a950a4ac9c359340d5963966e3e0a94a676bd6245a4b55bc43949eee26a655", size = 171727 }, + { url = "https://files.pythonhosted.org/packages/3d/97/50228be003bb2802627d28ec0627837ac0bf35c90cf769812056f235b2d1/cffi-1.17.1-cp311-cp311-win_amd64.whl", hash = "sha256:caaf0640ef5f5517f49bc275eca1406b0ffa6aa184892812030f04c2abf589a0", size = 181400 }, + { url = "https://files.pythonhosted.org/packages/5a/84/e94227139ee5fb4d600a7a4927f322e1d4aea6fdc50bd3fca8493caba23f/cffi-1.17.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:805b4371bf7197c329fcb3ead37e710d1bca9da5d583f5073b799d5c5bd1eee4", size = 183178 }, + { url = "https://files.pythonhosted.org/packages/da/ee/fb72c2b48656111c4ef27f0f91da355e130a923473bf5ee75c5643d00cca/cffi-1.17.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:733e99bc2df47476e3848417c5a4540522f234dfd4ef3ab7fafdf555b082ec0c", size = 178840 }, + { url = "https://files.pythonhosted.org/packages/cc/b6/db007700f67d151abadf508cbfd6a1884f57eab90b1bb985c4c8c02b0f28/cffi-1.17.1-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1257bdabf294dceb59f5e70c64a3e2f462c30c7ad68092d01bbbfb1c16b1ba36", size = 454803 }, + { url = "https://files.pythonhosted.org/packages/1a/df/f8d151540d8c200eb1c6fba8cd0dfd40904f1b0682ea705c36e6c2e97ab3/cffi-1.17.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:da95af8214998d77a98cc14e3a3bd00aa191526343078b530ceb0bd710fb48a5", size = 478850 }, + { url = "https://files.pythonhosted.org/packages/28/c0/b31116332a547fd2677ae5b78a2ef662dfc8023d67f41b2a83f7c2aa78b1/cffi-1.17.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d63afe322132c194cf832bfec0dc69a99fb9bb6bbd550f161a49e9e855cc78ff", size = 485729 }, + { url = "https://files.pythonhosted.org/packages/91/2b/9a1ddfa5c7f13cab007a2c9cc295b70fbbda7cb10a286aa6810338e60ea1/cffi-1.17.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f79fc4fc25f1c8698ff97788206bb3c2598949bfe0fef03d299eb1b5356ada99", size = 471256 }, + { url = "https://files.pythonhosted.org/packages/b2/d5/da47df7004cb17e4955df6a43d14b3b4ae77737dff8bf7f8f333196717bf/cffi-1.17.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b62ce867176a75d03a665bad002af8e6d54644fad99a3c70905c543130e39d93", size = 479424 }, + { url = "https://files.pythonhosted.org/packages/0b/ac/2a28bcf513e93a219c8a4e8e125534f4f6db03e3179ba1c45e949b76212c/cffi-1.17.1-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:386c8bf53c502fff58903061338ce4f4950cbdcb23e2902d86c0f722b786bbe3", size = 484568 }, + { url = "https://files.pythonhosted.org/packages/d4/38/ca8a4f639065f14ae0f1d9751e70447a261f1a30fa7547a828ae08142465/cffi-1.17.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:4ceb10419a9adf4460ea14cfd6bc43d08701f0835e979bf821052f1805850fe8", size = 488736 }, + { url = "https://files.pythonhosted.org/packages/86/c5/28b2d6f799ec0bdecf44dced2ec5ed43e0eb63097b0f58c293583b406582/cffi-1.17.1-cp312-cp312-win32.whl", hash = "sha256:a08d7e755f8ed21095a310a693525137cfe756ce62d066e53f502a83dc550f65", size = 172448 }, + { url = "https://files.pythonhosted.org/packages/50/b9/db34c4755a7bd1cb2d1603ac3863f22bcecbd1ba29e5ee841a4bc510b294/cffi-1.17.1-cp312-cp312-win_amd64.whl", hash = "sha256:51392eae71afec0d0c8fb1a53b204dbb3bcabcb3c9b807eedf3e1e6ccf2de903", size = 181976 }, + { url = "https://files.pythonhosted.org/packages/8d/f8/dd6c246b148639254dad4d6803eb6a54e8c85c6e11ec9df2cffa87571dbe/cffi-1.17.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:f3a2b4222ce6b60e2e8b337bb9596923045681d71e5a082783484d845390938e", size = 182989 }, + { url = "https://files.pythonhosted.org/packages/8b/f1/672d303ddf17c24fc83afd712316fda78dc6fce1cd53011b839483e1ecc8/cffi-1.17.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:0984a4925a435b1da406122d4d7968dd861c1385afe3b45ba82b750f229811e2", size = 178802 }, + { url = "https://files.pythonhosted.org/packages/0e/2d/eab2e858a91fdff70533cab61dcff4a1f55ec60425832ddfdc9cd36bc8af/cffi-1.17.1-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d01b12eeeb4427d3110de311e1774046ad344f5b1a7403101878976ecd7a10f3", size = 454792 }, + { url = "https://files.pythonhosted.org/packages/75/b2/fbaec7c4455c604e29388d55599b99ebcc250a60050610fadde58932b7ee/cffi-1.17.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:706510fe141c86a69c8ddc029c7910003a17353970cff3b904ff0686a5927683", size = 478893 }, + { url = "https://files.pythonhosted.org/packages/4f/b7/6e4a2162178bf1935c336d4da8a9352cccab4d3a5d7914065490f08c0690/cffi-1.17.1-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:de55b766c7aa2e2a3092c51e0483d700341182f08e67c63630d5b6f200bb28e5", size = 485810 }, + { url = "https://files.pythonhosted.org/packages/c7/8a/1d0e4a9c26e54746dc08c2c6c037889124d4f59dffd853a659fa545f1b40/cffi-1.17.1-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c59d6e989d07460165cc5ad3c61f9fd8f1b4796eacbd81cee78957842b834af4", size = 471200 }, + { url = "https://files.pythonhosted.org/packages/26/9f/1aab65a6c0db35f43c4d1b4f580e8df53914310afc10ae0397d29d697af4/cffi-1.17.1-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dd398dbc6773384a17fe0d3e7eeb8d1a21c2200473ee6806bb5e6a8e62bb73dd", size = 479447 }, + { url = "https://files.pythonhosted.org/packages/5f/e4/fb8b3dd8dc0e98edf1135ff067ae070bb32ef9d509d6cb0f538cd6f7483f/cffi-1.17.1-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:3edc8d958eb099c634dace3c7e16560ae474aa3803a5df240542b305d14e14ed", size = 484358 }, + { url = "https://files.pythonhosted.org/packages/f1/47/d7145bf2dc04684935d57d67dff9d6d795b2ba2796806bb109864be3a151/cffi-1.17.1-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:72e72408cad3d5419375fc87d289076ee319835bdfa2caad331e377589aebba9", size = 488469 }, + { url = "https://files.pythonhosted.org/packages/bf/ee/f94057fa6426481d663b88637a9a10e859e492c73d0384514a17d78ee205/cffi-1.17.1-cp313-cp313-win32.whl", hash = "sha256:e03eab0a8677fa80d646b5ddece1cbeaf556c313dcfac435ba11f107ba117b5d", size = 172475 }, + { url = "https://files.pythonhosted.org/packages/7c/fc/6a8cb64e5f0324877d503c854da15d76c1e50eb722e320b15345c4d0c6de/cffi-1.17.1-cp313-cp313-win_amd64.whl", hash = "sha256:f6a16c31041f09ead72d69f583767292f750d24913dadacf5756b966aacb3f1a", size = 182009 }, ] [[package]] @@ -603,11 +603,11 @@ wheels = [ [[package]] name = "filelock" -version = "3.15.4" +version = "3.16.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/08/dd/49e06f09b6645156550fb9aee9cc1e59aba7efbc972d665a1bd6ae0435d4/filelock-3.15.4.tar.gz", hash = "sha256:2207938cbc1844345cb01a5a95524dae30f0ce089eba5b00378295a17e3e90cb", size = 18007 } +sdist = { url = "https://files.pythonhosted.org/packages/e6/76/3981447fd369539aba35797db99a8e2ff7ed01d9aa63e9344a31658b8d81/filelock-3.16.0.tar.gz", hash = "sha256:81de9eb8453c769b63369f87f11131a7ab04e367f8d97ad39dc230daa07e3bec", size = 18008 } wheels = [ - { url = "https://files.pythonhosted.org/packages/ae/f0/48285f0262fe47103a4a45972ed2f9b93e4c80b8fd609fa98da78b2a5706/filelock-3.15.4-py3-none-any.whl", hash = "sha256:6ca1fffae96225dab4c6eaf1c4f4f28cd2568d3ec2a44e15a08520504de468e7", size = 16159 }, + { url = "https://files.pythonhosted.org/packages/2f/95/f9310f35376024e1086c59cbb438d319fc9a4ef853289ce7c661539edbd4/filelock-3.16.0-py3-none-any.whl", hash = "sha256:f6ed4c963184f4c84dd5557ce8fece759a3724b37b80c6c4f20a2f63a4dc6609", size = 16170 }, ] [[package]] @@ -854,43 +854,58 @@ wheels = [ [[package]] name = "kiwisolver" -version = "1.4.6" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/52/bd/e54734b47fa63b52e34bad5b60e6842628b9a47c14254c5557f2a4b37b2e/kiwisolver-1.4.6.tar.gz", hash = "sha256:3cda29d601445e6aa11f80d90a9b8c2ae501650c55d7ad29829bd44499c9e7e0", size = 97171 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/9a/9a/d22443947c1bfacff8596fe588ac5c3bf9e88a1b557c9e3fec12f1487133/kiwisolver-1.4.6-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:45a5cb5abad1ad9c265eed7e058fefafeb7964565b93b397ba2f480faec8d674", size = 122442 }, - { url = "https://files.pythonhosted.org/packages/b8/70/888ce89a1a2b4fbeb141729a4ea73c7227e758a7a8e0f5f7b9a10c83e03a/kiwisolver-1.4.6-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:7e52b2568c47fb4f54d17576954e02b1de156c85152f87283a99db9670fd18c0", size = 65755 }, - { url = "https://files.pythonhosted.org/packages/17/fb/8d7100e23b1130256bb480a19e2a99b9100c268c0ea4ce6ce42073301ef0/kiwisolver-1.4.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:00af95204100bc1d0f26e1ed52ec77d6e3da5c9b845c88d31875c164e4ba6c0c", size = 64311 }, - { url = "https://files.pythonhosted.org/packages/77/34/704e1e382a5b59097ed546d1093758e6c106eb4b5ffd9340704b6cb5414e/kiwisolver-1.4.6-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:50ab1fedf86f3951a9e90a64edd15f598860ed60cd3664259756f097d527b5ae", size = 1334259 }, - { url = "https://files.pythonhosted.org/packages/2f/8d/63f912f0f7245cbcd0ee9956585509dc85cb764adbe8d06e342596f03536/kiwisolver-1.4.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dbc985766bf20141ce64baecc39fb9fedbce094b2b8de1bb62676b79328988e4", size = 1426582 }, - { url = "https://files.pythonhosted.org/packages/37/cb/ae78c5a007d3c71aecd6d008c9923b29e14ef3663ccc2bc05f5dde9f071c/kiwisolver-1.4.6-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f1942a155c737a7c3835a957897f0cc9ebc0085b7a75d934d86aecb1b27b8873", size = 1541078 }, - { url = "https://files.pythonhosted.org/packages/bf/69/f21cdc8537c08e7cc2097361b1d7ad3c47192509dfca7848e42abe6f2dec/kiwisolver-1.4.6-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f464403e391724f8e7dff188d3fb77a85bd1273b3fdba182e6671abcc44434f8", size = 1470055 }, - { url = "https://files.pythonhosted.org/packages/79/25/b4e6929ee94dcb3144cacb2f427dc27aaec42aeb9367421b2efd5f771393/kiwisolver-1.4.6-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ce5efe545eea86f52ec5a1185e5052815ea86778e8268bad71fa46433f7c0bef", size = 1426374 }, - { url = "https://files.pythonhosted.org/packages/40/dd/11ae8c3276e7f975f8c7e6117184cc3afe1ef5a71745456926104b0c468d/kiwisolver-1.4.6-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:cb30165f71b7b3378668346e220c81d590593a3a1ff76428a53780310df03f35", size = 2222229 }, - { url = "https://files.pythonhosted.org/packages/67/28/46b28157c237e6c08d40843f4d1ccb74ef727c6c420ced5864e0501b5200/kiwisolver-1.4.6-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:f5a987f740e1c9964e614acb87ba1f014b4be760a341effc8dc789913d1840e6", size = 2368628 }, - { url = "https://files.pythonhosted.org/packages/33/77/8d876efef1921bd918a9dca177fe5e9adda372b4b19300101a38aca5558b/kiwisolver-1.4.6-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:f2ceaa6d0450623d108956647ef19a1a28c7e07880f1171c932477308d44d80b", size = 2329025 }, - { url = "https://files.pythonhosted.org/packages/fe/55/d9637527165b65fc3281d52415aaa12a8526200362ebd8ababb1962149c5/kiwisolver-1.4.6-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:788cbf99738f18ae8a27b9d4d7314502b4b917005cfdacd1d6a59038332ae24d", size = 2468484 }, - { url = "https://files.pythonhosted.org/packages/b7/7d/2297d08507d54a6a73c6f4377d8b7a795b4715caeca571e8a494f527d120/kiwisolver-1.4.6-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:2f6668678a6b9488a7f8a6320e1b1c6396d179a976472dbc08d1600d04119511", size = 2284076 }, - { url = "https://files.pythonhosted.org/packages/8f/5b/64bc3c75c269b8820d98120c9d41079bac3129d83eed1892c50c4d760d2d/kiwisolver-1.4.6-cp311-cp311-win32.whl", hash = "sha256:10a09a3e4213c2806bcfd2eb4edb756c557973d2cacf06873b18a247fce897da", size = 46643 }, - { url = "https://files.pythonhosted.org/packages/5f/40/2b03bc57af2e41da8fec1b30d16f733ee28b85888a5368688e99d5c664c2/kiwisolver-1.4.6-cp311-cp311-win_amd64.whl", hash = "sha256:683ffef2c51fdc54112dc610d06b59b88c21e23fb669b905da6d5bec80da1bde", size = 56023 }, - { url = "https://files.pythonhosted.org/packages/23/f1/ea9a7d24ad1f8c4144dd4eefb11d456f2aa90fc59a6f373b8de5f770f35a/kiwisolver-1.4.6-cp311-cp311-win_arm64.whl", hash = "sha256:3b852c7f0ed9a2fd339c228829bca0964233ed45de50aae3e87b72ca37d177f8", size = 48540 }, - { url = "https://files.pythonhosted.org/packages/81/84/8a5b628c6f2e661a48b296f335fdc1503f8ab5f49782db79217439853a34/kiwisolver-1.4.6-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:979df7e9334f6a3694ee9be8d42817e519ef6d155a16499714d082cf41296852", size = 121807 }, - { url = "https://files.pythonhosted.org/packages/7f/2f/92210b842c87a22df953727c2ba2ceb28827de3a47dc157701d4524885fa/kiwisolver-1.4.6-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:50c9c6c42bb6ca231626d1182b9128e89c5ce3c64456f811ff0280deb42d7bfe", size = 65529 }, - { url = "https://files.pythonhosted.org/packages/51/8f/e1a0d4be4f549a2ef7a9dfa478b50ee92e9b9156e0194072c96f8b934757/kiwisolver-1.4.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ace86489e7951bd26329a589198d3875c3d48380f889c69d3eb254b506a80101", size = 63895 }, - { url = "https://files.pythonhosted.org/packages/6d/0a/b82266406429d3a114f861d9dbfe08eee9ba1475ea09a75cefc0ccbb5372/kiwisolver-1.4.6-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f94771988da902b475f78e85cf63c5c94392773b4a6494234d87c1b363b2fbc5", size = 1369291 }, - { url = "https://files.pythonhosted.org/packages/61/b5/2e68f99a97131bd06f7eeca5294541cde33d92af875f945cd4c1296c94a4/kiwisolver-1.4.6-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a62379eee430b1c477bb0a0bf6858a57c7c0dad9cee8b3144a5cb5d366c66a54", size = 1461449 }, - { url = "https://files.pythonhosted.org/packages/89/9e/47db05cdf2109a2e375c076fce6088c5fb493331225f8e588bd1992f287c/kiwisolver-1.4.6-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e99b97d69499a7414572c906fbc7ca312519f2e17999730129f6c4492786e953", size = 1579164 }, - { url = "https://files.pythonhosted.org/packages/1f/d7/b6d86dd194ef83a259e30e2356c3ed16b40f59053a13dd6295c2ab99816e/kiwisolver-1.4.6-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ab93f58afe3a02922a343189404f24ed885564e6316649790240124b95ef1d6e", size = 1507308 }, - { url = "https://files.pythonhosted.org/packages/5a/5f/f011569a61d48b39bbf606d675de79c85effabc1fbd291a6396538a8cc87/kiwisolver-1.4.6-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:34105f4460ba50fc18a16a8e77a5122f7affe075628763fda748ad0ec534c3ee", size = 1464190 }, - { url = "https://files.pythonhosted.org/packages/97/44/9adc480290c47e3a3f2bac4e1de2b3f164fef80c50b2e68d25f1503e36de/kiwisolver-1.4.6-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:0081f85f0222620563409d4804c6567a930a45dafbe9674c7913fde131653992", size = 2247874 }, - { url = "https://files.pythonhosted.org/packages/5c/5a/0585de17a52af89689b9d79575317e54d5541bc8d0aa8449faf8b9fd58a2/kiwisolver-1.4.6-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:df2a4a7cc2e01991e039a792457751b601bdf30143ab5f23f9a1e58f20c875f4", size = 2404199 }, - { url = "https://files.pythonhosted.org/packages/05/9c/fb3c9c407415126e31918db329de230988e779c9205a7099d674e5f64775/kiwisolver-1.4.6-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:1f401784df70ea2870e4e10adade66b5b06cb2c151bc2a8a414a1d10554e9a81", size = 2352457 }, - { url = "https://files.pythonhosted.org/packages/e2/e7/d7768d21801eb26dea144c264b4da10b995af279b017056c242c8f2ed5ac/kiwisolver-1.4.6-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:b19761c8c613b6d04c44f1a4797a144b44136f17ec009ccfb025e17b5698140c", size = 2501358 }, - { url = "https://files.pythonhosted.org/packages/92/47/fe6423e99e5e00fd8c014013bd146c019b299defee0d78a8fc8619c77d88/kiwisolver-1.4.6-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ee7289430ded484cc2eff9d8ffcce58ed7fe2c26919321dbc0580322a49e0120", size = 2314119 }, - { url = "https://files.pythonhosted.org/packages/ee/90/d6ede870b381ae0386475c20327b1c8e52d3b3ced0c9a6d4f1bb067bfba2/kiwisolver-1.4.6-cp312-cp312-win32.whl", hash = "sha256:331b9d9f408e874ecf34bd79b79df8e099f0b1b351b8844609c1bfdc8d2d45b2", size = 46366 }, - { url = "https://files.pythonhosted.org/packages/6a/32/755f2db6c96102ebb7f078f617b17be18d5ba9ecf1423fec2194e5812451/kiwisolver-1.4.6-cp312-cp312-win_amd64.whl", hash = "sha256:a9be95d086578b3ada61a4621c0e7ee5f456820bfdccc3329061fdeae1e31179", size = 55882 }, - { url = "https://files.pythonhosted.org/packages/85/86/1c4fb5c0cd90bd1048d7de3febc8f94cd015d8c523d96a7aff4fc0045b00/kiwisolver-1.4.6-cp312-cp312-win_arm64.whl", hash = "sha256:773f2d87825779ab69196dfcf63e9d91043273421c6128c8d4ed82bc6316068f", size = 48533 }, - { url = "https://files.pythonhosted.org/packages/6d/16/de2395bfdc90626e8e7dc86f2349b0802d7e91d9cce4cd992c69ba2a8084/kiwisolver-1.4.6-cp313-cp313-win_arm64.whl", hash = "sha256:140f376c22b5148453acff768cff19c34ebbd593126617018732ea1d9ce65547", size = 48533 }, +version = "1.4.7" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/85/4d/2255e1c76304cbd60b48cee302b66d1dde4468dc5b1160e4b7cb43778f2a/kiwisolver-1.4.7.tar.gz", hash = "sha256:9893ff81bd7107f7b685d3017cc6583daadb4fc26e4a888350df530e41980a60", size = 97286 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/e9/44/77429fa0a58f941d6e1c58da9efe08597d2e86bf2b2cce6626834f49d07b/kiwisolver-1.4.7-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d2b0e12a42fb4e72d509fc994713d099cbb15ebf1103545e8a45f14da2dfca54", size = 122442 }, + { url = "https://files.pythonhosted.org/packages/e5/20/8c75caed8f2462d63c7fd65e16c832b8f76cda331ac9e615e914ee80bac9/kiwisolver-1.4.7-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2a8781ac3edc42ea4b90bc23e7d37b665d89423818e26eb6df90698aa2287c95", size = 65762 }, + { url = "https://files.pythonhosted.org/packages/f4/98/fe010f15dc7230f45bc4cf367b012d651367fd203caaa992fd1f5963560e/kiwisolver-1.4.7-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:46707a10836894b559e04b0fd143e343945c97fd170d69a2d26d640b4e297935", size = 64319 }, + { url = "https://files.pythonhosted.org/packages/8b/1b/b5d618f4e58c0675654c1e5051bcf42c776703edb21c02b8c74135541f60/kiwisolver-1.4.7-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ef97b8df011141c9b0f6caf23b29379f87dd13183c978a30a3c546d2c47314cb", size = 1334260 }, + { url = "https://files.pythonhosted.org/packages/b8/01/946852b13057a162a8c32c4c8d2e9ed79f0bb5d86569a40c0b5fb103e373/kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3ab58c12a2cd0fc769089e6d38466c46d7f76aced0a1f54c77652446733d2d02", size = 1426589 }, + { url = "https://files.pythonhosted.org/packages/70/d1/c9f96df26b459e15cf8a965304e6e6f4eb291e0f7a9460b4ad97b047561e/kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:803b8e1459341c1bb56d1c5c010406d5edec8a0713a0945851290a7930679b51", size = 1541080 }, + { url = "https://files.pythonhosted.org/packages/d3/73/2686990eb8b02d05f3de759d6a23a4ee7d491e659007dd4c075fede4b5d0/kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f9a9e8a507420fe35992ee9ecb302dab68550dedc0da9e2880dd88071c5fb052", size = 1470049 }, + { url = "https://files.pythonhosted.org/packages/a7/4b/2db7af3ed3af7c35f388d5f53c28e155cd402a55432d800c543dc6deb731/kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:18077b53dc3bb490e330669a99920c5e6a496889ae8c63b58fbc57c3d7f33a18", size = 1426376 }, + { url = "https://files.pythonhosted.org/packages/05/83/2857317d04ea46dc5d115f0df7e676997bbd968ced8e2bd6f7f19cfc8d7f/kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:6af936f79086a89b3680a280c47ea90b4df7047b5bdf3aa5c524bbedddb9e545", size = 2222231 }, + { url = "https://files.pythonhosted.org/packages/0d/b5/866f86f5897cd4ab6d25d22e403404766a123f138bd6a02ecb2cdde52c18/kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:3abc5b19d24af4b77d1598a585b8a719beb8569a71568b66f4ebe1fb0449460b", size = 2368634 }, + { url = "https://files.pythonhosted.org/packages/c1/ee/73de8385403faba55f782a41260210528fe3273d0cddcf6d51648202d6d0/kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:933d4de052939d90afbe6e9d5273ae05fb836cc86c15b686edd4b3560cc0ee36", size = 2329024 }, + { url = "https://files.pythonhosted.org/packages/a1/e7/cd101d8cd2cdfaa42dc06c433df17c8303d31129c9fdd16c0ea37672af91/kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:65e720d2ab2b53f1f72fb5da5fb477455905ce2c88aaa671ff0a447c2c80e8e3", size = 2468484 }, + { url = "https://files.pythonhosted.org/packages/e1/72/84f09d45a10bc57a40bb58b81b99d8f22b58b2040c912b7eb97ebf625bf2/kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:3bf1ed55088f214ba6427484c59553123fdd9b218a42bbc8c6496d6754b1e523", size = 2284078 }, + { url = "https://files.pythonhosted.org/packages/d2/d4/71828f32b956612dc36efd7be1788980cb1e66bfb3706e6dec9acad9b4f9/kiwisolver-1.4.7-cp311-cp311-win32.whl", hash = "sha256:4c00336b9dd5ad96d0a558fd18a8b6f711b7449acce4c157e7343ba92dd0cf3d", size = 46645 }, + { url = "https://files.pythonhosted.org/packages/a1/65/d43e9a20aabcf2e798ad1aff6c143ae3a42cf506754bcb6a7ed8259c8425/kiwisolver-1.4.7-cp311-cp311-win_amd64.whl", hash = "sha256:929e294c1ac1e9f615c62a4e4313ca1823ba37326c164ec720a803287c4c499b", size = 56022 }, + { url = "https://files.pythonhosted.org/packages/35/b3/9f75a2e06f1b4ca00b2b192bc2b739334127d27f1d0625627ff8479302ba/kiwisolver-1.4.7-cp311-cp311-win_arm64.whl", hash = "sha256:e33e8fbd440c917106b237ef1a2f1449dfbb9b6f6e1ce17c94cd6a1e0d438376", size = 48536 }, + { url = "https://files.pythonhosted.org/packages/97/9c/0a11c714cf8b6ef91001c8212c4ef207f772dd84540104952c45c1f0a249/kiwisolver-1.4.7-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:5360cc32706dab3931f738d3079652d20982511f7c0ac5711483e6eab08efff2", size = 121808 }, + { url = "https://files.pythonhosted.org/packages/f2/d8/0fe8c5f5d35878ddd135f44f2af0e4e1d379e1c7b0716f97cdcb88d4fd27/kiwisolver-1.4.7-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:942216596dc64ddb25adb215c3c783215b23626f8d84e8eff8d6d45c3f29f75a", size = 65531 }, + { url = "https://files.pythonhosted.org/packages/80/c5/57fa58276dfdfa612241d640a64ca2f76adc6ffcebdbd135b4ef60095098/kiwisolver-1.4.7-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:48b571ecd8bae15702e4f22d3ff6a0f13e54d3d00cd25216d5e7f658242065ee", size = 63894 }, + { url = "https://files.pythonhosted.org/packages/8b/e9/26d3edd4c4ad1c5b891d8747a4f81b1b0aba9fb9721de6600a4adc09773b/kiwisolver-1.4.7-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ad42ba922c67c5f219097b28fae965e10045ddf145d2928bfac2eb2e17673640", size = 1369296 }, + { url = "https://files.pythonhosted.org/packages/b6/67/3f4850b5e6cffb75ec40577ddf54f7b82b15269cc5097ff2e968ee32ea7d/kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:612a10bdae23404a72941a0fc8fa2660c6ea1217c4ce0dbcab8a8f6543ea9e7f", size = 1461450 }, + { url = "https://files.pythonhosted.org/packages/52/be/86cbb9c9a315e98a8dc6b1d23c43cffd91d97d49318854f9c37b0e41cd68/kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9e838bba3a3bac0fe06d849d29772eb1afb9745a59710762e4ba3f4cb8424483", size = 1579168 }, + { url = "https://files.pythonhosted.org/packages/0f/00/65061acf64bd5fd34c1f4ae53f20b43b0a017a541f242a60b135b9d1e301/kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:22f499f6157236c19f4bbbd472fa55b063db77a16cd74d49afe28992dff8c258", size = 1507308 }, + { url = "https://files.pythonhosted.org/packages/21/e4/c0b6746fd2eb62fe702118b3ca0cb384ce95e1261cfada58ff693aeec08a/kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:693902d433cf585133699972b6d7c42a8b9f8f826ebcaf0132ff55200afc599e", size = 1464186 }, + { url = "https://files.pythonhosted.org/packages/0a/0f/529d0a9fffb4d514f2782c829b0b4b371f7f441d61aa55f1de1c614c4ef3/kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:4e77f2126c3e0b0d055f44513ed349038ac180371ed9b52fe96a32aa071a5107", size = 2247877 }, + { url = "https://files.pythonhosted.org/packages/d1/e1/66603ad779258843036d45adcbe1af0d1a889a07af4635f8b4ec7dccda35/kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:657a05857bda581c3656bfc3b20e353c232e9193eb167766ad2dc58b56504948", size = 2404204 }, + { url = "https://files.pythonhosted.org/packages/8d/61/de5fb1ca7ad1f9ab7970e340a5b833d735df24689047de6ae71ab9d8d0e7/kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:4bfa75a048c056a411f9705856abfc872558e33c055d80af6a380e3658766038", size = 2352461 }, + { url = "https://files.pythonhosted.org/packages/ba/d2/0edc00a852e369827f7e05fd008275f550353f1f9bcd55db9363d779fc63/kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:34ea1de54beef1c104422d210c47c7d2a4999bdecf42c7b5718fbe59a4cac383", size = 2501358 }, + { url = "https://files.pythonhosted.org/packages/84/15/adc15a483506aec6986c01fb7f237c3aec4d9ed4ac10b756e98a76835933/kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:90da3b5f694b85231cf93586dad5e90e2d71b9428f9aad96952c99055582f520", size = 2314119 }, + { url = "https://files.pythonhosted.org/packages/36/08/3a5bb2c53c89660863a5aa1ee236912269f2af8762af04a2e11df851d7b2/kiwisolver-1.4.7-cp312-cp312-win32.whl", hash = "sha256:18e0cca3e008e17fe9b164b55735a325140a5a35faad8de92dd80265cd5eb80b", size = 46367 }, + { url = "https://files.pythonhosted.org/packages/19/93/c05f0a6d825c643779fc3c70876bff1ac221f0e31e6f701f0e9578690d70/kiwisolver-1.4.7-cp312-cp312-win_amd64.whl", hash = "sha256:58cb20602b18f86f83a5c87d3ee1c766a79c0d452f8def86d925e6c60fbf7bfb", size = 55884 }, + { url = "https://files.pythonhosted.org/packages/d2/f9/3828d8f21b6de4279f0667fb50a9f5215e6fe57d5ec0d61905914f5b6099/kiwisolver-1.4.7-cp312-cp312-win_arm64.whl", hash = "sha256:f5a8b53bdc0b3961f8b6125e198617c40aeed638b387913bf1ce78afb1b0be2a", size = 48528 }, + { url = "https://files.pythonhosted.org/packages/c4/06/7da99b04259b0f18b557a4effd1b9c901a747f7fdd84cf834ccf520cb0b2/kiwisolver-1.4.7-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:2e6039dcbe79a8e0f044f1c39db1986a1b8071051efba3ee4d74f5b365f5226e", size = 121913 }, + { url = "https://files.pythonhosted.org/packages/97/f5/b8a370d1aa593c17882af0a6f6755aaecd643640c0ed72dcfd2eafc388b9/kiwisolver-1.4.7-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:a1ecf0ac1c518487d9d23b1cd7139a6a65bc460cd101ab01f1be82ecf09794b6", size = 65627 }, + { url = "https://files.pythonhosted.org/packages/2a/fc/6c0374f7503522539e2d4d1b497f5ebad3f8ed07ab51aed2af988dd0fb65/kiwisolver-1.4.7-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:7ab9ccab2b5bd5702ab0803676a580fffa2aa178c2badc5557a84cc943fcf750", size = 63888 }, + { url = "https://files.pythonhosted.org/packages/bf/3e/0b7172793d0f41cae5c923492da89a2ffcd1adf764c16159ca047463ebd3/kiwisolver-1.4.7-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f816dd2277f8d63d79f9c8473a79fe54047bc0467754962840782c575522224d", size = 1369145 }, + { url = "https://files.pythonhosted.org/packages/77/92/47d050d6f6aced2d634258123f2688fbfef8ded3c5baf2c79d94d91f1f58/kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cf8bcc23ceb5a1b624572a1623b9f79d2c3b337c8c455405ef231933a10da379", size = 1461448 }, + { url = "https://files.pythonhosted.org/packages/9c/1b/8f80b18e20b3b294546a1adb41701e79ae21915f4175f311a90d042301cf/kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:dea0bf229319828467d7fca8c7c189780aa9ff679c94539eed7532ebe33ed37c", size = 1578750 }, + { url = "https://files.pythonhosted.org/packages/a4/fe/fe8e72f3be0a844f257cadd72689c0848c6d5c51bc1d60429e2d14ad776e/kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7c06a4c7cf15ec739ce0e5971b26c93638730090add60e183530d70848ebdd34", size = 1507175 }, + { url = "https://files.pythonhosted.org/packages/39/fa/cdc0b6105d90eadc3bee525fecc9179e2b41e1ce0293caaf49cb631a6aaf/kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:913983ad2deb14e66d83c28b632fd35ba2b825031f2fa4ca29675e665dfecbe1", size = 1463963 }, + { url = "https://files.pythonhosted.org/packages/6e/5c/0c03c4e542720c6177d4f408e56d1c8315899db72d46261a4e15b8b33a41/kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:5337ec7809bcd0f424c6b705ecf97941c46279cf5ed92311782c7c9c2026f07f", size = 2248220 }, + { url = "https://files.pythonhosted.org/packages/3d/ee/55ef86d5a574f4e767df7da3a3a7ff4954c996e12d4fbe9c408170cd7dcc/kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:4c26ed10c4f6fa6ddb329a5120ba3b6db349ca192ae211e882970bfc9d91420b", size = 2404463 }, + { url = "https://files.pythonhosted.org/packages/0f/6d/73ad36170b4bff4825dc588acf4f3e6319cb97cd1fb3eb04d9faa6b6f212/kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:c619b101e6de2222c1fcb0531e1b17bbffbe54294bfba43ea0d411d428618c27", size = 2352842 }, + { url = "https://files.pythonhosted.org/packages/0b/16/fa531ff9199d3b6473bb4d0f47416cdb08d556c03b8bc1cccf04e756b56d/kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:073a36c8273647592ea332e816e75ef8da5c303236ec0167196793eb1e34657a", size = 2501635 }, + { url = "https://files.pythonhosted.org/packages/78/7e/aa9422e78419db0cbe75fb86d8e72b433818f2e62e2e394992d23d23a583/kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:3ce6b2b0231bda412463e152fc18335ba32faf4e8c23a754ad50ffa70e4091ee", size = 2314556 }, + { url = "https://files.pythonhosted.org/packages/a8/b2/15f7f556df0a6e5b3772a1e076a9d9f6c538ce5f05bd590eca8106508e06/kiwisolver-1.4.7-cp313-cp313-win32.whl", hash = "sha256:f4c9aee212bc89d4e13f58be11a56cc8036cabad119259d12ace14b34476fd07", size = 46364 }, + { url = "https://files.pythonhosted.org/packages/0b/db/32e897e43a330eee8e4770bfd2737a9584b23e33587a0812b8e20aac38f7/kiwisolver-1.4.7-cp313-cp313-win_amd64.whl", hash = "sha256:8a3ec5aa8e38fc4c8af308917ce12c536f1c88452ce554027e55b22cbbfbff76", size = 55887 }, + { url = "https://files.pythonhosted.org/packages/c8/a4/df2bdca5270ca85fd25253049eb6708d4127be2ed0e5c2650217450b59e9/kiwisolver-1.4.7-cp313-cp313-win_arm64.whl", hash = "sha256:76c8094ac20ec259471ac53e774623eb62e6e1f56cd8690c67ce6ce4fcb05650", size = 48530 }, ] [[package]] @@ -1198,16 +1213,16 @@ wheels = [ [[package]] name = "msal" -version = "1.30.0" +version = "1.31.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cryptography" }, { name = "pyjwt", extra = ["crypto"] }, { name = "requests" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/03/ce/45b9af8f43fbbf34d15162e1e39ce34b675c234c56638277cc05562b6dbf/msal-1.30.0.tar.gz", hash = "sha256:b4bf00850092e465157d814efa24a18f788284c9a479491024d62903085ea2fb", size = 142510 } +sdist = { url = "https://files.pythonhosted.org/packages/59/04/8d7aa5c671a26ca5612257fd419f97380ba89cdd231b2eb67df58483796d/msal-1.31.0.tar.gz", hash = "sha256:2c4f189cf9cc8f00c80045f66d39b7c0f3ed45873fd3d1f2af9f22db2e12ff4b", size = 144950 } wheels = [ - { url = "https://files.pythonhosted.org/packages/ab/82/8f19334da43b7ef72d995587991a446f140346d76edb96a2c1a2689588e9/msal-1.30.0-py3-none-any.whl", hash = "sha256:423872177410cb61683566dc3932db7a76f661a5d2f6f52f02a047f101e1c1de", size = 111760 }, + { url = "https://files.pythonhosted.org/packages/cd/40/0a5d743484e1ad00493bdffa8d10d7dbc6a51fec95290ad396e47e79fa43/msal-1.31.0-py3-none-any.whl", hash = "sha256:96bc37cff82ebe4b160d5fc0f1196f6ca8b50e274ecd0ec5bf69c438514086e7", size = 113109 }, ] [[package]] @@ -1351,7 +1366,7 @@ wheels = [ [[package]] name = "onnxruntime" -version = "1.19.0" +version = "1.19.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "coloredlogs" }, @@ -1362,21 +1377,15 @@ dependencies = [ { name = "sympy" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/80/16/fc200316725d04731d8ffc5d2105887a1e400d760b0c7fd464744335cd29/onnxruntime-1.19.0-cp311-cp311-macosx_11_0_universal2.whl", hash = "sha256:a2b53b3c287cd933e5eb597273926e899082d8c84ab96e1b34035764a1627e17", size = 16778356 }, - { url = "https://files.pythonhosted.org/packages/cc/3c/ff2ecf2a842822bc5e9758747bdfd4163c53af470421f07afd6cba1ced7d/onnxruntime-1.19.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:e94984663963e74fbb468bde9ec6f19dcf890b594b35e249c4dc8789d08993c5", size = 11492628 }, - { url = "https://files.pythonhosted.org/packages/fa/ca/769da06e76b14a315a1effa5b01d906963379495cd82c00b5023be4c3e61/onnxruntime-1.19.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6f379d1f050cfb55ce015d53727b78ee362febc065c38eed81512b22b757da73", size = 13172071 }, - { url = "https://files.pythonhosted.org/packages/75/7c/5a7e3fd98f9af3c43d6073c38afff8c18d201a72d1eba77c93dd230b8501/onnxruntime-1.19.0-cp311-cp311-win32.whl", hash = "sha256:4ccb48faea02503275ae7e79e351434fc43c294c4cb5c4d8bcb7479061396614", size = 9589924 }, - { url = "https://files.pythonhosted.org/packages/78/86/fd21288f9e4096d9c27bd0f221cb61719baa97d5e187549a9f0e84e386ae/onnxruntime-1.19.0-cp311-cp311-win_amd64.whl", hash = "sha256:9cdc8d311289a84e77722de68bd22b8adfb94eea26f4be6f9e017350faac8b18", size = 11083172 }, - { url = "https://files.pythonhosted.org/packages/d1/3c/7cd126254658f0371fadf8651957387d7f743b1b85545e3b783a7f717215/onnxruntime-1.19.0-cp312-cp312-macosx_11_0_universal2.whl", hash = "sha256:1b59eaec1be9a8613c5fdeaafe67f73a062edce3ac03bbbdc9e2d98b58a30617", size = 16789643 }, - { url = "https://files.pythonhosted.org/packages/bf/6e/aae5420a45cbbcacef4c65f70067c11bed7cbb8fda12e0728f37d29746e5/onnxruntime-1.19.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:be4144d014a4b25184e63ce7a463a2e7796e2f3df931fccc6a6aefa6f1365dc5", size = 11483896 }, - { url = "https://files.pythonhosted.org/packages/e6/0f/ad2ec6d490d9cb4ea82dd46382396827cb8ca9a469a56368fc7ef2fb52a4/onnxruntime-1.19.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:10d7e7d4ca7021ce7f29a66dbc6071addf2de5839135339bd855c6d9c2bba371", size = 13177713 }, - { url = "https://files.pythonhosted.org/packages/de/4e/059cae46e48d183ac9b1d0be7ece1c5878711f4a31a206a9dcb34a89e3f5/onnxruntime-1.19.0-cp312-cp312-win32.whl", hash = "sha256:87f2c58b577a1fb31dc5d92b647ecc588fd5f1ea0c3ad4526f5f80a113357c8d", size = 9591661 }, - { url = "https://files.pythonhosted.org/packages/a0/ed/7ac157855cd2135ba894836ce4d027830b78d71832c9e658046e5b1b3d23/onnxruntime-1.19.0-cp312-cp312-win_amd64.whl", hash = "sha256:8a1f50d49676d7b69566536ff039d9e4e95fc482a55673719f46528218ecbb94", size = 11084335 }, + { url = "https://files.pythonhosted.org/packages/f3/78/e29f5fb76e0f6524f3520e8e5b9d53282784b45d14068c5112db9f712b0a/onnxruntime-1.19.2-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c1dfe4f660a71b31caa81fc298a25f9612815215a47b286236e61d540350d7b6", size = 11496005 }, + { url = "https://files.pythonhosted.org/packages/60/ce/be4152da5c1030ab5a159a4a792ed9abad6ba498d79ef0aeba593ff7b5bf/onnxruntime-1.19.2-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a36511dc07c5c964b916697e42e366fa43c48cdb3d3503578d78cef30417cb84", size = 13167809 }, + { url = "https://files.pythonhosted.org/packages/47/64/da42254ec14452cad2cdd4cf407094841c0a378c0d08944e9a36172197e9/onnxruntime-1.19.2-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d2d366fbcc205ce68a8a3bde2185fd15c604d9645888703785b61ef174265168", size = 11486028 }, + { url = "https://files.pythonhosted.org/packages/b2/92/3574f6836f33b1b25f272293e72538c38451b12c2d9aa08630bb6bc0f057/onnxruntime-1.19.2-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:477b93df4db467e9cbf34051662a4b27c18e131fa1836e05974eae0d6e4cf29b", size = 13175054 }, ] [[package]] name = "onnxruntime-gpu" -version = "1.19.0" +version = "1.19.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "coloredlogs" }, @@ -1387,10 +1396,8 @@ dependencies = [ { name = "sympy" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/14/cf/fbe7d9d1dfb09876f8b1c79ab00fecc7c151be30660edea6dfe768752588/onnxruntime_gpu-1.19.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:c8bae9164d9586cbf7c7976915b515584d077470307a255b7ca03cf425ce38bf", size = 223132057 }, - { url = "https://files.pythonhosted.org/packages/ed/6c/32d9d64b2ab2d17871d67f07144990adf996400466fdbcb751a9217a927c/onnxruntime_gpu-1.19.0-cp311-cp311-win_amd64.whl", hash = "sha256:62418bf4bde804afd1cea1e391f1ee4ba5f50e09cd0397c852e150c013e27ae4", size = 223248909 }, - { url = "https://files.pythonhosted.org/packages/6d/b4/7ce4b35f062e76cd0cac0bf26b4f510eb7e49e5f9ffbe2ed6356bbc05fb3/onnxruntime_gpu-1.19.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:cbceb55c265266350fa731365ccd224dc29c352470671a24cbc153fe0c4be1f9", size = 223122847 }, - { url = "https://files.pythonhosted.org/packages/f0/3d/cadf1ba55ebeb700f1209d90a32a896d971b54d67208bc6148d697958049/onnxruntime_gpu-1.19.0-cp312-cp312-win_amd64.whl", hash = "sha256:35405747644bf8d9d9c84fb6ee3dd04cc594e9c3f5448735c68565fb3372b1cd", size = 223250583 }, + { url = "https://files.pythonhosted.org/packages/85/33/06e856502a1d482532cfa7d4c7ca775dfddcd851c7bd1833f5177e567055/onnxruntime_gpu-1.19.2-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:562fc7c755393eaad9751e56149339dd201ffbfdb3ef5f43ff21d0619ba9045f", size = 226175096 }, + { url = "https://files.pythonhosted.org/packages/68/55/49e5b4b4d6e9a8841dcdec2f102069716b626bf6ce9640b832a9497504eb/onnxruntime_gpu-1.19.2-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:554a02a3fac0119707eb87327908afd21c4e6f0fa5bf9a034398f098adc316c5", size = 226163139 }, ] [[package]] @@ -1685,11 +1692,11 @@ wheels = [ [[package]] name = "platformdirs" -version = "4.2.2" +version = "4.3.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/f5/52/0763d1d976d5c262df53ddda8d8d4719eedf9594d046f117c25a27261a19/platformdirs-4.2.2.tar.gz", hash = "sha256:38b7b51f512eed9e84a22788b4bce1de17c0adb134d6becb09836e37d8654cd3", size = 20916 } +sdist = { url = "https://files.pythonhosted.org/packages/75/a0/d7cab8409cdc7d39b037c85ac46d92434fb6595432e069251b38e5c8dd0e/platformdirs-4.3.2.tar.gz", hash = "sha256:9e5e27a08aa095dd127b9f2e764d74254f482fef22b0970773bfba79d091ab8c", size = 21276 } wheels = [ - { url = "https://files.pythonhosted.org/packages/68/13/2aa1f0e1364feb2c9ef45302f387ac0bd81484e9c9a4c5688a322fbdfd08/platformdirs-4.2.2-py3-none-any.whl", hash = "sha256:2d7a1657e36a80ea911db832a8a6ece5ee53d8de21edd5cc5879af6530b1bfee", size = 18146 }, + { url = "https://files.pythonhosted.org/packages/da/8b/d497999c4017b80678017ddce745cf675489c110681ad3c84a55eddfd3e7/platformdirs-4.3.2-py3-none-any.whl", hash = "sha256:eb1c8582560b34ed4ba105009a4badf7f6f85768b30126f351328507b2beb617", size = 18417 }, ] [[package]] @@ -4938,49 +4945,49 @@ wheels = [ [[package]] name = "ruff" -version = "0.6.3" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/5d/f9/0b32e5d1c6f957df49398cd882a011e9488fcbca0d6acfeeea50ccd37a4d/ruff-0.6.3.tar.gz", hash = "sha256:183b99e9edd1ef63be34a3b51fee0a9f4ab95add123dbf89a71f7b1f0c991983", size = 2463514 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/72/68/1da6a1e39a03a229ea57c511691d6225072759cc7764206c3f0989521194/ruff-0.6.3-py3-none-linux_armv6l.whl", hash = "sha256:97f58fda4e309382ad30ede7f30e2791d70dd29ea17f41970119f55bdb7a45c3", size = 9696928 }, - { url = "https://files.pythonhosted.org/packages/6e/59/3b8b1d3a4271c6eb6ceecd3cef19a6d881639a0f18ad651563d6f619aaae/ruff-0.6.3-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:3b061e49b5cf3a297b4d1c27ac5587954ccb4ff601160d3d6b2f70b1622194dc", size = 9448462 }, - { url = "https://files.pythonhosted.org/packages/35/4f/b942ecb8bbebe53aa9b33e9b96df88acd50b70adaaed3070f1d92131a1cb/ruff-0.6.3-py3-none-macosx_11_0_arm64.whl", hash = "sha256:34e2824a13bb8c668c71c1760a6ac7d795ccbd8d38ff4a0d8471fdb15de910b1", size = 9176190 }, - { url = "https://files.pythonhosted.org/packages/a0/20/b0bcb29d4ee437f3567b73b6905c034e2e94d29b9b826c66daecc1cf6388/ruff-0.6.3-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bddfbb8d63c460f4b4128b6a506e7052bad4d6f3ff607ebbb41b0aa19c2770d1", size = 10108892 }, - { url = "https://files.pythonhosted.org/packages/9c/e3/211bc759f424e8823a9937e0f678695ca02113c621dfde1fa756f9f26f6d/ruff-0.6.3-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:ced3eeb44df75353e08ab3b6a9e113b5f3f996bea48d4f7c027bc528ba87b672", size = 9476471 }, - { url = "https://files.pythonhosted.org/packages/b2/a3/2ec35a2d7a554364864206f0e46812b92a074ad8a014b923d821ead532aa/ruff-0.6.3-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:47021dff5445d549be954eb275156dfd7c37222acc1e8014311badcb9b4ec8c1", size = 10294802 }, - { url = "https://files.pythonhosted.org/packages/03/8b/56ef687b3489c88886dea48c78fb4969b6b65f18007d0ac450070edd1f58/ruff-0.6.3-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:7d7bd20dc07cebd68cc8bc7b3f5ada6d637f42d947c85264f94b0d1cd9d87384", size = 11022372 }, - { url = "https://files.pythonhosted.org/packages/a5/21/327d147feb442adb88975e81e2263102789eba9ad2afa102c661912a482f/ruff-0.6.3-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:500f166d03fc6d0e61c8e40a3ff853fa8a43d938f5d14c183c612df1b0d6c58a", size = 10596596 }, - { url = "https://files.pythonhosted.org/packages/6c/86/ff386de63729da3e08c8099c57f577a00ec9f3eea711b23ac07cf3588dc5/ruff-0.6.3-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:42844ff678f9b976366b262fa2d1d1a3fe76f6e145bd92c84e27d172e3c34500", size = 11572830 }, - { url = "https://files.pythonhosted.org/packages/38/5d/b33284c108e3f315ddd09b70296fd76bd28ecf8965a520bc93f3bbd8ac40/ruff-0.6.3-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:70452a10eb2d66549de8e75f89ae82462159855e983ddff91bc0bce6511d0470", size = 10262577 }, - { url = "https://files.pythonhosted.org/packages/29/99/9cdfad0d7f460e66567236eddc691473791afd9aff93a0dfcdef0462a6c7/ruff-0.6.3-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:65a533235ed55f767d1fc62193a21cbf9e3329cf26d427b800fdeacfb77d296f", size = 10098751 }, - { url = "https://files.pythonhosted.org/packages/a8/9f/f801a1619f5549e552f1f722f1db57eb39e7e1d83d482133142781d450de/ruff-0.6.3-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:d2e2c23cef30dc3cbe9cc5d04f2899e7f5e478c40d2e0a633513ad081f7361b5", size = 9563859 }, - { url = "https://files.pythonhosted.org/packages/0b/4d/fb2424faf04ffdb960ae2b3a1d991c5183dd981003de727d2d5cc38abc98/ruff-0.6.3-py3-none-musllinux_1_2_i686.whl", hash = "sha256:d8a136aa7d228975a6aee3dd8bea9b28e2b43e9444aa678fb62aeb1956ff2351", size = 9914291 }, - { url = "https://files.pythonhosted.org/packages/2e/dd/94fddf002a8f6152e8ebfbb51d3f93febc415c1fe694345623c31ce8b33b/ruff-0.6.3-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:f92fe93bc72e262b7b3f2bba9879897e2d58a989b4714ba6a5a7273e842ad2f8", size = 10331549 }, - { url = "https://files.pythonhosted.org/packages/b4/73/ca9c2f9237a430ca423b6dca83b77e9a428afeb7aec80596e86c369123fe/ruff-0.6.3-py3-none-win32.whl", hash = "sha256:7a62d3b5b0d7f9143d94893f8ba43aa5a5c51a0ffc4a401aa97a81ed76930521", size = 7962163 }, - { url = "https://files.pythonhosted.org/packages/55/ce/061c605b1dfb52748d59bc0c7a8507546c178801156415773d18febfd71d/ruff-0.6.3-py3-none-win_amd64.whl", hash = "sha256:746af39356fee2b89aada06c7376e1aa274a23493d7016059c3a72e3b296befb", size = 8800901 }, - { url = "https://files.pythonhosted.org/packages/63/28/ae4ffe7d3b6134ca6d31ebef07447ef70097c4a9e8fbbc519b374c5c1559/ruff-0.6.3-py3-none-win_arm64.whl", hash = "sha256:14a9528a8b70ccc7a847637c29e56fd1f9183a9db743bbc5b8e0c4ad60592a82", size = 8229171 }, +version = "0.6.4" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/a4/55/9f485266e6326cab707369601b13e3e72eb90ba3eee2d6779549a00a0d58/ruff-0.6.4.tar.gz", hash = "sha256:ac3b5bfbee99973f80aa1b7cbd1c9cbce200883bdd067300c22a6cc1c7fba212", size = 2469375 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/e3/78/307591f81d09c8721b5e64539f287c82c81a46f46d16278eb27941ac17f9/ruff-0.6.4-py3-none-linux_armv6l.whl", hash = "sha256:c4b153fc152af51855458e79e835fb6b933032921756cec9af7d0ba2aa01a258", size = 9692673 }, + { url = "https://files.pythonhosted.org/packages/69/63/ef398fcacdbd3995618ed30b5a6c809a1ebbf112ba604b3f5b8c3be464cf/ruff-0.6.4-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:bedff9e4f004dad5f7f76a9d39c4ca98af526c9b1695068198b3bda8c085ef60", size = 9481182 }, + { url = "https://files.pythonhosted.org/packages/a6/fd/8784e3bbd79bc17de0a62de05fe5165f494ff7d77cb06630d6428c2f10d2/ruff-0.6.4-py3-none-macosx_11_0_arm64.whl", hash = "sha256:d02a4127a86de23002e694d7ff19f905c51e338c72d8e09b56bfb60e1681724f", size = 9174356 }, + { url = "https://files.pythonhosted.org/packages/6d/bc/c69db2d68ac7bfbb222c81dc43a86e0402d0063e20b13e609f7d17d81d3f/ruff-0.6.4-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7862f42fc1a4aca1ea3ffe8a11f67819d183a5693b228f0bb3a531f5e40336fc", size = 10129365 }, + { url = "https://files.pythonhosted.org/packages/3b/10/8ed14ff60a4e5eb08cac0a04a9b4e8590c72d1ce4d29ef22cef97d19536d/ruff-0.6.4-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:eebe4ff1967c838a1a9618a5a59a3b0a00406f8d7eefee97c70411fefc353617", size = 9483351 }, + { url = "https://files.pythonhosted.org/packages/a9/69/13316b8d64ffd6a43627cf0753339a7f95df413450c301a60904581bee6e/ruff-0.6.4-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:932063a03bac394866683e15710c25b8690ccdca1cf192b9a98260332ca93408", size = 10301099 }, + { url = "https://files.pythonhosted.org/packages/42/00/9623494087272643e8f02187c266638306c6829189a5bf1446968bbe438b/ruff-0.6.4-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:50e30b437cebef547bd5c3edf9ce81343e5dd7c737cb36ccb4fe83573f3d392e", size = 11033216 }, + { url = "https://files.pythonhosted.org/packages/c5/31/e0c9d881db42ea1267e075c29aafe0db5a8a3024b131f952747f6234f858/ruff-0.6.4-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c44536df7b93a587de690e124b89bd47306fddd59398a0fb12afd6133c7b3818", size = 10618140 }, + { url = "https://files.pythonhosted.org/packages/5b/35/f1d8b746aedd4c8fde4f83397e940cc4c8fc619860ebbe3073340381a34d/ruff-0.6.4-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:0ea086601b22dc5e7693a78f3fcfc460cceabfdf3bdc36dc898792aba48fbad6", size = 11606672 }, + { url = "https://files.pythonhosted.org/packages/c5/70/899b03cbb3eb48ed0507d4b32b6f7aee562bc618ef9ffda855ec98c0461a/ruff-0.6.4-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0b52387d3289ccd227b62102c24714ed75fbba0b16ecc69a923a37e3b5e0aaaa", size = 10288013 }, + { url = "https://files.pythonhosted.org/packages/17/c6/906bf895640521ca5115ccdd857b2bac42bd61facde6620fdc2efc0a4806/ruff-0.6.4-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:0308610470fcc82969082fc83c76c0d362f562e2f0cdab0586516f03a4e06ec6", size = 10109473 }, + { url = "https://files.pythonhosted.org/packages/28/da/1284eb04172f8a5d42eb52fce9d643dd747ac59a4ed6c5d42729f72e934d/ruff-0.6.4-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:803b96dea21795a6c9d5bfa9e96127cc9c31a1987802ca68f35e5c95aed3fc0d", size = 9568817 }, + { url = "https://files.pythonhosted.org/packages/6c/e2/f8250b54edbb2e9222e22806e1bcc35a192ac18d1793ea556fa4977a843a/ruff-0.6.4-py3-none-musllinux_1_2_i686.whl", hash = "sha256:66dbfea86b663baab8fcae56c59f190caba9398df1488164e2df53e216248baa", size = 9910840 }, + { url = "https://files.pythonhosted.org/packages/9c/7c/dcf2c10562346ecdf6f0e5f6669b2ddc9a74a72956c3f419abd6820c2aff/ruff-0.6.4-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:34d5efad480193c046c86608dbba2bccdc1c5fd11950fb271f8086e0c763a5d1", size = 10354263 }, + { url = "https://files.pythonhosted.org/packages/f1/94/c39d7ac5729e94788110503d928c98c203488664b0fb92c2b801cb832bec/ruff-0.6.4-py3-none-win32.whl", hash = "sha256:f0f8968feea5ce3777c0d8365653d5e91c40c31a81d95824ba61d871a11b8523", size = 7958602 }, + { url = "https://files.pythonhosted.org/packages/6b/d2/2dee8c547bee3d4cfdd897f7b8e38510383acaff2c8130ea783b67631d72/ruff-0.6.4-py3-none-win_amd64.whl", hash = "sha256:549daccee5227282289390b0222d0fbee0275d1db6d514550d65420053021a58", size = 8795059 }, + { url = "https://files.pythonhosted.org/packages/07/1a/23280818aa4fa89bd0552aab10857154e1d3b90f27b5b745f09ec1ac6ad8/ruff-0.6.4-py3-none-win_arm64.whl", hash = "sha256:ac4b75e898ed189b3708c9ab3fc70b79a433219e1e87193b4f2b77251d058d14", size = 8239636 }, ] [[package]] name = "scons" -version = "4.8.0" +version = "4.8.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/ec/5c/cc835a17633de8b260ec1a6e527b5c57f4975cee5949f49e57ad4d5fab4b/scons-4.8.0.tar.gz", hash = "sha256:2c7377ff6a22ca136c795ae3dc3d0824696e5478d1e4940f2af75659b0d45454", size = 3243129 } +sdist = { url = "https://files.pythonhosted.org/packages/b9/76/a2c1293642f9a448f2d012cabf525be69ca5abf4af289bc0935ac1554ee8/scons-4.8.1.tar.gz", hash = "sha256:5b641357904d2f56f7bfdbb37e165ab996b6143c948b9df0efc7305f54949daa", size = 3244174 } wheels = [ - { url = "https://files.pythonhosted.org/packages/7b/01/4ea08ba8414db39e597939ff82d587082674f616f78e3dc505dae4b6a176/SCons-4.8.0-py3-none-any.whl", hash = "sha256:760fbfd05e459113e9a1362ab2b00e12ea4195607e820a127d30e6275c8436a1", size = 4122772 }, + { url = "https://files.pythonhosted.org/packages/b8/a7/823091100c88d7d992c8c608d82a88ed59e227d13f8ccb33ea7a96d43d51/SCons-4.8.1-py3-none-any.whl", hash = "sha256:a4c3b434330e2d7d975002fd6783284ba348bf394db94c8f83fdc5bf69cdb8d7", size = 4123564 }, ] [[package]] name = "sentry-sdk" -version = "2.13.0" +version = "2.14.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "certifi" }, { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/bb/41/97f673384dae5ed81cc2a568cc5c28e76deee85f8ba50def862e86150a5a/sentry_sdk-2.13.0.tar.gz", hash = "sha256:8d4a576f7a98eb2fdb40e13106e41f330e5c79d72a68be1316e7852cf4995260", size = 279937 } +sdist = { url = "https://files.pythonhosted.org/packages/3c/23/6527e56fb17817153c37d702d6b9ed0a2f75ed213fd98a176c1b8894ad20/sentry_sdk-2.14.0.tar.gz", hash = "sha256:1e0e2eaf6dad918c7d1e0edac868a7bf20017b177f242cefe2a6bcd47955961d", size = 282948 } wheels = [ - { url = "https://files.pythonhosted.org/packages/ad/7e/e9ca09f24a6c334286631a2d32c267cdc5edad5ac03fd9d20a01a82f1c35/sentry_sdk-2.13.0-py2.py3-none-any.whl", hash = "sha256:6beede8fc2ab4043da7f69d95534e320944690680dd9a963178a49de71d726c6", size = 309078 }, + { url = "https://files.pythonhosted.org/packages/40/de/956ce1d71459fa1af0486ca141fc605ac16f7c8855750668ff663e2b436a/sentry_sdk-2.14.0-py2.py3-none-any.whl", hash = "sha256:b8bc3dc51d06590df1291b7519b85c75e2ced4f28d9ea655b6d54033503b5bf4", size = 311425 }, ] [[package]] @@ -5017,11 +5024,11 @@ wheels = [ [[package]] name = "setuptools" -version = "74.1.1" +version = "74.1.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/27/cb/e754933c1ca726b0d99980612dc9da2886e76c83968c246cfb50f491a96b/setuptools-74.1.1.tar.gz", hash = "sha256:2353af060c06388be1cecbf5953dcdb1f38362f87a2356c480b6b4d5fcfc8847", size = 1357738 } +sdist = { url = "https://files.pythonhosted.org/packages/3e/2c/f0a538a2f91ce633a78daaeb34cbfb93a54bd2132a6de1f6cec028eee6ef/setuptools-74.1.2.tar.gz", hash = "sha256:95b40ed940a1c67eb70fc099094bd6e99c6ee7c23aa2306f4d2697ba7916f9c6", size = 1356467 } wheels = [ - { url = "https://files.pythonhosted.org/packages/48/f3/e30ee63caefa90716afdffd7d9ae959cd8d0dbd2d0a0eb9fe1d73ddf806b/setuptools-74.1.1-py3-none-any.whl", hash = "sha256:fc91b5f89e392ef5b77fe143b17e32f65d3024744fba66dc3afe07201684d766", size = 1263655 }, + { url = "https://files.pythonhosted.org/packages/cb/9c/9ad11ac06b97e55ada655f8a6bea9d1d3f06e120b178cd578d80e558191d/setuptools-74.1.2-py3-none-any.whl", hash = "sha256:5f4c08aa4d3ebcb57a50c33b1b07e94315d7fc7230f7115e47fc99776c8ce308", size = 1262071 }, ] [[package]] @@ -5165,14 +5172,14 @@ wheels = [ [[package]] name = "types-requests" -version = "2.32.0.20240712" +version = "2.32.0.20240907" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/5e/9e/7663eb27c33568b8fc20ccdaf2a1ce53a9530c42a7cceb9f552a6ff4a1d8/types-requests-2.32.0.20240712.tar.gz", hash = "sha256:90c079ff05e549f6bf50e02e910210b98b8ff1ebdd18e19c873cd237737c1358", size = 17896 } +sdist = { url = "https://files.pythonhosted.org/packages/9f/94/b6f90e5f09e1d621d5cd6d1057d5d28d4019d95f06eab205afa743ba1907/types-requests-2.32.0.20240907.tar.gz", hash = "sha256:ff33935f061b5e81ec87997e91050f7b4af4f82027a7a7a9d9aaea04a963fdf8", size = 18004 } wheels = [ - { url = "https://files.pythonhosted.org/packages/30/4d/cbed87a6912fbd9259ce23a5d4aa1de9816edf75eec6ed9a757c00906c8e/types_requests-2.32.0.20240712-py3-none-any.whl", hash = "sha256:f754283e152c752e46e70942fa2a146b5bc70393522257bb85bd1ef7e019dcc3", size = 15816 }, + { url = "https://files.pythonhosted.org/packages/5f/6e/425219be1dfc954c3e129b3ea70407abc78c1bd6414d0c7180df9940ca1f/types_requests-2.32.0.20240907-py3-none-any.whl", hash = "sha256:1d1e79faeaf9d42def77f3c304893dea17a97cae98168ac69f3cb465516ee8da", size = 15828 }, ] [[package]] @@ -5254,60 +5261,60 @@ wheels = [ [[package]] name = "yarl" -version = "1.9.7" +version = "1.11.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "idna" }, { name = "multidict" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ce/50/dcf6d0ea0da893b23f73ea5b21fa1f96fd45e9cb4404cc6b665368b4ab19/yarl-1.9.7.tar.gz", hash = "sha256:f28e602edeeec01fc96daf7728e8052bc2e12a672e2a138561a1ebaf30fd9df7", size = 153261 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/b4/26/99c3331253bf9d906d8292aba292d5801cef75537098a47027431746e43c/yarl-1.9.7-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:596069ddeaf72b5eb36cd714dcd2b5751d0090d05a8d65113b582ed9e1c801fb", size = 188476 }, - { url = "https://files.pythonhosted.org/packages/dc/f2/789992d30e2b6c9a6460e1da4d59ec1d5c91aa624b97788cce4ce83f9a54/yarl-1.9.7-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:cb870907e8b86b2f32541403da9455afc1e535ce483e579bea0e6e79a0cc751c", size = 112728 }, - { url = "https://files.pythonhosted.org/packages/f2/d2/95e5686881ac6e864d6edb18d92e5cc80a18d1b4ddcbc84f2f0d3b451da9/yarl-1.9.7-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ca5e86be84492fa403c4dcd4dcaf8e1b1c4ffc747b5176f7c3d09878c45719b0", size = 110853 }, - { url = "https://files.pythonhosted.org/packages/d7/cc/773c741e3fe0f9d38c87e1faacc4c5864dbe840fcc46e889482678b2891f/yarl-1.9.7-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a99cecfb51c84d00132db909e83ae388793ca86e48df7ae57f1be0beab0dcce5", size = 504153 }, - { url = "https://files.pythonhosted.org/packages/a5/a4/7fabbd75113591b6cbab9a71e3a2e3c0170fb7958afa3a399e8ed9968023/yarl-1.9.7-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:25508739e9b44d251172145f54c084b71747b09e4d237dc2abb045f46c36a66e", size = 525561 }, - { url = "https://files.pythonhosted.org/packages/52/01/2aabad17c2549e7068f8ec855e9de8d56d95a3a0823e3a398ea17582c6a0/yarl-1.9.7-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:60f3b5aec3146b6992640592856414870f5b20eb688c1f1d5f7ac010a7f86561", size = 520140 }, - { url = "https://files.pythonhosted.org/packages/46/c9/68d4f410c24a10fe0a9d0ab6fa975da433329cd611f12cf11f35e625c60d/yarl-1.9.7-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b1557456afce5db3d655b5f8a31cdcaae1f47e57958760525c44b76e812b4987", size = 508027 }, - { url = "https://files.pythonhosted.org/packages/f8/87/107ac4245975b7ef5d65b99375fa9e1e71bbe66974a4d2c4a6e9375c77d2/yarl-1.9.7-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:71bb1435a84688ed831220c5305d96161beb65cac4a966374475348aa3de4575", size = 489310 }, - { url = "https://files.pythonhosted.org/packages/c0/81/c6e44b3b41227b44337d9bbd0a585b79e3ce12e75500b6470b1b0ea2b5a2/yarl-1.9.7-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:f87d8645a7a806ec8f66aac5e3b1dcb5014849ff53ffe2a1f0b86ca813f534c7", size = 504009 }, - { url = "https://files.pythonhosted.org/packages/36/07/272c6c0d36c13a7fd62d2ae3850a70abe1de54afc503a2eb3d61fd083b3e/yarl-1.9.7-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:58e3f01673873b8573da3abe138debc63e4e68541b2104a55df4c10c129513a4", size = 502250 }, - { url = "https://files.pythonhosted.org/packages/d3/23/a26969785e3639b73c796061deb4e3d12df8813bf6f8a51483ab57039b6d/yarl-1.9.7-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:8af0bbd4d84f8abdd9b11be9488e32c76b1501889b73c9e2292a15fb925b378b", size = 533891 }, - { url = "https://files.pythonhosted.org/packages/d7/f0/a73047a29b643869ff3f8af51d400763546c1ac98fa7b8eab5c0d12905dd/yarl-1.9.7-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:7fc441408ed0d9c6d2d627a02e281c21f5de43eb5209c16636a17fc704f7d0f8", size = 537621 }, - { url = "https://files.pythonhosted.org/packages/be/ff/531ce46088bd8834bedf09cb2252b3af3d1f8a4b79f4c4e5d8c5480caa51/yarl-1.9.7-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:a9552367dc440870556da47bb289a806f08ad06fbc4054072d193d9e5dd619ba", size = 519177 }, - { url = "https://files.pythonhosted.org/packages/cd/71/28e058729ea289903a19169dda80944fb13704f06e03defb4be97e97f7b3/yarl-1.9.7-cp311-cp311-win32.whl", hash = "sha256:628619008680a11d07243391271b46f07f13b75deb9fe92ef342305058c70722", size = 98901 }, - { url = "https://files.pythonhosted.org/packages/7e/bd/1ddd698d8307f35c71a6ee5e3dffeeff0f9e95d926ed9444a0df23a39d5e/yarl-1.9.7-cp311-cp311-win_amd64.whl", hash = "sha256:bc23d870864971c8455cfba17498ccefa53a5719ea9f5fce5e7e9c1606b5755f", size = 108645 }, - { url = "https://files.pythonhosted.org/packages/dd/4e/b3d7679b158a981e6fa36c1d4388a7c3f4adb1b5c33ec22708ec550ddf91/yarl-1.9.7-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:0d8cf3d0b67996edc11957aece3fbce4c224d0451c7c3d6154ec3a35d0e55f6b", size = 188957 }, - { url = "https://files.pythonhosted.org/packages/0e/7b/2fe90636cf0f745210bcb79347369a3882e829e1070ab7d8b3949684d209/yarl-1.9.7-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:3a7748cd66fef49c877e59503e0cc76179caf1158d1080228e67e1db14554f08", size = 113292 }, - { url = "https://files.pythonhosted.org/packages/e2/ee/fae90e40bb4c2af6fd8a1a50d052140101a6634f1d2b32596a6cf53f4244/yarl-1.9.7-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:4a6fa3aeca8efabb0fbbb3b15e0956b0cb77f7d9db67c107503c30af07cd9e00", size = 110974 }, - { url = "https://files.pythonhosted.org/packages/28/60/3e985358440d6467c2ea81673000aef762c448462ab88e98e6676845f24f/yarl-1.9.7-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cf37dd0008e5ac5c3880198976063c491b6a15b288d150d12833248cf2003acb", size = 504133 }, - { url = "https://files.pythonhosted.org/packages/e3/ae/f0730026d7011f5403a8f49fec4e666358db43a0339dc8259b19a7c2e6f1/yarl-1.9.7-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:87aa5308482f248f8c3bd9311cd6c7dfd98ea1a8e57e35fb11e4adcac3066003", size = 521269 }, - { url = "https://files.pythonhosted.org/packages/24/5d/1b982866e45906f236cb9a93ec9a07a5b61854b34f0f6fa368056ee9cda3/yarl-1.9.7-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:867b13c1b361f9ba5d2f84dc5408082f5d744c83f66de45edc2b96793a9c5e48", size = 518617 }, - { url = "https://files.pythonhosted.org/packages/8c/ec/eaab7e272ddf1eab39b793e5cd3af304ac28d9342f6a3f2e356276bcc4fe/yarl-1.9.7-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:48ce93947554c2c85fe97fc4866646ec90840bc1162e4db349b37d692a811755", size = 510893 }, - { url = "https://files.pythonhosted.org/packages/98/c3/ed093752106c61e3b2a108f798649cb24119484802bb5ca521a36cf559bd/yarl-1.9.7-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fcd3d94b848cba132f39a5b40d80b0847d001a91a6f35a2204505cdd46afe1b2", size = 487621 }, - { url = "https://files.pythonhosted.org/packages/71/ff/bce0bda27957d4f8cdb8e56b807f185683e8b6a3717637fb8d1faa39269d/yarl-1.9.7-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:d06d6a8f98dd87646d98f0c468be14b201e47ec6092ad569adf835810ad0dffb", size = 506332 }, - { url = "https://files.pythonhosted.org/packages/ff/b5/95702c9719808331d2401e13660af86b323139f0293feb3a44698a194439/yarl-1.9.7-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:91567ff4fce73d2e7ac67ed5983ad26ba2343bc28cb22e1e1184a9677df98d7c", size = 505515 }, - { url = "https://files.pythonhosted.org/packages/17/7d/74a41e5d49329be134602a7e840adf3a499c7562afb982282d079067d5e4/yarl-1.9.7-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:1d5594512541e63188fea640b7f066c218d2176203d6e6f82abf702ae3dca3b2", size = 528662 }, - { url = "https://files.pythonhosted.org/packages/c1/f9/8a9083b6b73944c0bb5c99cfc0edf3bec14456b621f76b338fc945afc69f/yarl-1.9.7-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:9c2743e43183e4afbb07d5605693299b8756baff0b086c25236c761feb0e3c56", size = 539801 }, - { url = "https://files.pythonhosted.org/packages/44/74/877076885263c214abbed93462ef2e4e95579c047d188530c849ea207846/yarl-1.9.7-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:daa69a3a2204355af39f4cfe7f3870d87c53d77a597b5100b97e3faa9460428b", size = 524783 }, - { url = "https://files.pythonhosted.org/packages/95/58/e509c4ad1460bce6cf5cd485c5baa5c4c6a9a53999a82f90462f7908ee26/yarl-1.9.7-cp312-cp312-win32.whl", hash = "sha256:36b16884336c15adf79a4bf1d592e0c1ffdb036a760e36a1361565b66785ec6c", size = 98822 }, - { url = "https://files.pythonhosted.org/packages/b0/71/c8136c8c240ccf9d38715aaad31fb4f2c2f14e83c6db6b83d389274b0e9e/yarl-1.9.7-cp312-cp312-win_amd64.whl", hash = "sha256:2ead2f87a1174963cc406d18ac93d731fbb190633d3995fa052d10cefae69ed8", size = 108657 }, - { url = "https://files.pythonhosted.org/packages/2b/3c/c159233854485307e3355af11099d9c351c8475b10b2b3dc64bb8cdc608b/yarl-1.9.7-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:808eddabcb6f7b2cdb6929b3e021ac824a2c07dc7bc83f7618e18438b1b65781", size = 185789 }, - { url = "https://files.pythonhosted.org/packages/89/f3/24c3b30a9d95827280130ecb6ef33f0ab2bdc690391f19178493cf149196/yarl-1.9.7-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:395ab0d8ce6d104a988da429bcbfd445e03fb4c911148dfd523f69d13f772e47", size = 111661 }, - { url = "https://files.pythonhosted.org/packages/5c/a1/e610bfb3c74efdbeeff19ee370e6a76dd552c66680a9180777828dc2e7fa/yarl-1.9.7-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:49827dfccbd59c4499605c13805e947349295466e490860a855b7c7e82ec9c75", size = 109560 }, - { url = "https://files.pythonhosted.org/packages/d0/aa/dc3657bcf79cd98bdfa03c1b85c88de2a36037171894fa56890146e08615/yarl-1.9.7-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f6b8bbdd425d0978311520ea99fb6c0e9e04e64aee84fac05f3157ace9f81b05", size = 485985 }, - { url = "https://files.pythonhosted.org/packages/cf/2a/a69ad3ae4facef03df228790e6f4cfd4971cc267ee140fc8f6331c7e6194/yarl-1.9.7-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:71d33fd1c219b5b28ee98cd76da0c9398a4ed4792fd75c94135237db05ba5ca8", size = 501335 }, - { url = "https://files.pythonhosted.org/packages/f5/8f/b0a35ecd3f31fdffa704d11bf452a277ce4b29e7b878a94e636349945d87/yarl-1.9.7-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:62440431741d0b7d410e5cbad800885e3289048140a43390ecab4f0b96dde3bb", size = 502295 }, - { url = "https://files.pythonhosted.org/packages/39/68/bfc953df3a6ee6c0c9cd9f84d488681e377e49b8ced6d2d5b9289d639c89/yarl-1.9.7-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4db97210433366dfba55590e48285b89ad0146c52bf248dd0da492dd9f0f72cf", size = 493550 }, - { url = "https://files.pythonhosted.org/packages/40/5d/5092b93da54659f1e737f95d9a554f79aa68d1fda05e26c9f0e86184d894/yarl-1.9.7-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:653597b615809f2e5f4dba6cd805608b6fd3597128361a22cc612cf7c7a4d1bf", size = 470835 }, - { url = "https://files.pythonhosted.org/packages/66/e6/dedce99c469f8d1c66432006910adf943fdb7d0cfb77f026030e234f234f/yarl-1.9.7-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:df47612129e66f7ce7c9994d4cd4e6852f6e3bf97699375d86991481796eeec8", size = 490437 }, - { url = "https://files.pythonhosted.org/packages/50/52/b36cd8d9356734fda4a668ce358f56ecb16c7171b8a658fdfde31476de7c/yarl-1.9.7-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:5e338b6febbae6c9fe86924bac3ea9c1944e33255c249543cd82a4af6df6047b", size = 492765 }, - { url = "https://files.pythonhosted.org/packages/aa/9e/6ad4300fc040fc34e323f1254a05886a6441d05bd251a9a4063ed8d35c32/yarl-1.9.7-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:e649d37d04665dddb90994bbf0034331b6c14144cc6f3fbce400dc5f28dc05b7", size = 508901 }, - { url = "https://files.pythonhosted.org/packages/77/cc/8b27ea0a0faaba43b389c3a170c25a1fc063c34ae41c8660055e47d5dc89/yarl-1.9.7-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:0a1b8fd849567be56342e988e72c9d28bd3c77b9296c38b9b42d2fe4813c9d3f", size = 519676 }, - { url = "https://files.pythonhosted.org/packages/ca/e6/1b88c9b952c69b4bfb5d38260de4bf65eab4d0787bfcdc0a4d680e084ccb/yarl-1.9.7-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:f9d715b2175dff9a49c6dafdc2ab3f04850ba2f3d4a77f69a5a1786b057a9d45", size = 510005 }, - { url = "https://files.pythonhosted.org/packages/72/81/c456d5060bf4c2cb1213cd71e9211e0859ce6fff444bd13c61e2ae681b64/yarl-1.9.7-cp313-cp313-win32.whl", hash = "sha256:bc9233638b07c2e4a3a14bef70f53983389bffa9e8cb90a2da3f67ac9c5e1842", size = 483263 }, - { url = "https://files.pythonhosted.org/packages/5d/08/fe455390603d0377140c1ef02287dd32d3d4a0a6d596aa4a1fc881ac68d2/yarl-1.9.7-cp313-cp313-win_amd64.whl", hash = "sha256:62e110772330d7116f91e79cd83fef92545cb2f36414c95881477aa01971f75f", size = 491236 }, - { url = "https://files.pythonhosted.org/packages/48/04/8cc40203453e4bce05cd3e9a5bea930ac0086aa4848a9c41aa1da13ae1a0/yarl-1.9.7-py3-none-any.whl", hash = "sha256:49935cc51d272264358962d050d726c3e5603a616f53e52ea88e9df1728aa2ee", size = 35402 }, +sdist = { url = "https://files.pythonhosted.org/packages/d5/f0/56955b0dde04e8e811ad71a9308dd11cda14a079bf0fb2cdfabfb95f5d9c/yarl-1.11.0.tar.gz", hash = "sha256:f86f4f4a57a29ef08fa70c4667d04c5e3ba513500da95586208b285437cb9592", size = 160812 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/11/49/0895d3532224e99713f483d72f50a23fba35960fc2b579ac011e4f1c1279/yarl-1.11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:39e3087e1ef70862de81e22af9eb299faee580f41673ef92829949022791b521", size = 188003 }, + { url = "https://files.pythonhosted.org/packages/d6/7b/392f261aefe24ece4e80efc5612b7a28a6399a111900ae976c5ec6181153/yarl-1.11.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:7fd535cc41b81a566ad347081b671ab5c7e5f5b6a15526d85b4e748baf065cf0", size = 113889 }, + { url = "https://files.pythonhosted.org/packages/02/2e/46adc855d159b8898e7c975c467c29a551aa11634d8abe3d56efabd7590e/yarl-1.11.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f7cc02d8e9a612174869f4b983f159e87659096f7e2dc1fe9effd9902e408739", size = 112142 }, + { url = "https://files.pythonhosted.org/packages/12/fc/faa24a0b05f030d8c99d9c72029dde4d1ba2474c2f6105a75c92640b13d2/yarl-1.11.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:30f391ccf4b1b1e0ba4880075ba337d41a619a5350f67053927f67ebe764bf44", size = 484576 }, + { url = "https://files.pythonhosted.org/packages/11/64/fa9c04e685aeb0582e64e541b7b3684190f13ccbdfbee5e89fc597ced727/yarl-1.11.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4c19a0d95943bb2c914b4e71043803be34bc75c08c4a6ca232bdc649a1e9ef1b", size = 504473 }, + { url = "https://files.pythonhosted.org/packages/22/32/d9c8970b09139e701737062fe93927800f2b7204771b8087aa4ecdfaec5a/yarl-1.11.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ead4d89eade0e09b8ef97877664abb0e2e8704787db5564f83658fdee5c36497", size = 498891 }, + { url = "https://files.pythonhosted.org/packages/9c/b7/35577b3ab5dd0cabb5f793a5dd03186b2f10916833d894a1d611ecbe11a8/yarl-1.11.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:195f7791bc23d5f2480efe53f935daf8a61661000dfbfbdd70dbd06397594fff", size = 487450 }, + { url = "https://files.pythonhosted.org/packages/9d/8e/0ca5bfdaacb736f0fb5abd4ef0679b3685ae4a4f1868acef86e5fd4b598e/yarl-1.11.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:01a7905e662665ca8e058635377522bc3c98bdb873be761ff42c86eb72b03914", size = 470089 }, + { url = "https://files.pythonhosted.org/packages/20/5b/468c7f578c004b20b3860cb1270b007268e81eaec9be86aac31bd6d0c1d1/yarl-1.11.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:53c80b1927b75aed208d7fd965a3a705dc8c1db4d50b9112418fa0f7784363e6", size = 484143 }, + { url = "https://files.pythonhosted.org/packages/dc/64/082fd4f2e0b9d38437e8a7443924e4c6e6cbeb63da284034f8b7709061f3/yarl-1.11.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:11af21bbf807688d49b7d4915bb28cbc2e3aa028a2ee194738477eabcc413c65", size = 482014 }, + { url = "https://files.pythonhosted.org/packages/90/4a/0a9b2a817dd8fbd8212d9a5edd96f683eb4f3a5242618a2162bd424339dd/yarl-1.11.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:732d56da00ea7a5da4f0d15adbbd22dcb37da7825510aafde40112e53f6baa52", size = 512557 }, + { url = "https://files.pythonhosted.org/packages/27/12/68fefc9963099946919ca5347619958400902b83460c14068b2222fea07e/yarl-1.11.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:7bd54d79025b59d1dc5fb26a09734d6a9cc651a04bc381966ed264b28331a168", size = 514815 }, + { url = "https://files.pythonhosted.org/packages/af/97/71c0a9f3f028fdc5981c7c01c37d806611518a26deff1cda0107bdc98002/yarl-1.11.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:aacd62ff67efd54cb18cea2aa7ae4fb83cfbca19a07055d4777266b70561defe", size = 496917 }, + { url = "https://files.pythonhosted.org/packages/67/2e/df56566dca0d81cd23d4a168323b9145b4a1b3132d0a67f693de231d6213/yarl-1.11.0-cp311-cp311-win32.whl", hash = "sha256:68e14ae71e5b51c8282ae5db53ccb3baffc40e1551370a8a2361f1c1d8a0bf8c", size = 100817 }, + { url = "https://files.pythonhosted.org/packages/08/c2/d951e737c4ce9f31d5e55b5309db432bd35a33fb16bbccfbf3f82a0b0544/yarl-1.11.0-cp311-cp311-win_amd64.whl", hash = "sha256:3ade2265716667b6bd4123d6f684b5f7cf4a8d83dcf1d5581ac44643466bb00a", size = 110060 }, + { url = "https://files.pythonhosted.org/packages/2c/ef/afb63646e311b4b13a6751fcbb7628b8e935cba7a844d69e39f6d9ce5a7e/yarl-1.11.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:6e73dab98e3c3b5441720153e72a5f28e717aac2d22f1ec4b08ef33417d9987e", size = 188650 }, + { url = "https://files.pythonhosted.org/packages/32/31/fdac2a17133ee5e12ffc5c9266768fa05aa962e739ad35f39e9565a978f5/yarl-1.11.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:4a0d090d296ced05edfe29c6ff34869412fa6a97d0928c12b00939c4842884cd", size = 114472 }, + { url = "https://files.pythonhosted.org/packages/f8/f4/5c1e69c7bfc088a4389fc408fd09539e143edf10333b65c01f032c450131/yarl-1.11.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d29e446cfb0a82d3df7745968b9fa286665a9be8b4d68de46bcc32d917cb218e", size = 112332 }, + { url = "https://files.pythonhosted.org/packages/35/7f/2303b752846f4fb8ec53775545122aee5b854734d9c6d70fff4677ee05fe/yarl-1.11.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4c8dc0efcf8266ecfe057b95e01f43eb62516196a4bbf3918fd1dcb8d0dc0dff", size = 482463 }, + { url = "https://files.pythonhosted.org/packages/c3/71/c40f103724a7e3c4728a0f2952e95b31a4c7b9f101766f4c1e1fd022eb49/yarl-1.11.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:202f5ec49ff163dcc767426deb55020a28078e61d6bbe1f80331d92bca53b236", size = 498245 }, + { url = "https://files.pythonhosted.org/packages/f5/84/63d03c97b620f7a2b7e9c0cc28867db803d18843a0c3ff08ba9c570d904c/yarl-1.11.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8055b0d78ce1cafa657c4b455e22661e8d3b2834de66a0753c3567da47fcc4aa", size = 495761 }, + { url = "https://files.pythonhosted.org/packages/09/fa/9bf50e7c6dd7b1402ac8dc2ee5517f89b26b4df500914ef7600d09da1c74/yarl-1.11.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:60ed3c7f64e820959d7f682ec2f559b4f4df723dc09df619d269853a4214a4b4", size = 488688 }, + { url = "https://files.pythonhosted.org/packages/51/13/9bbd70849d0b1cd3ed5226b3844b8f185dc834a07081c874edfa4844a9fe/yarl-1.11.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2371510367d39d74997acfdcd1dead17938c79c99365482821627f7838a8eba0", size = 467864 }, + { url = "https://files.pythonhosted.org/packages/84/e3/d68f77ea24171e7eb09c1473aea38216fb52712c679691b4b5a6c68e0417/yarl-1.11.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:e24bb6a8be89ccc3ce8c47e8940fdfcb7429e9efbf65ce6fa3e7d122fcf0bcf0", size = 484168 }, + { url = "https://files.pythonhosted.org/packages/61/aa/a132bf6771efd523636998e1cc29d1e235aac1f0d94ec0dc57651973df34/yarl-1.11.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:18ec42da256cfcb9b4cd5d253e04c291f69911a5228d1438a7d431c15ba0ae40", size = 484541 }, + { url = "https://files.pythonhosted.org/packages/ff/60/7b7a3ab71f3df8d82888aac9f9b22097a72de79237ed3f06b86cb005b8b6/yarl-1.11.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:418eeb8f228ea36c368bf6782ebd6016ecebfb1a8b90145ef6726ffcbba65ef8", size = 505193 }, + { url = "https://files.pythonhosted.org/packages/0e/f7/b2714828dc249d915fe0dd9665fee73aac8e546b195308e0d531fe7d0a7b/yarl-1.11.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:07e8cfb1dd7669a129f8fd5df1da65efa73aea77582bde2a3a837412e2863543", size = 515538 }, + { url = "https://files.pythonhosted.org/packages/96/ea/6c7d34a0545ef449288c37607b5483f1a16f49f8dc723aed4013f01ea30f/yarl-1.11.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:3c458483711d393dad51340505c3fab3194748fd06bab311d2f8b5b7a7349e9a", size = 500875 }, + { url = "https://files.pythonhosted.org/packages/2d/8a/46785cee3bc1937c590c7176f140402b8eb8095c4b0bfb1fd46de47d70c7/yarl-1.11.0-cp312-cp312-win32.whl", hash = "sha256:5b008c3127382503e7a1e12b4c3a3236e3dd833a4c62a066f4a0fbd650c655d2", size = 100726 }, + { url = "https://files.pythonhosted.org/packages/b8/e6/f32b225643ee97b78809b7d55880fa69c834be47d3b19211dbd4dde223b6/yarl-1.11.0-cp312-cp312-win_amd64.whl", hash = "sha256:bc94be7472b9f88d7441340534a3ecae05c86ccfec7ba75ce5b6e4778b2bfc6e", size = 110098 }, + { url = "https://files.pythonhosted.org/packages/09/9c/b7d0f71112d2a8de7ea37a4e411364adfcbf679e7e8bd68a0cbf626e1021/yarl-1.11.0-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:a45e51ba3777031e0b20c1e7ab59114ed4e1884b3c1db48962c1d8d08aefb418", size = 184656 }, + { url = "https://files.pythonhosted.org/packages/8d/7f/a9add68784a938e578bd691203329cea2967fcf00c412a6ec00f3d9393aa/yarl-1.11.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:765128029218eade3a01187cdd7f375977cc827505ed31828196c8ae9b622928", size = 112659 }, + { url = "https://files.pythonhosted.org/packages/d2/ce/13b5bdd1187e1deae9efec2d64cecacb5287657fb570fc47da11d316f1a8/yarl-1.11.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:2516e238daf0339c8ac4dfab9d7cda9afad652ff073517f200d653d5d8371f7e", size = 110556 }, + { url = "https://files.pythonhosted.org/packages/73/cb/b27b1be50db78559ad9e1a871fec121a9008d95577480fd7ba491ea6a0ac/yarl-1.11.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d10be62bee117f05b1ad75a6c2538ca9e5367342dc8a4f3c206c87dadbc1189c", size = 469941 }, + { url = "https://files.pythonhosted.org/packages/85/9b/e969d4fa91b18f81076169efae00b54ad2cb642d24f66b980eded9f7913d/yarl-1.11.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:50ceaeda771ee3e382291168c90c7ede62b63ecf3e181024bcfeb35c0ea6c84f", size = 484373 }, + { url = "https://files.pythonhosted.org/packages/1d/88/8500d9dda26f8df114dd78a2230cdd510178c1bf54ac294c9209d666440f/yarl-1.11.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3a601c99fc20fd0eea84e7bc0dc9e7f196f55a0ded67242d724988c754295538", size = 485179 }, + { url = "https://files.pythonhosted.org/packages/b3/e5/b0c46b9e55959d6d0918dcf32eb7c0c4e4cd750990830740a91e86a65897/yarl-1.11.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:42ff79371614764fc0a4ab8eaba9adb493bf9ad856e2a4664f6c754fc907a903", size = 477399 }, + { url = "https://files.pythonhosted.org/packages/74/46/fad292dacca81b54cd9e032ea8cd2effab995c5294c0b9f2d5aadc139d43/yarl-1.11.0-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:93fca4c9f88c17ead902b3f3285b2d039fc8f26d117e1441973ba64315109b54", size = 454973 }, + { url = "https://files.pythonhosted.org/packages/50/17/a0b79bf596175691a7b8cf3918e430d386b206d0dec875d9af03103fd82a/yarl-1.11.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:e7dddf5f41395c84fc59e0ed5493b24bfeb39fb04823e880b52c8c55085d4695", size = 473497 }, + { url = "https://files.pythonhosted.org/packages/2d/55/ad4dbf1861d4677b931d9c433940441a3b152d78ee3c2fc256d01a1734b0/yarl-1.11.0-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:ea501ea07e14ba6364ff2621bfc8b2381e5b1e10353927fa9a607057fd2b98e5", size = 476002 }, + { url = "https://files.pythonhosted.org/packages/a1/8d/506fd44cfdcd70a88bf4639eede14f38814a0e87fb3525b1adc407c4dacc/yarl-1.11.0-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:a4f7e470f2c9c8b8774a5bda72adfb8e9dc4ec32311fe9bdaa4921e36cf6659b", size = 490486 }, + { url = "https://files.pythonhosted.org/packages/e0/8c/618f4f425746d4c1551d488e66c6a9b51e517088871464a6a567506794df/yarl-1.11.0-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:361fdb3993431157302b7104d525092b5df4d7d346df5a5ffeee2d1ca8e0d15b", size = 500692 }, + { url = "https://files.pythonhosted.org/packages/dd/98/370d73e15e56bd825192c90d4c269c6d4b6030eecfe9a11d35aefa3eda28/yarl-1.11.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:e300eaf5e0329ad31b3d53e2f3d26b4b6dff1217207c6ab1d4212967b54b2185", size = 491380 }, + { url = "https://files.pythonhosted.org/packages/81/c0/2c0578852fdc767bced8be44e554cb573e1dc54c6cee5720cfbd40ce4134/yarl-1.11.0-cp313-cp313-win32.whl", hash = "sha256:f1e2d4ce72e06e38a16da3e9c24a0520dbc19018a69ef6ed57b6b38527cb275c", size = 484844 }, + { url = "https://files.pythonhosted.org/packages/7e/a8/9ac6108837df19e46583cde169e20d69c68fbbe26dab8cedae53e41e2c69/yarl-1.11.0-cp313-cp313-win_amd64.whl", hash = "sha256:fa9de2f87be58f714a230bd1f3ef3aad1ed65c9931146e3fc55f85fcbe6bacc3", size = 492185 }, + { url = "https://files.pythonhosted.org/packages/f1/37/f3a2f78f3174d0150257dff57b4b81c562ef1648d0eba4acbe333b534317/yarl-1.11.0-py3-none-any.whl", hash = "sha256:03717a6627e55934b2a1d9caf24f299b461a2e8d048a90920f42ad5c20ae1b82", size = 38246 }, ] [[package]] From 838746c831752e49d76d3dd146e4d7891888e66e Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Mon, 9 Sep 2024 10:35:22 -0700 Subject: [PATCH 032/214] ui preview: keyboard (#33520) keyboard --- .github/workflows/ui_preview.yaml | 2 +- selfdrive/ui/tests/test_ui/run.py | 11 ++++++++++- 2 files changed, 11 insertions(+), 2 deletions(-) diff --git a/.github/workflows/ui_preview.yaml b/.github/workflows/ui_preview.yaml index 98eadc36c2..877951f623 100644 --- a/.github/workflows/ui_preview.yaml +++ b/.github/workflows/ui_preview.yaml @@ -84,7 +84,7 @@ jobs: run: >- sudo apt-get install -y imagemagick - scenes="homescreen settings_device offroad_alert update_available prime onroad onroad_sidebar onroad_wide onroad_wide_sidebar onroad_alert_small onroad_alert_mid onroad_alert_full driver_camera body" + scenes="homescreen settings_device offroad_alert update_available prime onroad onroad_sidebar onroad_wide onroad_wide_sidebar onroad_alert_small onroad_alert_mid onroad_alert_full driver_camera body keyboard" A=($scenes) DIFF="" diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 578d9d7e10..f5560efa72 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -77,6 +77,14 @@ def setup_body(click, pm: PubMaster): DATA['carState'].carState.fuelGauge = 50.0 setup_onroad(click, pm) +def setup_keyboard(click, pm: PubMaster): + setup_settings_device(click, pm) + click(250, 575) + click(2020, 218) + click(1830, 80) + click(2035, 808) + click(90, 480) + def setup_driver_camera(click, pm: PubMaster): setup_settings_device(click, pm) click(1950, 435) @@ -143,7 +151,8 @@ CASES = { "driver_camera": setup_driver_camera, "body": setup_body, "offroad_alert": setup_offroad_alert, - "update_available": setup_update_available + "update_available": setup_update_available, + "keyboard": setup_keyboard } TEST_DIR = pathlib.Path(__file__).parent From d73a787e8ab01b1e3c452785b7920816d5b8065f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 9 Sep 2024 12:03:34 -0700 Subject: [PATCH 033/214] release files: add tools/joystick (#33525) --- release/release_files.py | 1 + 1 file changed, 1 insertion(+) diff --git a/release/release_files.py b/release/release_files.py index 5e9371c6fc..788d45b88e 100755 --- a/release/release_files.py +++ b/release/release_files.py @@ -52,6 +52,7 @@ blacklist = [ whitelist = [ "tools/lib/", "tools/bodyteleop/", + "tools/joystick/", "tinygrad_repo/openpilot/compile2.py", "tinygrad_repo/extra/onnx.py", From d6644c457a41ca51db0a4915475233028b84541a Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 9 Sep 2024 12:04:04 -0700 Subject: [PATCH 034/214] test manager again in CI (#33523) * test manager again * fix * whitelist joystickd --- .github/workflows/selfdrive_tests.yaml | 2 +- system/manager/test/test_manager.py | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 09ac537845..b47d06f06d 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -60,7 +60,7 @@ jobs: run: | cd $STRIPPED_DIR ${{ env.RUN }} "release/check-dirty.sh && \ - MAX_EXAMPLES=5 $PYTEST -m 'not slow' selfdrive/car" + MAX_EXAMPLES=5 $PYTEST -m 'not slow' selfdrive/car system/manager" - name: Static analysis timeout-minutes: 1 run: | diff --git a/system/manager/test/test_manager.py b/system/manager/test/test_manager.py index e5960d1113..497f4f8240 100644 --- a/system/manager/test/test_manager.py +++ b/system/manager/test/test_manager.py @@ -18,7 +18,6 @@ MAX_STARTUP_TIME = 3 BLACKLIST_PROCS = ['manage_athenad', 'pandad', 'pigeond'] -@pytest.mark.tici class TestManager: def setup_method(self): HARDWARE.set_power_save(False) From 592778ab29b9125703032e011d52455e44d840f4 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 9 Sep 2024 14:11:07 -0700 Subject: [PATCH 035/214] inputs is real dependency (#33524) inputs is real dep --- pyproject.toml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/pyproject.toml b/pyproject.toml index b42eb67141..2f4ce136b6 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -55,6 +55,9 @@ dependencies = [ "casadi >=3.6.6", # 3.12 fixed in 3.6.6 "future-fstrings", + # joystickd + "inputs", + # these should be removed "psutil", "pycryptodome", # used in updated/casync, panda, body, and a test @@ -96,7 +99,6 @@ dev = [ "azure-storage-blob", "dictdiffer", "flaky", - "inputs", "lru-dict", "matplotlib", "metadrive-simulator @ https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal/metadrive_simulator-0.4.2.3-py3-none-any.whl ; (platform_machine != 'aarch64')", From 343de54030eea5eb898e7e0dd2be844d8d5b8be0 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 10 Sep 2024 05:34:11 +0800 Subject: [PATCH 036/214] ui: consolidate prime state management into `PrimeState` Class (#33473) new class PrimeState --- selfdrive/ui/SConscript | 4 +-- selfdrive/ui/qt/home.cc | 5 ++- selfdrive/ui/qt/network/networking.cc | 19 +++++----- selfdrive/ui/qt/network/networking.h | 3 ++ selfdrive/ui/qt/network/wifi_manager.cc | 7 ---- selfdrive/ui/qt/network/wifi_manager.h | 1 + selfdrive/ui/qt/offroad/settings.cc | 14 ++++---- selfdrive/ui/qt/offroad/settings.h | 1 - selfdrive/ui/qt/prime_state.cc | 48 +++++++++++++++++++++++++ selfdrive/ui/qt/prime_state.h | 33 +++++++++++++++++ selfdrive/ui/qt/widgets/prime.cc | 37 +++++-------------- selfdrive/ui/qt/widgets/prime.h | 3 -- selfdrive/ui/ui.cc | 28 ++------------- selfdrive/ui/ui.h | 20 ++--------- 14 files changed, 118 insertions(+), 105 deletions(-) create mode 100644 selfdrive/ui/qt/prime_state.cc create mode 100644 selfdrive/ui/qt/prime_state.h diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 319ca4547c..1ea4d44dc4 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -16,7 +16,7 @@ if arch == "Darwin": qt_env['CXXFLAGS'] += ["-Wno-deprecated-declarations"] qt_util = qt_env.Library("qt_util", ["#selfdrive/ui/qt/api.cc", "#selfdrive/ui/qt/util.cc"], LIBS=base_libs) -widgets_src = ["ui.cc", "qt/widgets/input.cc", "qt/widgets/wifi.cc", +widgets_src = ["qt/widgets/input.cc", "qt/widgets/wifi.cc", "qt/prime_state.cc", "qt/widgets/ssh_keys.cc", "qt/widgets/toggle.cc", "qt/widgets/controls.cc", "qt/widgets/offroad_alerts.cc", "qt/widgets/prime.cc", "qt/widgets/keyboard.cc", "qt/widgets/scrollview.cc", "qt/widgets/cameraview.cc", "#third_party/qrcode/QrCode.cc", @@ -26,7 +26,7 @@ widgets = qt_env.Library("qt_widgets", widgets_src, LIBS=base_libs) Export('widgets') qt_libs = [widgets, qt_util] + base_libs -qt_src = ["main.cc", "qt/sidebar.cc", "qt/body.cc", +qt_src = ["main.cc", "ui.cc", "qt/sidebar.cc", "qt/body.cc", "qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc", "qt/offroad/software_settings.cc", "qt/offroad/onboarding.cc", "qt/offroad/driverview.cc", "qt/offroad/experimental_mode.cc", diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index af946c7987..648f3685c7 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -150,9 +150,8 @@ OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) { left_widget->addWidget(new PrimeAdWidget); left_widget->setStyleSheet("border-radius: 10px;"); - left_widget->setCurrentIndex(uiState()->hasPrime() ? 0 : 1); - connect(uiState(), &UIState::primeChanged, [=](bool prime) { - left_widget->setCurrentIndex(prime ? 0 : 1); + connect(uiState()->prime_state, &PrimeState::changed, [left_widget]() { + left_widget->setCurrentIndex(uiState()->prime_state->isSubscribed() ? 0 : 1); }); home_layout->addWidget(left_widget, 1); diff --git a/selfdrive/ui/qt/network/networking.cc b/selfdrive/ui/qt/network/networking.cc index 250fa0fbf8..22d9c01efe 100644 --- a/selfdrive/ui/qt/network/networking.cc +++ b/selfdrive/ui/qt/network/networking.cc @@ -6,7 +6,6 @@ #include #include -#include "selfdrive/ui/ui.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/widgets/controls.h" @@ -73,6 +72,11 @@ Networking::Networking(QWidget* parent, bool show_advanced) : QFrame(parent) { main_layout->setCurrentWidget(wifiScreen); } +void Networking::setPrimeType(PrimeState::Type type) { + an->setGsmVisible(type == PrimeState::PRIME_TYPE_NONE || type == PrimeState::PRIME_TYPE_LITE); + wifi->ipv4_forward = (type == PrimeState::PRIME_TYPE_NONE || type == PrimeState::PRIME_TYPE_LITE); +} + void Networking::refresh() { wifiWidget->refresh(); an->refresh(); @@ -204,17 +208,16 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid // Set initial config wifi->updateGsmSettings(roamingEnabled, QString::fromStdString(params.get("GsmApn")), metered); - connect(uiState(), &UIState::primeTypeChanged, this, [=](PrimeType prime_type) { - bool gsmVisible = prime_type == PrimeType::PRIME_TYPE_NONE || prime_type == PrimeType::PRIME_TYPE_LITE; - roamingToggle->setVisible(gsmVisible); - editApnButton->setVisible(gsmVisible); - meteredToggle->setVisible(gsmVisible); - }); - main_layout->addWidget(new ScrollView(list, this)); main_layout->addStretch(1); } +void AdvancedNetworking::setGsmVisible(bool visible) { + roamingToggle->setVisible(visible); + editApnButton->setVisible(visible); + meteredToggle->setVisible(visible); +} + void AdvancedNetworking::refresh() { ipLabel->setText(wifi->ipv4_address); tetheringToggle->setEnabled(true); diff --git a/selfdrive/ui/qt/network/networking.h b/selfdrive/ui/qt/network/networking.h index 9b6af005ea..4fd604039b 100644 --- a/selfdrive/ui/qt/network/networking.h +++ b/selfdrive/ui/qt/network/networking.h @@ -3,6 +3,7 @@ #include #include "selfdrive/ui/qt/network/wifi_manager.h" +#include "selfdrive/ui/qt/prime_state.h" #include "selfdrive/ui/qt/widgets/input.h" #include "selfdrive/ui/qt/widgets/ssh_keys.h" #include "selfdrive/ui/qt/widgets/toggle.h" @@ -56,6 +57,7 @@ class AdvancedNetworking : public QWidget { Q_OBJECT public: explicit AdvancedNetworking(QWidget* parent = 0, WifiManager* wifi = 0); + void setGsmVisible(bool visible); private: LabelControl* ipLabel; @@ -81,6 +83,7 @@ class Networking : public QFrame { public: explicit Networking(QWidget* parent = 0, bool show_advanced = true); + void setPrimeType(PrimeState::Type type); WifiManager* wifi = nullptr; private: diff --git a/selfdrive/ui/qt/network/wifi_manager.cc b/selfdrive/ui/qt/network/wifi_manager.cc index b0c9535273..ddf13d26b7 100644 --- a/selfdrive/ui/qt/network/wifi_manager.cc +++ b/selfdrive/ui/qt/network/wifi_manager.cc @@ -2,10 +2,6 @@ #include -#include "selfdrive/ui/ui.h" -#include "selfdrive/ui/qt/widgets/prime.h" - -#include "common/params.h" #include "common/swaglog.h" #include "selfdrive/ui/qt/util.h" @@ -445,9 +441,6 @@ void WifiManager::addTetheringConnection() { } void WifiManager::tetheringActivated(QDBusPendingCallWatcher *call) { - int prime_type = uiState()->primeType(); - int ipv4_forward = (prime_type == PrimeType::PRIME_TYPE_NONE || prime_type == PrimeType::PRIME_TYPE_LITE); - if (!ipv4_forward) { QTimer::singleShot(5000, this, [=] { qWarning() << "net.ipv4.ip_forward = 0"; diff --git a/selfdrive/ui/qt/network/wifi_manager.h b/selfdrive/ui/qt/network/wifi_manager.h index 2f6a1829d7..5d18b87d86 100644 --- a/selfdrive/ui/qt/network/wifi_manager.h +++ b/selfdrive/ui/qt/network/wifi_manager.h @@ -42,6 +42,7 @@ public: QMap seenNetworks; QMap knownConnections; QString ipv4_address; + bool ipv4_forward = false; explicit WifiManager(QObject* parent); void start(); diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index fc92a471d6..7024a2a802 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -247,8 +247,8 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { }); addItem(translateBtn); - QObject::connect(uiState(), &UIState::primeTypeChanged, [this] (PrimeType type) { - pair_device->setVisible(type == PrimeType::PRIME_TYPE_UNPAIRED); + QObject::connect(uiState()->prime_state, &PrimeState::changed, [this] (PrimeState::Type type) { + pair_device->setVisible(type == PrimeState::PRIME_TYPE_UNPAIRED); }); QObject::connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { for (auto btn : findChildren()) { @@ -335,11 +335,6 @@ void DevicePanel::poweroff() { } } -void DevicePanel::showEvent(QShowEvent *event) { - pair_device->setVisible(uiState()->primeType() == PrimeType::PRIME_TYPE_UNPAIRED); - ListWidget::showEvent(event); -} - void SettingsWindow::showEvent(QShowEvent *event) { setCurrentPanel(0); } @@ -386,9 +381,12 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { TogglesPanel *toggles = new TogglesPanel(this); QObject::connect(this, &SettingsWindow::expandToggleDescription, toggles, &TogglesPanel::expandToggleDescription); + auto networking = new Networking(this); + QObject::connect(uiState()->prime_state, &PrimeState::changed, networking, &Networking::setPrimeType); + QList> panels = { {tr("Device"), device}, - {tr("Network"), new Networking(this)}, + {tr("Network"), networking}, {tr("Toggles"), toggles}, {tr("Software"), new SoftwarePanel(this)}, }; diff --git a/selfdrive/ui/qt/offroad/settings.h b/selfdrive/ui/qt/offroad/settings.h index 35a044bdd2..68ba0d1898 100644 --- a/selfdrive/ui/qt/offroad/settings.h +++ b/selfdrive/ui/qt/offroad/settings.h @@ -42,7 +42,6 @@ class DevicePanel : public ListWidget { Q_OBJECT public: explicit DevicePanel(SettingsWindow *parent); - void showEvent(QShowEvent *event) override; signals: void reviewTrainingGuide(); diff --git a/selfdrive/ui/qt/prime_state.cc b/selfdrive/ui/qt/prime_state.cc new file mode 100644 index 0000000000..f12daf1e3c --- /dev/null +++ b/selfdrive/ui/qt/prime_state.cc @@ -0,0 +1,48 @@ +#include "selfdrive/ui/qt/prime_state.h" + +#include + +#include "selfdrive/ui/qt/api.h" +#include "selfdrive/ui/qt/request_repeater.h" +#include "selfdrive/ui/qt/util.h" + +PrimeState::PrimeState(QObject* parent) : QObject(parent) { + const char *env_prime_type = std::getenv("PRIME_TYPE"); + auto type = env_prime_type ? env_prime_type : Params().get("PrimeType"); + + if (!type.empty()) { + prime_type = static_cast(std::atoi(type.c_str())); + } + + if (auto dongleId = getDongleId()) { + QString url = CommaApi::BASE_URL + "/v1.1/devices/" + *dongleId + "/"; + RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_Device", 5); + QObject::connect(repeater, &RequestRepeater::requestDone, this, &PrimeState::handleReply); + } + + // Emit the initial state change + QTimer::singleShot(1, [this]() { emit changed(prime_type); }); +} + +void PrimeState::handleReply(const QString& response, bool success) { + if (!success) return; + + QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8()); + if (doc.isNull()) { + qDebug() << "JSON Parse failed on getting pairing and PrimeState status"; + return; + } + + QJsonObject json = doc.object(); + bool is_paired = json["is_paired"].toBool(); + auto type = static_cast(json["prime_type"].toInt()); + setType(is_paired ? type : PrimeState::PRIME_TYPE_UNPAIRED); +} + +void PrimeState::setType(PrimeState::Type type) { + if (type != prime_type) { + prime_type = type; + Params().put("PrimeType", std::to_string(prime_type)); + emit changed(prime_type); + } +} diff --git a/selfdrive/ui/qt/prime_state.h b/selfdrive/ui/qt/prime_state.h new file mode 100644 index 0000000000..0e2e3bb043 --- /dev/null +++ b/selfdrive/ui/qt/prime_state.h @@ -0,0 +1,33 @@ +#pragma once + +#include + +class PrimeState : public QObject { + Q_OBJECT + +public: + + enum Type { + PRIME_TYPE_UNKNOWN = -2, + PRIME_TYPE_UNPAIRED = -1, + PRIME_TYPE_NONE = 0, + PRIME_TYPE_MAGENTA = 1, + PRIME_TYPE_LITE = 2, + PRIME_TYPE_BLUE = 3, + PRIME_TYPE_MAGENTA_NEW = 4, + PRIME_TYPE_PURPLE = 5, + }; + + PrimeState(QObject *parent); + void setType(PrimeState::Type type); + inline PrimeState::Type currentType() const { return prime_type; } + inline bool isSubscribed() const { return prime_type > PrimeState::PRIME_TYPE_NONE; } + +signals: + void changed(PrimeState::Type prime_type); + +private: + void handleReply(const QString &response, bool success); + + PrimeState::Type prime_type = PrimeState::PRIME_TYPE_UNKNOWN; +}; diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index f86258ea4f..9bc96fcdad 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -246,33 +246,12 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { sp_retain.setRetainSizeWhenHidden(true); setSizePolicy(sp_retain); - // set up API requests - if (auto dongleId = getDongleId()) { - QString url = CommaApi::BASE_URL + "/v1.1/devices/" + *dongleId + "/"; - RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_Device", 5); - - QObject::connect(repeater, &RequestRepeater::requestDone, this, &SetupWidget::replyFinished); - } -} - -void SetupWidget::replyFinished(const QString &response, bool success) { - if (!success) return; - - QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8()); - if (doc.isNull()) { - qDebug() << "JSON Parse failed on getting pairing and prime status"; - return; - } - - QJsonObject json = doc.object(); - bool is_paired = json["is_paired"].toBool(); - PrimeType prime_type = static_cast(json["prime_type"].toInt()); - uiState()->setPrimeType(is_paired ? prime_type : PrimeType::PRIME_TYPE_UNPAIRED); - - if (!is_paired) { - mainLayout->setCurrentIndex(0); - } else { - popup->reject(); - mainLayout->setCurrentIndex(1); - } + QObject::connect(uiState()->prime_state, &PrimeState::changed, [this](PrimeState::Type type) { + if (type == PrimeState::PRIME_TYPE_UNPAIRED) { + mainLayout->setCurrentIndex(0); // Display "Pair your device" widget + } else { + popup->reject(); + mainLayout->setCurrentIndex(1); // Display Wi-Fi prompt widget + } + }); } diff --git a/selfdrive/ui/qt/widgets/prime.h b/selfdrive/ui/qt/widgets/prime.h index eac71bcddb..d1ba334e81 100644 --- a/selfdrive/ui/qt/widgets/prime.h +++ b/selfdrive/ui/qt/widgets/prime.h @@ -66,7 +66,4 @@ signals: private: PairingPopup *popup; QStackedWidget *mainLayout; - -private slots: - void replyFinished(const QString &response, bool success); }; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 1a3198c936..cbe05edfc9 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -210,13 +210,8 @@ UIState::UIState(QObject *parent) : QObject(parent) { "pandaStates", "carParams", "driverMonitoringState", "carState", "driverStateV2", "wideRoadCameraState", "managerState", "selfdriveState", }); - - Params params; - language = QString::fromStdString(params.get("LanguageSetting")); - auto prime_value = params.get("PrimeType"); - if (!prime_value.empty()) { - prime_type = static_cast(std::atoi(prime_value.c_str())); - } + prime_state = new PrimeState(this); + language = QString::fromStdString(Params().get("LanguageSetting")); // update timer timer = new QTimer(this); @@ -229,31 +224,12 @@ void UIState::update() { update_state(this); updateStatus(); - if (std::getenv("PRIME_TYPE")) { - setPrimeType((PrimeType)atoi(std::getenv("PRIME_TYPE"))); - } - if (sm->frame % UI_FREQ == 0) { watchdog_kick(nanos_since_boot()); } emit uiUpdate(*this); } -void UIState::setPrimeType(PrimeType type) { - if (type != prime_type) { - bool prev_prime = hasPrime(); - - prime_type = type; - Params().put("PrimeType", std::to_string(prime_type)); - emit primeTypeChanged(prime_type); - - bool prime = hasPrime(); - if (prev_prime != prime) { - emit primeChanged(prime); - } - } -} - Device::Device(QObject *parent) : brightness_filter(BACKLIGHT_OFFROAD, BACKLIGHT_TS, BACKLIGHT_DT), QObject(parent) { setAwake(true); resetInteractiveTimeout(); diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 73b8c5ddeb..8cf2f52d58 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -15,6 +15,7 @@ #include "common/params.h" #include "common/timing.h" #include "system/hardware/hw.h" +#include "selfdrive/ui/qt/prime_state.h" const int UI_BORDER_SIZE = 30; const int UI_HEADER_HEIGHT = 420; @@ -40,17 +41,6 @@ typedef enum UIStatus { STATUS_ENGAGED, } UIStatus; -enum PrimeType { - PRIME_TYPE_UNKNOWN = -2, - PRIME_TYPE_UNPAIRED = -1, - PRIME_TYPE_NONE = 0, - PRIME_TYPE_MAGENTA = 1, - PRIME_TYPE_LITE = 2, - PRIME_TYPE_BLUE = 3, - PRIME_TYPE_MAGENTA_NEW = 4, - PRIME_TYPE_PURPLE = 5, -}; - const QColor bg_colors [] = { [STATUS_DISENGAGED] = QColor(0x17, 0x33, 0x49, 0xc8), [STATUS_OVERRIDE] = QColor(0x91, 0x9b, 0x95, 0xf1), @@ -94,10 +84,6 @@ public: return scene.started && (*sm)["selfdriveState"].getSelfdriveState().getEnabled(); } - void setPrimeType(PrimeType type); - inline PrimeType primeType() const { return prime_type; } - inline bool hasPrime() const { return prime_type > PrimeType::PRIME_TYPE_NONE; } - int fb_w = 0, fb_h = 0; std::unique_ptr sm; @@ -108,12 +94,11 @@ public: QString language; QTransform car_space_transform; + PrimeState *prime_state; signals: void uiUpdate(const UIState &s); void offroadTransition(bool offroad); - void primeChanged(bool prime); - void primeTypeChanged(PrimeType prime_type); private slots: void update(); @@ -121,7 +106,6 @@ private slots: private: QTimer *timer; bool started_prev = false; - PrimeType prime_type = PrimeType::PRIME_TYPE_UNKNOWN; }; UIState *uiState(); From f1331ae9bca8411b6609dcc50ca0fdf6d99bea0e Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Mon, 9 Sep 2024 14:35:40 -0700 Subject: [PATCH 037/214] ci: make ui preview more deterministic (#33526) set ping time --- selfdrive/ui/tests/test_ui/run.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index f5560efa72..4ae9e4e611 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -169,6 +169,7 @@ class TestUI: def setup(self): self.pm = PubMaster(list(DATA.keys())) DATA['deviceState'].deviceState.networkType = log.DeviceState.NetworkType.wifi + DATA['deviceState'].deviceState.lastAthenaPingTime = 0 for _ in range(10): self.pm.send('deviceState', DATA['deviceState']) DATA['deviceState'].clear_write_flag() From c8eb5916a7c2585f4e2b452988608d90045ce3b8 Mon Sep 17 00:00:00 2001 From: ugtthis <142481257+ugtthis@users.noreply.github.com> Date: Mon, 9 Sep 2024 20:20:42 -0700 Subject: [PATCH 038/214] Keyboard UX: Easier to type URLs (#33517) Easier access to / and - --- selfdrive/ui/qt/widgets/keyboard.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/qt/widgets/keyboard.cc b/selfdrive/ui/qt/widgets/keyboard.cc index 370e9a53cc..629ea94f20 100644 --- a/selfdrive/ui/qt/widgets/keyboard.cc +++ b/selfdrive/ui/qt/widgets/keyboard.cc @@ -11,7 +11,7 @@ const QString BACKSPACE_KEY = "⌫"; const QString ENTER_KEY = "→"; -const QMap KEY_STRETCH = {{" ", 5}, {ENTER_KEY, 2}}; +const QMap KEY_STRETCH = {{" ", 3}, {ENTER_KEY, 2}}; const QStringList CONTROL_BUTTONS = {"↑", "↓", "ABC", "#+=", "123", BACKSPACE_KEY, ENTER_KEY}; @@ -107,7 +107,7 @@ Keyboard::Keyboard(QWidget *parent) : QFrame(parent) { {"q", "w", "e", "r", "t", "y", "u", "i", "o", "p"}, {"a", "s", "d", "f", "g", "h", "j", "k", "l"}, {"↑", "z", "x", "c", "v", "b", "n", "m", BACKSPACE_KEY}, - {"123", " ", ".", ENTER_KEY}, + {"123", "/", "-", " ", ".", ENTER_KEY}, }; main_layout->addWidget(new KeyboardLayout(this, lowercase)); From 650ee44e898920e092a1c08ec0ad4d1b9b6f8e6d Mon Sep 17 00:00:00 2001 From: Shengming Yuan <11619780+ssysm@users.noreply.github.com> Date: Tue, 10 Sep 2024 00:53:15 -0400 Subject: [PATCH 039/214] ui: update CHS/CHT translation (#33529) --- selfdrive/ui/translations/main_zh-CHS.ts | 8 ++++---- selfdrive/ui/translations/main_zh-CHT.ts | 6 +++--- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 5fe66104d1..d900202515 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -419,11 +419,11 @@ Waiting to start - + 等待开始 System Unresponsive - + 系统无响应 @@ -476,7 +476,7 @@ 24/7 LTE connectivity - 全天候 LTE 連線 + 全天候 LTE 连接 1 year of drive storage @@ -484,7 +484,7 @@ Remote snapshots - + 远程快照 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index b7d2eb2bde..91b1cf3866 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -419,11 +419,11 @@ Waiting to start - + 等待開始 System Unresponsive - + 系統無回應 @@ -484,7 +484,7 @@ Remote snapshots - + 遠端快照 From 47409ab4d40c18d4a1e3030585646fbab7729e41 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 11 Sep 2024 02:53:10 +0800 Subject: [PATCH 040/214] ui: refactor CameraView to serve as a generic vision stream display class (#33457) refactor transform --- selfdrive/ui/qt/offroad/driverview.cc | 14 ++- selfdrive/ui/qt/offroad/driverview.h | 1 + selfdrive/ui/qt/onroad/annotated_camera.cc | 63 ++++++++---- selfdrive/ui/qt/onroad/annotated_camera.h | 2 +- selfdrive/ui/qt/onroad/onroad_home.cc | 2 +- selfdrive/ui/qt/widgets/cameraview.cc | 106 +++------------------ selfdrive/ui/qt/widgets/cameraview.h | 16 +--- selfdrive/ui/ui.cc | 52 +++------- selfdrive/ui/ui.h | 43 ++++----- selfdrive/ui/watch3.cc | 6 +- tools/cabana/videowidget.cc | 6 +- tools/cabana/videowidget.h | 2 +- 12 files changed, 119 insertions(+), 194 deletions(-) diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc index df9bb24651..00f7415cba 100644 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ b/selfdrive/ui/qt/offroad/driverview.cc @@ -7,7 +7,7 @@ const int FACE_IMG_SIZE = 130; -DriverViewWindow::DriverViewWindow(QWidget* parent) : CameraWidget("camerad", VISION_STREAM_DRIVER, true, parent) { +DriverViewWindow::DriverViewWindow(QWidget* parent) : CameraWidget("camerad", VISION_STREAM_DRIVER, parent) { face_img = loadPixmap("../assets/img_driver_face_static.png", {FACE_IMG_SIZE, FACE_IMG_SIZE}); QObject::connect(this, &CameraWidget::clicked, this, &DriverViewWindow::done); QObject::connect(device(), &Device::interactiveTimeout, this, [this]() { @@ -75,3 +75,15 @@ void DriverViewWindow::paintGL() { p.setOpacity(face_detected ? 1.0 : 0.2); p.drawPixmap(img_x, img_y, face_img); } + +mat4 DriverViewWindow::calcFrameMatrix() { + const float driver_view_ratio = 2.0; + const float yscale = stream_height * driver_view_ratio / stream_width; + const float xscale = yscale * glHeight() / glWidth() * stream_width / stream_height; + return mat4{{ + xscale, 0.0, 0.0, 0.0, + 0.0, yscale, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, + }}; +} diff --git a/selfdrive/ui/qt/offroad/driverview.h b/selfdrive/ui/qt/offroad/driverview.h index 155e4ede32..00acb68d29 100644 --- a/selfdrive/ui/qt/offroad/driverview.h +++ b/selfdrive/ui/qt/offroad/driverview.h @@ -12,6 +12,7 @@ signals: void done(); protected: + mat4 calcFrameMatrix() override; void showEvent(QShowEvent *event) override; void hideEvent(QHideEvent *event) override; void paintGL() override; diff --git a/selfdrive/ui/qt/onroad/annotated_camera.cc b/selfdrive/ui/qt/onroad/annotated_camera.cc index b538f19dde..c528501cbe 100644 --- a/selfdrive/ui/qt/onroad/annotated_camera.cc +++ b/selfdrive/ui/qt/onroad/annotated_camera.cc @@ -10,7 +10,8 @@ #include "selfdrive/ui/qt/util.h" // Window that shows camera view and variety of info drawn on top -AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget* parent) : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraWidget("camerad", type, true, parent) { +AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget *parent) + : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraWidget("camerad", type, parent) { pm = std::make_unique(std::vector{"uiDebug"}); main_layout = new QVBoxLayout(this); @@ -125,22 +126,54 @@ void AnnotatedCameraWidget::initializeGL() { setBackgroundColor(bg_colors[STATUS_DISENGAGED]); } -void AnnotatedCameraWidget::updateFrameMat() { - CameraWidget::updateFrameMat(); - UIState *s = uiState(); +mat4 AnnotatedCameraWidget::calcFrameMatrix() { + // Project point at "infinity" to compute x and y offsets + // to ensure this ends up in the middle of the screen + // for narrow come and a little lower for wide cam. + // TODO: use proper perspective transform? + + // Select intrinsic matrix and calibration based on camera type + auto *s = uiState(); + bool wide_cam = active_stream_type == VISION_STREAM_WIDE_ROAD; + const auto &intrinsic_matrix = wide_cam ? ECAM_INTRINSIC_MATRIX : FCAM_INTRINSIC_MATRIX; + const auto &calibration = wide_cam ? s->scene.view_from_wide_calib : s->scene.view_from_calib; + + // Compute the calibration transformation matrix + const auto calib_transform = intrinsic_matrix * calibration; + + float zoom = wide_cam ? 2.0 : 1.1; + Eigen::Vector3f inf(1000., 0., 0.); + auto Kep = calib_transform * inf; + int w = width(), h = height(); + float center_x = intrinsic_matrix(0, 2); + float center_y = intrinsic_matrix(1, 2); - s->fb_w = w; - s->fb_h = h; + float max_x_offset = center_x * zoom - w / 2 - 5; + float max_y_offset = center_y * zoom - h / 2 - 5; + float x_offset = std::clamp((Kep.x() / Kep.z() - center_x) * zoom, -max_x_offset, max_x_offset); + float y_offset = std::clamp((Kep.y() / Kep.z() - center_y) * zoom, -max_y_offset, max_y_offset); // Apply transformation such that video pixel coordinates match video // 1) Put (0, 0) in the middle of the video // 2) Apply same scaling as video // 3) Put (0, 0) in top left corner of video - s->car_space_transform.reset(); - s->car_space_transform.translate(w / 2 - x_offset, h / 2 - y_offset) - .scale(zoom, zoom) - .translate(-intrinsic_matrix.v[2], -intrinsic_matrix.v[5]); + Eigen::Matrix3f video_transform =(Eigen::Matrix3f() << + zoom, 0.0f, (w / 2 - x_offset) - (center_x * zoom), + 0.0f, zoom, (h / 2 - y_offset) - (center_y * zoom), + 0.0f, 0.0f, 1.0f).finished(); + + s->car_space_transform = video_transform * calib_transform; + s->clip_region = rect().adjusted(-500, -500, 500, 500); + + float zx = zoom * 2 * center_x / w; + float zy = zoom * 2 * center_y / h; + return mat4{{ + zx, 0.0, 0.0, -x_offset / w * 2, + 0.0, zy, 0.0, y_offset / h * 2, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, + }}; } void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) { @@ -271,18 +304,8 @@ void AnnotatedCameraWidget::paintGL() { wide_cam_requested = false; } wide_cam_requested = wide_cam_requested && sm["selfdriveState"].getSelfdriveState().getExperimentalMode(); - // for replay of old routes, never go to widecam - wide_cam_requested = wide_cam_requested && s->scene.calibration_wide_valid; } CameraWidget::setStreamType(wide_cam_requested ? VISION_STREAM_WIDE_ROAD : VISION_STREAM_ROAD); - - s->scene.wide_cam = CameraWidget::getStreamType() == VISION_STREAM_WIDE_ROAD; - if (s->scene.calibration_valid) { - auto calib = s->scene.wide_cam ? s->scene.view_from_wide_calib : s->scene.view_from_calib; - CameraWidget::updateCalibration(calib); - } else { - CameraWidget::updateCalibration(DEFAULT_CALIBRATION); - } CameraWidget::setFrameId(model.getFrameId()); CameraWidget::paintGL(); } diff --git a/selfdrive/ui/qt/onroad/annotated_camera.h b/selfdrive/ui/qt/onroad/annotated_camera.h index 4a4196b22c..3820de5d86 100644 --- a/selfdrive/ui/qt/onroad/annotated_camera.h +++ b/selfdrive/ui/qt/onroad/annotated_camera.h @@ -36,7 +36,7 @@ protected: void paintGL() override; void initializeGL() override; void showEvent(QShowEvent *event) override; - void updateFrameMat() override; + mat4 calcFrameMatrix() override; void drawLaneLines(QPainter &painter, const UIState *s); void drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd); void drawHud(QPainter &p); diff --git a/selfdrive/ui/qt/onroad/onroad_home.cc b/selfdrive/ui/qt/onroad/onroad_home.cc index 823e14bf3c..080f9bd50f 100644 --- a/selfdrive/ui/qt/onroad/onroad_home.cc +++ b/selfdrive/ui/qt/onroad/onroad_home.cc @@ -21,7 +21,7 @@ OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) { split->addWidget(nvg); if (getenv("DUAL_CAMERA_VIEW")) { - CameraWidget *arCam = new CameraWidget("camerad", VISION_STREAM_ROAD, true, this); + CameraWidget *arCam = new CameraWidget("camerad", VISION_STREAM_ROAD, this); split->insertWidget(0, arCam); } diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index b43f8c4322..674e5e999c 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -7,13 +7,7 @@ #endif #include -#include -#include -#include - #include -#include -#include namespace { @@ -66,40 +60,10 @@ const char frame_fragment_shader[] = "}\n"; #endif -mat4 get_driver_view_transform(int screen_width, int screen_height, int stream_width, int stream_height) { - const float driver_view_ratio = 2.0; - const float yscale = stream_height * driver_view_ratio / stream_width; - const float xscale = yscale*screen_height/screen_width*stream_width/stream_height; - mat4 transform = (mat4){{ - xscale, 0.0, 0.0, 0.0, - 0.0, yscale, 0.0, 0.0, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, - }}; - return transform; -} - -mat4 get_fit_view_transform(float widget_aspect_ratio, float frame_aspect_ratio) { - float zx = 1, zy = 1; - if (frame_aspect_ratio > widget_aspect_ratio) { - zy = widget_aspect_ratio / frame_aspect_ratio; - } else { - zx = frame_aspect_ratio / widget_aspect_ratio; - } - - const mat4 frame_transform = {{ - zx, 0.0, 0.0, 0.0, - 0.0, zy, 0.0, 0.0, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, - }}; - return frame_transform; -} - } // namespace -CameraWidget::CameraWidget(std::string stream_name, VisionStreamType type, bool zoom, QWidget* parent) : - stream_name(stream_name), active_stream_type(type), requested_stream_type(type), zoomed_view(zoom), QOpenGLWidget(parent) { +CameraWidget::CameraWidget(std::string stream_name, VisionStreamType type, QWidget* parent) : + stream_name(stream_name), active_stream_type(type), requested_stream_type(type), QOpenGLWidget(parent) { setAttribute(Qt::WA_OpaquePaintEvent); qRegisterMetaType>("availableStreams"); QObject::connect(this, &CameraWidget::vipcThreadConnected, this, &CameraWidget::vipcConnected, Qt::BlockingQueuedConnection); @@ -214,59 +178,19 @@ void CameraWidget::availableStreamsUpdated(std::set streams) { available_streams = streams; } -void CameraWidget::updateFrameMat() { - int w = glWidth(), h = glHeight(); +mat4 CameraWidget::calcFrameMatrix() { + // Scale the frame to fit the widget while maintaining the aspect ratio. + float widget_aspect_ratio = (float)width() / height(); + float frame_aspect_ratio = (float)stream_width / stream_height; + float zx = std::min(frame_aspect_ratio / widget_aspect_ratio, 1.0f); + float zy = std::min(widget_aspect_ratio / frame_aspect_ratio, 1.0f); - if (zoomed_view) { - if (active_stream_type == VISION_STREAM_DRIVER) { - if (stream_width > 0 && stream_height > 0) { - frame_mat = get_driver_view_transform(w, h, stream_width, stream_height); - } - } else { - // Project point at "infinity" to compute x and y offsets - // to ensure this ends up in the middle of the screen - // for narrow come and a little lower for wide cam. - // TODO: use proper perspective transform? - if (active_stream_type == VISION_STREAM_WIDE_ROAD) { - intrinsic_matrix = ECAM_INTRINSIC_MATRIX; - zoom = 2.0; - } else { - intrinsic_matrix = FCAM_INTRINSIC_MATRIX; - zoom = 1.1; - } - const vec3 inf = {{1000., 0., 0.}}; - const vec3 Ep = matvecmul3(calibration, inf); - const vec3 Kep = matvecmul3(intrinsic_matrix, Ep); - - float x_offset_ = (Kep.v[0] / Kep.v[2] - intrinsic_matrix.v[2]) * zoom; - float y_offset_ = (Kep.v[1] / Kep.v[2] - intrinsic_matrix.v[5]) * zoom; - - float max_x_offset = intrinsic_matrix.v[2] * zoom - w / 2 - 5; - float max_y_offset = intrinsic_matrix.v[5] * zoom - h / 2 - 5; - - x_offset = std::clamp(x_offset_, -max_x_offset, max_x_offset); - y_offset = std::clamp(y_offset_, -max_y_offset, max_y_offset); - - float zx = zoom * 2 * intrinsic_matrix.v[2] / w; - float zy = zoom * 2 * intrinsic_matrix.v[5] / h; - const mat4 frame_transform = {{ - zx, 0.0, 0.0, -x_offset / w * 2, - 0.0, zy, 0.0, y_offset / h * 2, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, - }}; - frame_mat = frame_transform; - } - } else if (stream_width > 0 && stream_height > 0) { - // fit frame to widget size - float widget_aspect_ratio = (float)w / h; - float frame_aspect_ratio = (float)stream_width / stream_height; - frame_mat = get_fit_view_transform(widget_aspect_ratio, frame_aspect_ratio); - } -} - -void CameraWidget::updateCalibration(const mat3 &calib) { - calibration = calib; + return mat4{{ + zx, 0.0, 0.0, 0.0, + 0.0, zy, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, + }}; } void CameraWidget::paintGL() { @@ -293,7 +217,7 @@ void CameraWidget::paintGL() { VisionBuf *frame = frames[frame_idx].second; assert(frame != nullptr); - updateFrameMat(); + auto frame_mat = calcFrameMatrix(); glViewport(0, 0, glWidth(), glHeight()); glBindVertexArray(frame_vao); diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 85ec498735..73f4858c4b 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -34,7 +34,7 @@ class CameraWidget : public QOpenGLWidget, protected QOpenGLFunctions { public: using QOpenGLWidget::QOpenGLWidget; - explicit CameraWidget(std::string stream_name, VisionStreamType stream_type, bool zoom, QWidget* parent = nullptr); + explicit CameraWidget(std::string stream_name, VisionStreamType stream_type, QWidget* parent = nullptr); ~CameraWidget(); void setBackgroundColor(const QColor &color) { bg = color; } void setFrameId(int frame_id) { draw_frame_id = frame_id; } @@ -51,21 +51,17 @@ signals: protected: void paintGL() override; void initializeGL() override; - void resizeGL(int w, int h) override { updateFrameMat(); } void showEvent(QShowEvent *event) override; void mouseReleaseEvent(QMouseEvent *event) override { emit clicked(); } - virtual void updateFrameMat(); - void updateCalibration(const mat3 &calib); + virtual mat4 calcFrameMatrix(); void vipcThread(); void clearFrames(); int glWidth(); int glHeight(); - bool zoomed_view; GLuint frame_vao, frame_vbo, frame_ibo; GLuint textures[2]; - mat4 frame_mat = {}; std::unique_ptr program; QColor bg = QColor("#000000"); @@ -81,14 +77,6 @@ protected: std::atomic requested_stream_type; std::set available_streams; QThread *vipc_thread = nullptr; - - // Calibration - float x_offset = 0; - float y_offset = 0; - float zoom = 1.0; - mat3 calibration = DEFAULT_CALIBRATION; - mat3 intrinsic_matrix = FCAM_INTRINSIC_MATRIX; - std::recursive_mutex frame_lock; std::deque> frames; uint32_t draw_frame_id = 0; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index cbe05edfc9..852980d54e 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -1,13 +1,11 @@ #include "selfdrive/ui/ui.h" #include -#include #include #include #include "common/transformations/orientation.hpp" -#include "common/params.h" #include "common/swaglog.h" #include "common/util.h" #include "common/watchdog.h" @@ -19,20 +17,10 @@ // Projects a point in car to space to the corresponding point in full frame // image space. static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y, float in_z, QPointF *out) { - const float margin = 500.0f; - const QRectF clip_region{-margin, -margin, s->fb_w + 2 * margin, s->fb_h + 2 * margin}; - - const vec3 pt = (vec3){{in_x, in_y, in_z}}; - const vec3 Ep = matvecmul3(s->scene.wide_cam ? s->scene.view_from_wide_calib : s->scene.view_from_calib, pt); - const vec3 KEp = matvecmul3(s->scene.wide_cam ? ECAM_INTRINSIC_MATRIX : FCAM_INTRINSIC_MATRIX, Ep); - - // Project. - QPointF point = s->car_space_transform.map(QPointF{KEp.v[0] / KEp.v[2], KEp.v[1] / KEp.v[2]}); - if (clip_region.contains(point)) { - *out = point; - return true; - } - return false; + Eigen::Vector3f input(in_x, in_y, in_z); + auto transformed = s->car_space_transform * input; + *out = QPointF(transformed.x() / transformed.z(), transformed.y() / transformed.z()); + return s->clip_region.contains(*out); } int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height) { @@ -119,29 +107,19 @@ static void update_state(UIState *s) { UIScene &scene = s->scene; if (sm.updated("liveCalibration")) { + auto list2rot = [](const capnp::List::Reader &rpy_list) ->Eigen::Matrix3f { + return euler2rot({rpy_list[0], rpy_list[1], rpy_list[2]}).cast(); + }; + auto live_calib = sm["liveCalibration"].getLiveCalibration(); - auto rpy_list = live_calib.getRpyCalib(); - auto wfde_list = live_calib.getWideFromDeviceEuler(); - Eigen::Vector3d rpy; - Eigen::Vector3d wfde; - if (rpy_list.size() == 3) rpy << rpy_list[0], rpy_list[1], rpy_list[2]; - if (wfde_list.size() == 3) wfde << wfde_list[0], wfde_list[1], wfde_list[2]; - Eigen::Matrix3d device_from_calib = euler2rot(rpy); - Eigen::Matrix3d wide_from_device = euler2rot(wfde); - Eigen::Matrix3d view_from_device; - view_from_device << 0, 1, 0, - 0, 0, 1, - 1, 0, 0; - Eigen::Matrix3d view_from_calib = view_from_device * device_from_calib; - Eigen::Matrix3d view_from_wide_calib = view_from_device * wide_from_device * device_from_calib; - for (int i = 0; i < 3; i++) { - for (int j = 0; j < 3; j++) { - scene.view_from_calib.v[i*3 + j] = view_from_calib(i, j); - scene.view_from_wide_calib.v[i*3 + j] = view_from_wide_calib(i, j); - } + if (live_calib.getCalStatus() == cereal::LiveCalibrationData::Status::CALIBRATED) { + auto device_from_calib = list2rot(live_calib.getRpyCalib()); + auto wide_from_device = list2rot(live_calib.getWideFromDeviceEuler()); + s->scene.view_from_calib = VIEW_FROM_DEVICE * device_from_calib; + s->scene.view_from_wide_calib = VIEW_FROM_DEVICE * wide_from_device * device_from_calib; + } else { + s->scene.view_from_calib = s->scene.view_from_wide_calib = VIEW_FROM_DEVICE; } - scene.calibration_valid = live_calib.getCalStatus() == cereal::LiveCalibrationData::Status::CALIBRATED; - scene.calibration_wide_valid = wfde_list.size() == 3; } if (sm.updated("pandaStates")) { auto pandaStates = sm["pandaStates"].getPandaStates(); diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 8cf2f52d58..8a06a4cccb 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -1,19 +1,18 @@ #pragma once +#include #include #include -#include #include #include #include #include -#include #include "cereal/messaging/messaging.h" #include "common/mat.h" #include "common/params.h" -#include "common/timing.h" +#include "common/util.h" #include "system/hardware/hw.h" #include "selfdrive/ui/qt/prime_state.h" @@ -25,15 +24,22 @@ const int BACKLIGHT_OFFROAD = 50; const float MIN_DRAW_DISTANCE = 10.0; const float MAX_DRAW_DISTANCE = 100.0; -constexpr mat3 DEFAULT_CALIBRATION = {{ 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 1.0, 0.0, 0.0 }}; -constexpr mat3 FCAM_INTRINSIC_MATRIX = (mat3){{2648.0, 0.0, 1928.0 / 2, - 0.0, 2648.0, 1208.0 / 2, - 0.0, 0.0, 1.0}}; +const Eigen::Matrix3f VIEW_FROM_DEVICE = (Eigen::Matrix3f() << + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0, + 1.0, 0.0, 0.0).finished(); + +const Eigen::Matrix3f FCAM_INTRINSIC_MATRIX = (Eigen::Matrix3f() << + 2648.0, 0.0, 1928.0 / 2, + 0.0, 2648.0, 1208.0 / 2, + 0.0, 0.0, 1.0).finished(); + // tici ecam focal probably wrong? magnification is not consistent across frame // Need to retrain model before this can be changed -constexpr mat3 ECAM_INTRINSIC_MATRIX = (mat3){{567.0, 0.0, 1928.0 / 2, - 0.0, 567.0, 1208.0 / 2, - 0.0, 0.0, 1.0}}; +const Eigen::Matrix3f ECAM_INTRINSIC_MATRIX = (Eigen::Matrix3f() << + 567.0, 0.0, 1928.0 / 2, + 0.0, 567.0, 1208.0 / 2, + 0.0, 0.0, 1.0).finished(); typedef enum UIStatus { STATUS_DISENGAGED, @@ -47,13 +53,9 @@ const QColor bg_colors [] = { [STATUS_ENGAGED] = QColor(0x17, 0x86, 0x44, 0xf1), }; - typedef struct UIScene { - bool calibration_valid = false; - bool calibration_wide_valid = false; - bool wide_cam = true; - mat3 view_from_calib = DEFAULT_CALIBRATION; - mat3 view_from_wide_calib = DEFAULT_CALIBRATION; + Eigen::Matrix3f view_from_calib = VIEW_FROM_DEVICE; + Eigen::Matrix3f view_from_wide_calib = VIEW_FROM_DEVICE; cereal::PandaState::PandaType pandaType; // modelV2 @@ -84,18 +86,16 @@ public: return scene.started && (*sm)["selfdriveState"].getSelfdriveState().getEnabled(); } - int fb_w = 0, fb_h = 0; - std::unique_ptr sm; - UIStatus status; UIScene scene = {}; QString language; - - QTransform car_space_transform; PrimeState *prime_state; + Eigen::Matrix3f car_space_transform = Eigen::Matrix3f::Zero(); + QRectF clip_region; + signals: void uiUpdate(const UIState &s); void offroadTransition(bool offroad); @@ -150,7 +150,6 @@ void ui_update_params(UIState *s); int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height); void update_model(UIState *s, const cereal::ModelDataV2::Reader &model); -void update_dmonitoring(UIState *s, const cereal::DriverStateV2::Reader &driverstate, float dm_fade_state, bool is_rhd); void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line); void update_line_data(const UIState *s, const cereal::XYZTData::Reader &line, float y_off, float z_off, QPolygonF *pvd, int max_idx, bool allow_invert); diff --git a/selfdrive/ui/watch3.cc b/selfdrive/ui/watch3.cc index c14e03aa6e..258e2a7bd6 100644 --- a/selfdrive/ui/watch3.cc +++ b/selfdrive/ui/watch3.cc @@ -19,14 +19,14 @@ int main(int argc, char *argv[]) { { QHBoxLayout *hlayout = new QHBoxLayout(); layout->addLayout(hlayout); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_ROAD, false)); + hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_ROAD)); } { QHBoxLayout *hlayout = new QHBoxLayout(); layout->addLayout(hlayout); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_DRIVER, false)); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_WIDE_ROAD, false)); + hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_DRIVER)); + hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_WIDE_ROAD)); } return a.exec(); diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index 48f768c819..07d283787f 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -148,7 +148,7 @@ QWidget *VideoWidget::createCameraWidget() { QStackedLayout *stacked = new QStackedLayout(); stacked->setStackingMode(QStackedLayout::StackAll); - stacked->addWidget(cam_widget = new StreamCameraView("camerad", VISION_STREAM_ROAD, false)); + stacked->addWidget(cam_widget = new StreamCameraView("camerad", VISION_STREAM_ROAD)); cam_widget->setMinimumHeight(MIN_VIDEO_HEIGHT); cam_widget->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::MinimumExpanding); stacked->addWidget(alert_label = new InfoLabel(this)); @@ -420,8 +420,8 @@ void InfoLabel::paintEvent(QPaintEvent *event) { } } -StreamCameraView::StreamCameraView(std::string stream_name, VisionStreamType stream_type, bool zoom, QWidget *parent) - : CameraWidget(stream_name, stream_type, zoom, parent) { +StreamCameraView::StreamCameraView(std::string stream_name, VisionStreamType stream_type, QWidget *parent) + : CameraWidget(stream_name, stream_type, parent) { fade_animation = new QPropertyAnimation(this, "overlayOpacity"); fade_animation->setDuration(500); fade_animation->setStartValue(0.2f); diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h index 76364083a8..17bec78545 100644 --- a/tools/cabana/videowidget.h +++ b/tools/cabana/videowidget.h @@ -64,7 +64,7 @@ class StreamCameraView : public CameraWidget { Q_PROPERTY(float overlayOpacity READ overlayOpacity WRITE setOverlayOpacity) public: - StreamCameraView(std::string stream_name, VisionStreamType stream_type, bool zoom, QWidget *parent = nullptr); + StreamCameraView(std::string stream_name, VisionStreamType stream_type, QWidget *parent = nullptr); void paintGL() override; void showPausedOverlay() { fade_animation->start(); } float overlayOpacity() const { return overlay_opacity; } From d018fd56da8eb45c19bcd01c201f41ad733781da Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 10 Sep 2024 15:55:18 -0700 Subject: [PATCH 041/214] AEB prep (#33515) * init aeb * remove that for now --- cereal/car.capnp | 2 ++ selfdrive/selfdrived/events.py | 9 +++++++++ 2 files changed, 11 insertions(+) diff --git a/cereal/car.capnp b/cereal/car.capnp index cfaa2238c8..e80d64651b 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -115,6 +115,7 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { actuatorsApiUnavailable @120; espActive @121; personalityChanged @122; + aeb @123; radarCanErrorDEPRECATED @15; communityFeatureDisallowedDEPRECATED @62; @@ -371,6 +372,7 @@ struct CarControl { pid @1; stopping @2; starting @3; + emergencyBraking @4; } } diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index d9c922bb90..471e46b88f 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -388,6 +388,15 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { priority=Priority.LOWEST), }, + EventName.aeb: { + ET.PERMANENT: Alert( + "BRAKE!", + "Emergency Braking: Risk of Collision", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.fcw, AudibleAlert.none, 2.), + ET.NO_ENTRY: NoEntryAlert("AEB: Risk of Collision"), + }, + EventName.stockAeb: { ET.PERMANENT: Alert( "BRAKE!", From d02e9393d204ae9e0992b30098ad7e55d98ba237 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 10 Sep 2024 18:58:01 -0700 Subject: [PATCH 042/214] this probably shouldn't go here --- cereal/car.capnp | 1 - 1 file changed, 1 deletion(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index e80d64651b..31c4445af1 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -372,7 +372,6 @@ struct CarControl { pid @1; stopping @2; starting @3; - emergencyBraking @4; } } From e951b7093f830fefe490af795f24b891e1c45916 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Tue, 10 Sep 2024 20:52:12 -0700 Subject: [PATCH 043/214] point tinygrad_repo to commaai/tinygrad (#33536) update submodule --- .gitmodules | 2 +- tinygrad_repo | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.gitmodules b/.gitmodules index ad6530de9a..54c7393986 100644 --- a/.gitmodules +++ b/.gitmodules @@ -15,4 +15,4 @@ url = ../../commaai/teleoprtc [submodule "tinygrad"] path = tinygrad_repo - url = https://github.com/tinygrad/tinygrad.git + url = https://github.com/commaai/tinygrad.git diff --git a/tinygrad_repo b/tinygrad_repo index ae5d1407ee..f51aa0fc7c 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit ae5d1407ee844a97a52ad3756835d38e7e2b9e1b +Subproject commit f51aa0fc7cdbac710e640172db280cfb747d2718 From b9dbefc491024537574b97b33918258bda3aa582 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 11 Sep 2024 13:20:07 -0700 Subject: [PATCH 044/214] Deprecate testJoystick (#33539) * Deprecate testJoystick * fix --- cereal/log.capnp | 2 +- cereal/services.py | 1 - system/webrtc/tests/test_stream_session.py | 2 +- 3 files changed, 2 insertions(+), 3 deletions(-) diff --git a/cereal/log.capnp b/cereal/log.capnp index 258c1f7ab4..d6629206b3 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -2407,7 +2407,6 @@ struct Event { uiDebug @102 :UIDebug; # *********** debug *********** - testJoystick @52 :Joystick; roadEncodeData @86 :EncodeData; driverEncodeData @87 :EncodeData; wideRoadEncodeData @88 :EncodeData; @@ -2476,5 +2475,6 @@ struct Event { uiPlanDEPRECATED @106 :UiPlan; liveLocationKalmanDEPRECATED @72 :LiveLocationKalman; liveTracksDEPRECATED @16 :List(LiveTracksDEPRECATED); + testJoystickDEPRECATED @52 :Joystick; } } diff --git a/cereal/services.py b/cereal/services.py index 926461aec2..e47ddc6c3f 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -75,7 +75,6 @@ _services: dict[str, tuple] = { # debug "uiDebug": (True, 0., 1), - "testJoystick": (True, 0.), "roadEncodeData": (False, 20.), "driverEncodeData": (False, 20.), "wideRoadEncodeData": (False, 20.), diff --git a/system/webrtc/tests/test_stream_session.py b/system/webrtc/tests/test_stream_session.py index 113fa5e7e6..6683c65804 100644 --- a/system/webrtc/tests/test_stream_session.py +++ b/system/webrtc/tests/test_stream_session.py @@ -50,7 +50,7 @@ class TestStreamSession: tested_msgs = [ {"type": "customReservedRawData0", "data": "test"}, # primitive {"type": "can", "data": [{"address": 0, "dat": "", "src": 0}]}, # list - {"type": "testJoystick", "data": {"axes": [0, 0], "buttons": [False]}}, # dict + {"type": "testJoystickDEPRECATED", "data": {"axes": [0, 0], "buttons": [False]}}, # dict ] mocked_pubmaster = mocker.MagicMock(spec=messaging.PubMaster) From 13d947375a5908d68b33bf3b51b799f8021a35a6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 11 Sep 2024 14:02:00 -0700 Subject: [PATCH 045/214] plotjuggler: add bin/ to LD_LIBRARY_PATH (#33538) --- tools/plotjuggler/juggle.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tools/plotjuggler/juggle.py b/tools/plotjuggler/juggle.py index 82bd36622f..6f52e70006 100755 --- a/tools/plotjuggler/juggle.py +++ b/tools/plotjuggler/juggle.py @@ -16,6 +16,8 @@ from openpilot.tools.lib.logreader import LogReader, ReadMode, save_log juggle_dir = os.path.dirname(os.path.realpath(__file__)) +os.environ['LD_LIBRARY_PATH'] = os.environ.get('LD_LIBRARY_PATH', '') + f":{juggle_dir}/bin/" + DEMO_ROUTE = "a2a0ccea32023010|2023-07-27--13-01-19" RELEASES_URL = "https://github.com/commaai/PlotJuggler/releases/download/latest" INSTALL_DIR = os.path.join(juggle_dir, "bin") From b168c6f9af4ba45cdab1a66e770b6d9c236acf6e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 11 Sep 2024 15:02:38 -0700 Subject: [PATCH 046/214] controlsd is driven by selfdriveState (#33541) * controlsd is driven by selfdriveState * update refs --- selfdrive/controls/controlsd.py | 2 +- selfdrive/test/process_replay/process_replay.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 4492b21b47..80331c6ee7 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -37,7 +37,7 @@ class Controls: self.sm = messaging.SubMaster(['liveParameters', 'liveTorqueParameters', 'modelV2', 'selfdriveState', 'liveCalibration', 'livePose', 'longitudinalPlan', 'carState', 'carOutput', - 'driverMonitoringState', 'onroadEvents', 'driverAssistance'], poll='carState') + 'driverMonitoringState', 'onroadEvents', 'driverAssistance'], poll='selfdriveState') self.pm = messaging.PubMaster(['carControl', 'controlsState']) self.steer_limited = False diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index a2ba4a5787..d94c1d1f52 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -485,7 +485,7 @@ CONFIGS = [ subs=["carControl", "controlsState"], ignore=["logMonoTime", ], init_callback=get_car_params_callback, - should_recv_callback=MessageBasedRcvCallback("carState"), + should_recv_callback=MessageBasedRcvCallback("selfdriveState"), tolerance=NUMPY_TOLERANCE, ), ProcessConfig( diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index cfdddb0965..49d920fe2a 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -849fcc369f7afa78606cba636fe7c73e540e6df8 \ No newline at end of file +13d947375a5908d68b33bf3b51b799f8021a35a6 \ No newline at end of file From eae369c7dd373ea93f3214253f8f316275881e2f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 11 Sep 2024 16:18:47 -0700 Subject: [PATCH 047/214] carControl cleanup --- cereal/car.capnp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index 31c4445af1..0ccd00c0ba 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -336,12 +336,10 @@ struct CarControl { latActive @11: Bool; longActive @12: Bool; - # Actuator commands as computed by controlsd + # Final actuator commands actuators @6 :Actuators; - # moved to CarOutput - actuatorsOutputDEPRECATED @10 :Actuators; - + # Blinker controls leftBlinker @15: Bool; rightBlinker @16: Bool; @@ -431,6 +429,7 @@ struct CarControl { activeDEPRECATED @7 :Bool; rollDEPRECATED @8 :Float32; pitchDEPRECATED @9 :Float32; + actuatorsOutputDEPRECATED @10 :Actuators; } struct CarOutput { From 188de7b90ee6005eb4e817f46ddae8463a6e928e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 11 Sep 2024 17:23:33 -0700 Subject: [PATCH 048/214] CI: disable devcontainer until it's faster. not worth 5m --- .github/workflows/tools_tests.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml index 1bdde2a59a..c1c3552472 100644 --- a/.github/workflows/tools_tests.yaml +++ b/.github/workflows/tools_tests.yaml @@ -46,6 +46,7 @@ jobs: devcontainer: name: devcontainer runs-on: ubuntu-latest + if: false # we can re-enable once this is faster steps: - uses: actions/checkout@v4 with: From 9211b701ce7e5ce2716a245ade2cccdf8629d4ce Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 11 Sep 2024 17:23:53 -0700 Subject: [PATCH 049/214] carControl API cleanup (#33543) carControl cleanup --- cereal/car.capnp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index 0ccd00c0ba..f5469a54d7 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -350,21 +350,21 @@ struct CarControl { hudControl @5 :HUDControl; struct Actuators { - # range from 0.0 - 1.0 - gas @0: Float32; - brake @1: Float32; - # range from -1.0 - 1.0 - steer @2: Float32; - # value sent over can to the car - steerOutputCan @8: Float32; + # lateral commands, mutually exclusive + steer @2: Float32; # [0.0, 1.0] steeringAngleDeg @3: Float32; - curvature @7: Float32; - speed @6: Float32; # m/s - accel @4: Float32; # m/s^2 + # longitudinal commands + accel @4: Float32; # m/s^2 longControlState @5: LongControlState; + # these are only for logging the actual values sent to the car over CAN + gas @0: Float32; # [0.0, 1.0] + brake @1: Float32; # [0.0, 1.0] + steerOutputCan @8: Float32; # value sent over can to the car + speed @6: Float32; # m/s + enum LongControlState @0xe40f3a917d908282{ off @0; pid @1; From 82f8db87f464ad826c03f116a35940331304667f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 12 Sep 2024 14:10:18 -0700 Subject: [PATCH 050/214] add longitudinal maneuvers (#33527) * add longitudinal profiles * stash * unfortunately even longitudinalPlan causes circle * add to process config * reach target speed smoothly * stash * works * clean up * debug alert * rename * fix * better text * toggle via exp button * try coming to a stop better, smoother target reaching * closer to target * revert controlsd migration * add description to alert * generate report from local logs * hide bad maneuvers * pdflike * Revert "pdflike" This reverts commit 6d4af1bf9be2e9e0798eaecf026a53d860da7613. * try this * use alert manager * fix that check * wat * Revert "wat" This reverts commit 93d0d27ab838d3f580d06ff212f380e0b912d599. * some clean up * rm * cleanup * move * fix test * more fix * clean up * fix that --- cereal/car.capnp | 1 + cereal/log.capnp | 6 + cereal/services.py | 1 + common/params.cc | 1 + release/release_files.py | 1 + selfdrive/selfdrived/events.py | 16 ++ selfdrive/selfdrived/selfdrived.py | 8 +- system/manager/process_config.py | 9 +- .../longitudinal_maneuvers/generate_report.py | 115 ++++++++++++ tools/longitudinal_maneuvers/maneuversd.py | 165 ++++++++++++++++++ 10 files changed, 320 insertions(+), 3 deletions(-) create mode 100755 tools/longitudinal_maneuvers/generate_report.py create mode 100755 tools/longitudinal_maneuvers/maneuversd.py diff --git a/cereal/car.capnp b/cereal/car.capnp index f5469a54d7..2c18c7c617 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -54,6 +54,7 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { manualRestart @30; lowSpeedLockout @31; joystickDebug @34; + longitudinalManeuver @124; steerTempUnavailableSilent @35; resumeRequired @36; preDriverDistracted @37; diff --git a/cereal/log.capnp b/cereal/log.capnp index d6629206b3..6cd7fe7534 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -2304,6 +2304,11 @@ struct EncodeData { height @5 :UInt32; } +struct DebugAlert { + alertText1 @0 :Text; + alertText2 @1 :Text; +} + struct UserFlag { } @@ -2411,6 +2416,7 @@ struct Event { driverEncodeData @87 :EncodeData; wideRoadEncodeData @88 :EncodeData; qRoadEncodeData @89 :EncodeData; + alertDebug @133 :DebugAlert; livestreamRoadEncodeData @120 :EncodeData; livestreamWideRoadEncodeData @121 :EncodeData; diff --git a/cereal/services.py b/cereal/services.py index e47ddc6c3f..d94c3f11fb 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -75,6 +75,7 @@ _services: dict[str, tuple] = { # debug "uiDebug": (True, 0., 1), + "alertDebug": (True, 0.), "roadEncodeData": (False, 20.), "driverEncodeData": (False, 20.), "wideRoadEncodeData": (False, 20.), diff --git a/common/params.cc b/common/params.cc index 0932acd54d..c75a09e28b 100644 --- a/common/params.cc +++ b/common/params.cc @@ -158,6 +158,7 @@ std::unordered_map keys = { {"LiveParameters", PERSISTENT}, {"LiveTorqueParameters", PERSISTENT | DONT_LOG}, {"LocationFilterInitialState", PERSISTENT}, + {"LongitudinalManeuverMode", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"LongitudinalPersonality", PERSISTENT}, {"NetworkMetered", PERSISTENT}, {"ObdMultiplexingChanged", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, diff --git a/release/release_files.py b/release/release_files.py index 788d45b88e..afd0d468b6 100755 --- a/release/release_files.py +++ b/release/release_files.py @@ -53,6 +53,7 @@ whitelist = [ "tools/lib/", "tools/bodyteleop/", "tools/joystick/", + "tools/longitudinal_maneuvers/", "tinygrad_repo/openpilot/compile2.py", "tinygrad_repo/extra/onnx.py", diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index 471e46b88f..29ab060d9b 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -325,6 +325,17 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" return NormalPermanentAlert("Joystick Mode", vals) + +def longitudinal_maneuver_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: + ad = sm['alertDebug'] + audible_alert = AudibleAlert.prompt if 'Active' in ad.alertText1 else AudibleAlert.none + alert_status = AlertStatus.userPrompt if 'Active' in ad.alertText1 else AlertStatus.normal + alert_size = AlertSize.mid if ad.alertText2 else AlertSize.small + return Alert(ad.alertText1, ad.alertText2, + alert_status, alert_size, + Priority.LOW, VisualAlert.none, audible_alert, 0.2) + + def personality_changed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: personality = str(personality).title() return NormalPermanentAlert(f"Driving Personality: {personality}", duration=1.5) @@ -344,6 +355,11 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.PERMANENT: NormalPermanentAlert("Joystick Mode"), }, + EventName.longitudinalManeuver: { + ET.WARNING: longitudinal_maneuver_alert, + ET.PERMANENT: NormalPermanentAlert("Longitudinal Maneuver Mode"), + }, + EventName.selfdriveInitializing: { ET.NO_ENTRY: NoEntryAlert("System Initializing"), }, diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 255ce080df..4559c82bd6 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -61,7 +61,7 @@ class SelfdriveD: # TODO: de-couple selfdrived with card/conflate on carState without introducing controls mismatches self.car_state_sock = messaging.sub_sock('carState', timeout=20) - ignore = self.sensor_packets + self.gps_packets + ignore = self.sensor_packets + self.gps_packets + ['alertDebug'] if SIMULATION: ignore += ['driverCameraState', 'managerState'] if REPLAY: @@ -70,7 +70,7 @@ class SelfdriveD: self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', - 'controlsState', 'carControl', 'driverAssistance'] + \ + 'controlsState', 'carControl', 'driverAssistance', 'alertDebug'] + \ self.camera_packets + self.sensor_packets + self.gps_packets, ignore_alive=ignore, ignore_avg_freq=ignore+['radarState',], ignore_valid=ignore, frequency=int(1/DT_CTRL)) @@ -135,6 +135,10 @@ class SelfdriveD: self.events.add(EventName.joystickDebug) self.startup_event = None + if self.sm.recv_frame['alertDebug'] > 0: + self.events.add(EventName.longitudinalManeuver) + self.startup_event = None + # Add startup event if self.startup_event is not None: self.events.add(self.startup_event) diff --git a/system/manager/process_config.py b/system/manager/process_config.py index a85bfd1f46..538c55813b 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -35,6 +35,12 @@ def joystick(started: bool, params, CP: car.CarParams) -> bool: def not_joystick(started: bool, params, CP: car.CarParams) -> bool: return started and not params.get_bool("JoystickDebugMode") +def long_maneuver(started: bool, params, CP: car.CarParams) -> bool: + return started and params.get_bool("LongitudinalManeuverMode") + +def not_long_maneuver(started: bool, params, CP: car.CarParams) -> bool: + return started and not params.get_bool("LongitudinalManeuverMode") + def qcomgps(started, params, CP: car.CarParams) -> bool: return started and not ublox_available() @@ -81,7 +87,8 @@ procs = [ PythonProcess("paramsd", "selfdrive.locationd.paramsd", only_onroad), NativeProcess("ubloxd", "system/ubloxd", ["./ubloxd"], ublox, enabled=TICI), PythonProcess("pigeond", "system.ubloxd.pigeond", ublox, enabled=TICI), - PythonProcess("plannerd", "selfdrive.controls.plannerd", only_onroad), + PythonProcess("plannerd", "selfdrive.controls.plannerd", not_long_maneuver), + PythonProcess("maneuversd", "tools.longitudinal_maneuvers.maneuversd", long_maneuver), PythonProcess("radard", "selfdrive.controls.radard", only_onroad), PythonProcess("hardwared", "system.hardware.hardwared", always_run), PythonProcess("tombstoned", "system.tombstoned", always_run, enabled=not PC), diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py new file mode 100755 index 0000000000..262ea93ef3 --- /dev/null +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -0,0 +1,115 @@ +#!/usr/bin/env python3 +import argparse +import base64 +import io +import os +import time +from pathlib import Path +import matplotlib.pyplot as plt + +from openpilot.tools.lib.logreader import LogReader +from openpilot.system.hardware.hw import Paths + + +def report(platform, maneuvers): + output_path = Path(__file__).resolve().parent / "longitudinal_reports" + output_fn = output_path / f"{platform}_{time.strftime('%Y%m%d-%H_%M_%S')}.html" + output_path.mkdir(exist_ok=True) + with open(output_fn, "w") as f: + f.write("

Longitudinal maneuver report

\n") + f.write(f"

{platform}

\n") + for description, runs in maneuvers: + print('plotting maneuver:', description, 'runs:', len(runs)) + f.write("
\n") + f.write(f"

{description}

\n") + for run, msgs in enumerate(runs): + t_carControl, carControl = zip(*[(m.logMonoTime, m.carControl) for m in msgs if m.which() == 'carControl'], strict=True) + t_carOutput, carOutput = zip(*[(m.logMonoTime, m.carOutput) for m in msgs if m.which() == 'carOutput'], strict=True) + t_carState, carState = zip(*[(m.logMonoTime, m.carState) for m in msgs if m.which() == 'carState'], strict=True) + t_longitudinalPlan, longitudinalPlan = zip(*[(m.logMonoTime, m.longitudinalPlan) for m in msgs if m.which() == 'longitudinalPlan'], strict=True) + + longActive = [m.longActive for m in carControl] + gasPressed = [m.gasPressed for m in carState] + brakePressed = [m.brakePressed for m in carState] + + maneuver_valid = all(longActive) and not (any(gasPressed) or any(brakePressed)) + + _open = 'open' if maneuver_valid else '' + title = f'Run #{int(run)+1}' + (' (invalid maneuver!)' if not maneuver_valid else '') + + f.write(f"

{title}

\n") + + plt.rcParams['font.size'] = 40 + fig = plt.figure(figsize=(30, 25)) + ax = fig.subplots(4, 1, sharex=True, gridspec_kw={'hspace': 0, 'height_ratios': [5, 3, 1, 1]}) + + ax[0].grid(linewidth=4) + ax[0].plot(t_carControl, [m.actuators.accel for m in carControl], label='carControl.actuators.accel', linewidth=6) + ax[0].plot(t_carOutput, [m.actuatorsOutput.accel for m in carOutput], label='carOutput.actuatorsOutput.accel', linewidth=6) + ax[0].plot(t_longitudinalPlan, [m.aTarget for m in longitudinalPlan], label='longitudinalPlan.aTarget', linewidth=6) + ax[0].plot(t_carState, [m.aEgo for m in carState], label='carState.aEgo', linewidth=6) + # TODO localizer accel + ax[0].set_ylabel('Acceleration (m/s^2)') + #ax[0].set_ylim(-6.5, 6.5) + ax[0].legend() + + ax[1].grid(linewidth=4) + ax[1].plot(t_carState, [m.vEgo for m in carState], 'g', label='vEgo', linewidth=6) + ax[1].set_ylabel('Velocity (m/s)') + ax[1].legend() + + ax[2].plot(t_carControl, longActive, label='longActive', linewidth=6) + ax[3].plot(t_carState, gasPressed, label='gasPressed', linewidth=6) + ax[3].plot(t_carState, brakePressed, label='brakePressed', linewidth=6) + for i in (2, 3): + ax[i].set_yticks([0, 1], minor=False) + ax[i].set_ylim(-1, 2) + ax[i].legend() + + ax[-1].set_xlabel("Time (s)") + fig.tight_layout() + + buffer = io.BytesIO() + fig.savefig(buffer, format='png') + buffer.seek(0) + f.write(f"\n") + f.write("
\n") + + print(f"\nReport written to {output_fn}\n") + + +if __name__ == '__main__': + parser = argparse.ArgumentParser(description='Generate longitudinal maneuver report from route') + parser.add_argument('route', type=str, help='Route name (e.g. 00000000--5f742174be)') + + args = parser.parse_args() + + if '/' in args.route or '|' in args.route: + lr = LogReader(args.route) + else: + segs = [seg for seg in os.listdir(Paths.log_root()) if args.route in seg] + lr = LogReader([os.path.join(Paths.log_root(), seg, 'rlog') for seg in segs]) + + CP = lr.first('carParams') + platform = CP.carFingerprint + print('processing report for', platform) + + maneuvers: list[tuple[str, list[list]]] = [] + active_prev = False + description_prev = None + + for msg in lr: + if msg.which() == 'alertDebug': + active = 'Maneuver Active' in msg.alertDebug.alertText1 + if active and not active_prev: + if msg.alertDebug.alertText2 == description_prev: + maneuvers[-1][1].append([]) + else: + maneuvers.append((msg.alertDebug.alertText2, [[]])) + description_prev = maneuvers[-1][0] + active_prev = active + + if active_prev: + maneuvers[-1][1][-1].append(msg) + + report(platform, maneuvers) diff --git a/tools/longitudinal_maneuvers/maneuversd.py b/tools/longitudinal_maneuvers/maneuversd.py new file mode 100755 index 0000000000..30304a37c2 --- /dev/null +++ b/tools/longitudinal_maneuvers/maneuversd.py @@ -0,0 +1,165 @@ +#!/usr/bin/env python3 +from dataclasses import dataclass + +from cereal import messaging, car +from opendbc.car.common.conversions import Conversions as CV +from openpilot.common.realtime import DT_MDL +from openpilot.common.params import Params +from openpilot.common.swaglog import cloudlog + + +@dataclass +class Action: + accel: float # m/s^2 + duration: float # seconds + + +@dataclass +class Maneuver: + description: str + actions: list[Action] + repeat: int = 0 + initial_speed: float = 0. # m/s + + _active: bool = False + _finished: bool = False + _action_index: int = 0 + _action_frames: int = 0 + _ready_cnt: int = 0 + _repeated: int = 0 + + def get_accel(self, v_ego: float, enabled: bool, standstill: bool) -> float: + ready = abs(v_ego - self.initial_speed) < 0.3 and enabled and not standstill + self._ready_cnt = (self._ready_cnt + 1) if ready else 0 + + if self._ready_cnt > (3. / DT_MDL): + self._active = True + + if not self._active: + return min(max(self.initial_speed - v_ego, -2.), 2.) + + action = self.actions[self._action_index] + + self._action_frames += 1 + + # reached duration of action + if self._action_frames > (action.duration / DT_MDL): + # next action + if self._action_index < len(self.actions) - 1: + self._action_index += 1 + self._action_frames = 0 + # repeat maneuver + elif self._repeated < self.repeat: + self._repeated += 1 + self._action_index = 0 + self._action_frames = 0 + self._active = False + # finish maneuver + else: + self._finished = True + + return action.accel + + @property + def finished(self): + return self._finished + + @property + def active(self): + return self._active + + +MANEUVERS = [ + Maneuver( + "creep: alternate between +1m/s^2 and -1m/s^2", + [ + Action(1, 2), Action(-1, 2), + Action(1, 2), Action(-1, 2), + Action(1, 2), Action(-1, 2), + ], + repeat=1, + initial_speed=0., + ), + Maneuver( + "brake step response: -1m/s^2 from 20mph", + [Action(-1, 3)], + repeat=2, + initial_speed=20. * CV.MPH_TO_MS, + ), + Maneuver( + "brake step response: -4m/s^2 from 20mph", + [Action(-4, 3)], + repeat=2, + initial_speed=20. * CV.MPH_TO_MS, + ), + Maneuver( + "gas step response: +1m/s^2 from 20mph", + [Action(1, 3)], + repeat=2, + initial_speed=20. * CV.MPH_TO_MS, + ), + Maneuver( + "gas step response: +4m/s^2 from 20mph", + [Action(4, 3)], + repeat=2, + initial_speed=20. * CV.MPH_TO_MS, + ), +] + + +def main(): + params = Params() + cloudlog.info("joystickd is waiting for CarParams") + CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) + + sm = messaging.SubMaster(['carState', 'controlsState', 'selfdriveState', 'modelV2'], poll='modelV2') + pm = messaging.PubMaster(['longitudinalPlan', 'driverAssistance', 'alertDebug']) + + maneuvers = iter(MANEUVERS) + maneuver = None + + while True: + sm.update() + + if maneuver is None: + maneuver = next(maneuvers, None) + + alert_msg = messaging.new_message('alertDebug') + alert_msg.valid = True + + plan_send = messaging.new_message('longitudinalPlan') + plan_send.valid = sm.all_checks() + + longitudinalPlan = plan_send.longitudinalPlan + accel = 0 + cs = sm['carState'] + v_ego = max(cs.vEgo, 0) + + if maneuver is not None: + accel = maneuver.get_accel(v_ego, cs.cruiseState.enabled, cs.cruiseState.standstill) + + if maneuver.active: + alert_msg.alertDebug.alertText1 = f'Maneuver Active: {accel:0.2f} m/s^2' + else: + alert_msg.alertDebug.alertText1 = f'Reaching Speed: {maneuver.initial_speed * CV.MS_TO_MPH:0.2f} mph' + alert_msg.alertDebug.alertText2 = f'{maneuver.description}' + else: + alert_msg.alertDebug.alertText1 = 'Maneuvers Finished' + + pm.send('alertDebug', alert_msg) + + longitudinalPlan.aTarget = accel + longitudinalPlan.shouldStop = v_ego < CP.vEgoStopping and accel < 1e-2 + + longitudinalPlan.allowBrake = True + longitudinalPlan.allowThrottle = True + longitudinalPlan.hasLead = True + + pm.send('longitudinalPlan', plan_send) + + assistance_send = messaging.new_message('driverAssistance') + assistance_send.valid = True + pm.send('driverAssistance', assistance_send) + + if maneuver is not None and maneuver.finished: + maneuver = None From 5305f7a95eefb2876d2c2bf8a823cfbde77cca31 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 12 Sep 2024 16:10:48 -0700 Subject: [PATCH 051/214] maneuversd: add second line warning --- selfdrive/selfdrived/events.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index 29ab060d9b..9ed1b454f0 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -357,7 +357,8 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { EventName.longitudinalManeuver: { ET.WARNING: longitudinal_maneuver_alert, - ET.PERMANENT: NormalPermanentAlert("Longitudinal Maneuver Mode"), + ET.PERMANENT: NormalPermanentAlert("Longitudinal Maneuver Mode", + "Ensure road ahead is clear"), }, EventName.selfdriveInitializing: { From 5f0aa663c8d20e6b368d05205521bcecd6fb37e1 Mon Sep 17 00:00:00 2001 From: commaci-public <60409688+commaci-public@users.noreply.github.com> Date: Thu, 12 Sep 2024 16:51:42 -0700 Subject: [PATCH 052/214] [bot] Update Python packages (#33549) * Update Python packages * bump --------- Co-authored-by: Vehicle Researcher Co-authored-by: Shane Smiskol --- opendbc_repo | 2 +- panda | 2 +- uv.lock | 235 +++++++++++++++++++++++++++------------------------ 3 files changed, 127 insertions(+), 112 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index ef7102a8ae..b43d3003c5 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit ef7102a8ae2334d77ff4b0be512c073e81b01d18 +Subproject commit b43d3003c50d88f4b9d5735b48a101f77a577c54 diff --git a/panda b/panda index fcccbb3a13..b8a2a8678f 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit fcccbb3a131cc8f60025fc7da9b9fdb7a4e3acf7 +Subproject commit b8a2a8678fc201d7c02453a4fb819389d0fbf53b diff --git a/uv.lock b/uv.lock index fb10566645..aec5037de8 100644 --- a/uv.lock +++ b/uv.lock @@ -160,16 +160,16 @@ wheels = [ [[package]] name = "azure-core" -version = "1.30.2" +version = "1.31.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "requests" }, { name = "six" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/99/d4/1f469fa246f554b86fb5cebc30eef1b2a38b7af7a2c2791bce0a4c6e4604/azure-core-1.30.2.tar.gz", hash = "sha256:a14dc210efcd608821aa472d9fb8e8d035d29b68993819147bc290a8ac224472", size = 271104 } +sdist = { url = "https://files.pythonhosted.org/packages/03/7a/f79ad135a276a37e61168495697c14ba1721a52c3eab4dae2941929c79f8/azure_core-1.31.0.tar.gz", hash = "sha256:656a0dd61e1869b1506b7c6a3b31d62f15984b1a573d6326f6aa2f3e4123284b", size = 277147 } wheels = [ - { url = "https://files.pythonhosted.org/packages/ef/d7/69d53f37733f8cb844862781767aef432ff3152bc9b9864dc98c7e286ce9/azure_core-1.30.2-py3-none-any.whl", hash = "sha256:cf019c1ca832e96274ae85abd3d9f752397194d9fea3b41487290562ac8abe4a", size = 194253 }, + { url = "https://files.pythonhosted.org/packages/01/8e/fcb6a77d3029d2a7356f38dbc77cf7daa113b81ddab76b5593d23321e44c/azure_core-1.31.0-py3-none-any.whl", hash = "sha256:22954de3777e0250029360ef31d80448ef1be13b80a459bff80ba7073379e2cd", size = 197399 }, ] [[package]] @@ -473,7 +473,7 @@ wheels = [ [package.optional-dependencies] toml = [ - { name = "tomli", marker = "python_full_version == '3.11'" }, + { name = "tomli", marker = "python_full_version <= '3.11'" }, ] [[package]] @@ -791,14 +791,14 @@ wheels = [ [[package]] name = "importlib-metadata" -version = "8.4.0" +version = "8.5.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "zipp" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c0/bd/fa8ce65b0a7d4b6d143ec23b0f5fd3f7ab80121078c465bc02baeaab22dc/importlib_metadata-8.4.0.tar.gz", hash = "sha256:9a547d3bc3608b025f93d403fdd1aae741c24fbb8314df4b155675742ce303c5", size = 54320 } +sdist = { url = "https://files.pythonhosted.org/packages/cd/12/33e59336dca5be0c398a7482335911a33aa0e20776128f038019f1a95f1b/importlib_metadata-8.5.0.tar.gz", hash = "sha256:71522656f0abace1d072b9e5481a48f07c138e00f079c38c8f883823f9c26bd7", size = 55304 } wheels = [ - { url = "https://files.pythonhosted.org/packages/c0/14/362d31bf1076b21e1bcdcb0dc61944822ff263937b804a79231df2774d28/importlib_metadata-8.4.0-py3-none-any.whl", hash = "sha256:66f342cc6ac9818fc6ff340576acd24d65ba0b3efabb2b4ac08b598965a4a2f1", size = 26269 }, + { url = "https://files.pythonhosted.org/packages/a0/d9/a1e041c5e7caa9a05c925f4bdbdfb7f006d1f74996af53467bc394c97be7/importlib_metadata-8.5.0-py3-none-any.whl", hash = "sha256:45e54197d28b7a7f1559e60b95e7c567032b602131fbd588f1497f47880aa68b", size = 26514 }, ] [[package]] @@ -1240,41 +1240,56 @@ wheels = [ [[package]] name = "multidict" -version = "6.0.5" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/f9/79/722ca999a3a09a63b35aac12ec27dfa8e5bb3a38b0f857f7a1a209a88836/multidict-6.0.5.tar.gz", hash = "sha256:f7e301075edaf50500f0b341543c41194d8df3ae5caf4702f2095f3ca73dd8da", size = 59867 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/5f/da/b10ea65b850b54f44a6479177c6987f456bc2d38f8dc73009b78afcf0ede/multidict-6.0.5-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f285e862d2f153a70586579c15c44656f888806ed0e5b56b64489afe4a2dbfba", size = 50815 }, - { url = "https://files.pythonhosted.org/packages/21/db/3403263f158b0bc7b0d4653766d71cb39498973f2042eead27b2e9758782/multidict-6.0.5-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:53689bb4e102200a4fafa9de9c7c3c212ab40a7ab2c8e474491914d2305f187e", size = 30269 }, - { url = "https://files.pythonhosted.org/packages/02/c1/b15ecceb6ffa5081ed2ed450aea58d65b0e0358001f2b426705f9f41f4c2/multidict-6.0.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:612d1156111ae11d14afaf3a0669ebf6c170dbb735e510a7438ffe2369a847fd", size = 30500 }, - { url = "https://files.pythonhosted.org/packages/3f/e1/7fdd0f39565df3af87d6c2903fb66a7d529fbd0a8a066045d7a5b6ad1145/multidict-6.0.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7be7047bd08accdb7487737631d25735c9a04327911de89ff1b26b81745bd4e3", size = 130751 }, - { url = "https://files.pythonhosted.org/packages/76/bc/9f593f9e38c6c09bbf0344b56ad67dd53c69167937c2edadee9719a5e17d/multidict-6.0.5-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:de170c7b4fe6859beb8926e84f7d7d6c693dfe8e27372ce3b76f01c46e489fcf", size = 138185 }, - { url = "https://files.pythonhosted.org/packages/28/32/d7799a208701d537b92705f46c777ded812a6dc139c18d8ed599908f6b1c/multidict-6.0.5-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:04bde7a7b3de05732a4eb39c94574db1ec99abb56162d6c520ad26f83267de29", size = 133585 }, - { url = "https://files.pythonhosted.org/packages/52/ec/be54a3ad110f386d5bd7a9a42a4ff36b3cd723ebe597f41073a73ffa16b8/multidict-6.0.5-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:85f67aed7bb647f93e7520633d8f51d3cbc6ab96957c71272b286b2f30dc70ed", size = 128684 }, - { url = "https://files.pythonhosted.org/packages/36/e1/a680eabeb71e25d4733276d917658dfa1cd3a99b1223625dbc247d266c98/multidict-6.0.5-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:425bf820055005bfc8aa9a0b99ccb52cc2f4070153e34b701acc98d201693733", size = 120994 }, - { url = "https://files.pythonhosted.org/packages/ef/08/08f4f44a8a43ea4cee13aa9cdbbf4a639af8db49310a0637ca389c4cf817/multidict-6.0.5-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:d3eb1ceec286eba8220c26f3b0096cf189aea7057b6e7b7a2e60ed36b373b77f", size = 159689 }, - { url = "https://files.pythonhosted.org/packages/aa/a9/46cdb4cb40bbd4b732169413f56b04a6553460b22bd914f9729c9ba63761/multidict-6.0.5-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:7901c05ead4b3fb75113fb1dd33eb1253c6d3ee37ce93305acd9d38e0b5f21a4", size = 150611 }, - { url = "https://files.pythonhosted.org/packages/e9/32/35668bb3e6ab2f12f4e4f7f4000f72f714882a94f904d4c3633fbd036753/multidict-6.0.5-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:e0e79d91e71b9867c73323a3444724d496c037e578a0e1755ae159ba14f4f3d1", size = 164444 }, - { url = "https://files.pythonhosted.org/packages/fa/10/f1388a91552af732d8ec48dab928abc209e732767e9e8f92d24c3544353c/multidict-6.0.5-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:29bfeb0dff5cb5fdab2023a7a9947b3b4af63e9c47cae2a10ad58394b517fddc", size = 160158 }, - { url = "https://files.pythonhosted.org/packages/14/c3/f602601f1819983e018156e728e57b3f19726cb424b543667faab82f6939/multidict-6.0.5-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:e030047e85cbcedbfc073f71836d62dd5dadfbe7531cae27789ff66bc551bd5e", size = 156072 }, - { url = "https://files.pythonhosted.org/packages/82/a6/0290af8487326108c0d03d14f8a0b8b1001d71e4494df5f96ab0c88c0b88/multidict-6.0.5-cp311-cp311-win32.whl", hash = "sha256:2f4848aa3baa109e6ab81fe2006c77ed4d3cd1e0ac2c1fbddb7b1277c168788c", size = 25731 }, - { url = "https://files.pythonhosted.org/packages/88/aa/ea217cb18325aa05cb3e3111c19715f1e97c50a4a900cbc20e54648de5f5/multidict-6.0.5-cp311-cp311-win_amd64.whl", hash = "sha256:2faa5ae9376faba05f630d7e5e6be05be22913782b927b19d12b8145968a85ea", size = 28176 }, - { url = "https://files.pythonhosted.org/packages/90/9c/7fda9c0defa09538c97b1f195394be82a1f53238536f70b32eb5399dfd4e/multidict-6.0.5-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:51d035609b86722963404f711db441cf7134f1889107fb171a970c9701f92e1e", size = 49575 }, - { url = "https://files.pythonhosted.org/packages/be/21/d6ca80dd1b9b2c5605ff7475699a8ff5dc6ea958cd71fb2ff234afc13d79/multidict-6.0.5-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:cbebcd5bcaf1eaf302617c114aa67569dd3f090dd0ce8ba9e35e9985b41ac35b", size = 29638 }, - { url = "https://files.pythonhosted.org/packages/9c/18/9565f32c19d186168731e859692dfbc0e98f66a1dcf9e14d69c02a78b75a/multidict-6.0.5-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2ffc42c922dbfddb4a4c3b438eb056828719f07608af27d163191cb3e3aa6cc5", size = 29874 }, - { url = "https://files.pythonhosted.org/packages/4e/4e/3815190e73e6ef101b5681c174c541bf972a1b064e926e56eea78d06e858/multidict-6.0.5-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ceb3b7e6a0135e092de86110c5a74e46bda4bd4fbfeeb3a3bcec79c0f861e450", size = 129914 }, - { url = "https://files.pythonhosted.org/packages/0c/08/bb47f886457e2259aefc10044e45c8a1b62f0c27228557e17775869d0341/multidict-6.0.5-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:79660376075cfd4b2c80f295528aa6beb2058fd289f4c9252f986751a4cd0496", size = 134589 }, - { url = "https://files.pythonhosted.org/packages/d5/2f/952f79b5f0795cf4e34852fc5cf4dfda6166f63c06c798361215b69c131d/multidict-6.0.5-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e4428b29611e989719874670fd152b6625500ad6c686d464e99f5aaeeaca175a", size = 133259 }, - { url = "https://files.pythonhosted.org/packages/24/1f/af976383b0b772dd351210af5b60ff9927e3abb2f4a103e93da19a957da0/multidict-6.0.5-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d84a5c3a5f7ce6db1f999fb9438f686bc2e09d38143f2d93d8406ed2dd6b9226", size = 130779 }, - { url = "https://files.pythonhosted.org/packages/fc/b1/b0a7744be00b0f5045c7ed4e4a6b8ee6bde4672b2c620474712299df5979/multidict-6.0.5-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:76c0de87358b192de7ea9649beb392f107dcad9ad27276324c24c91774ca5271", size = 120125 }, - { url = "https://files.pythonhosted.org/packages/d0/bf/2a1d667acf11231cdf0b97a6cd9f30e7a5cf847037b5cf6da44884284bd0/multidict-6.0.5-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:79a6d2ba910adb2cbafc95dad936f8b9386e77c84c35bc0add315b856d7c3abb", size = 167095 }, - { url = "https://files.pythonhosted.org/packages/5e/e8/ad6ee74b1a2050d3bc78f566dabcc14c8bf89cbe87eecec866c011479815/multidict-6.0.5-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:92d16a3e275e38293623ebf639c471d3e03bb20b8ebb845237e0d3664914caef", size = 155823 }, - { url = "https://files.pythonhosted.org/packages/45/7c/06926bb91752c52abca3edbfefac1ea90d9d1bc00c84d0658c137589b920/multidict-6.0.5-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:fb616be3538599e797a2017cccca78e354c767165e8858ab5116813146041a24", size = 170233 }, - { url = "https://files.pythonhosted.org/packages/3c/29/3dd36cf6b9c5abba8b97bba84eb499a168ba59c3faec8829327b3887d123/multidict-6.0.5-cp312-cp312-musllinux_1_1_s390x.whl", hash = "sha256:14c2976aa9038c2629efa2c148022ed5eb4cb939e15ec7aace7ca932f48f9ba6", size = 169035 }, - { url = "https://files.pythonhosted.org/packages/60/47/9a0f43470c70bbf6e148311f78ef5a3d4996b0226b6d295bdd50fdcfe387/multidict-6.0.5-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:435a0984199d81ca178b9ae2c26ec3d49692d20ee29bc4c11a2a8d4514c67eda", size = 166229 }, - { url = "https://files.pythonhosted.org/packages/1d/23/c1b7ae7a0b8a3e08225284ef3ecbcf014b292a3ee821bc4ed2185fd4ce7d/multidict-6.0.5-cp312-cp312-win32.whl", hash = "sha256:9fe7b0653ba3d9d65cbe7698cca585bf0f8c83dbbcc710db9c90f478e175f2d5", size = 25840 }, - { url = "https://files.pythonhosted.org/packages/4a/68/66fceb758ad7a88993940dbdf3ac59911ba9dc46d7798bf6c8652f89f853/multidict-6.0.5-cp312-cp312-win_amd64.whl", hash = "sha256:01265f5e40f5a17f8241d52656ed27192be03bfa8764d88e8220141d1e4b3556", size = 27905 }, - { url = "https://files.pythonhosted.org/packages/fa/a2/17e1e23c6be0a916219c5292f509360c345b5fa6beeb50d743203c27532c/multidict-6.0.5-py3-none-any.whl", hash = "sha256:0d63c74e3d7ab26de115c49bffc92cc77ed23395303d496eae515d4204a625e7", size = 9729 }, +version = "6.1.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/d6/be/504b89a5e9ca731cd47487e91c469064f8ae5af93b7259758dcfc2b9c848/multidict-6.1.0.tar.gz", hash = "sha256:22ae2ebf9b0c69d206c003e2f6a914ea33f0a932d4aa16f236afc049d9958f4a", size = 64002 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/93/13/df3505a46d0cd08428e4c8169a196131d1b0c4b515c3649829258843dde6/multidict-6.1.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3efe2c2cb5763f2f1b275ad2bf7a287d3f7ebbef35648a9726e3b69284a4f3d6", size = 48570 }, + { url = "https://files.pythonhosted.org/packages/f0/e1/a215908bfae1343cdb72f805366592bdd60487b4232d039c437fe8f5013d/multidict-6.1.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c7053d3b0353a8b9de430a4f4b4268ac9a4fb3481af37dfe49825bf45ca24156", size = 29316 }, + { url = "https://files.pythonhosted.org/packages/70/0f/6dc70ddf5d442702ed74f298d69977f904960b82368532c88e854b79f72b/multidict-6.1.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:27e5fc84ccef8dfaabb09d82b7d179c7cf1a3fbc8a966f8274fcb4ab2eb4cadb", size = 29640 }, + { url = "https://files.pythonhosted.org/packages/d8/6d/9c87b73a13d1cdea30b321ef4b3824449866bd7f7127eceed066ccb9b9ff/multidict-6.1.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0e2b90b43e696f25c62656389d32236e049568b39320e2735d51f08fd362761b", size = 131067 }, + { url = "https://files.pythonhosted.org/packages/cc/1e/1b34154fef373371fd6c65125b3d42ff5f56c7ccc6bfff91b9b3c60ae9e0/multidict-6.1.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d83a047959d38a7ff552ff94be767b7fd79b831ad1cd9920662db05fec24fe72", size = 138507 }, + { url = "https://files.pythonhosted.org/packages/fb/e0/0bc6b2bac6e461822b5f575eae85da6aae76d0e2a79b6665d6206b8e2e48/multidict-6.1.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d1a9dd711d0877a1ece3d2e4fea11a8e75741ca21954c919406b44e7cf971304", size = 133905 }, + { url = "https://files.pythonhosted.org/packages/ba/af/73d13b918071ff9b2205fcf773d316e0f8fefb4ec65354bbcf0b10908cc6/multidict-6.1.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ec2abea24d98246b94913b76a125e855eb5c434f7c46546046372fe60f666351", size = 129004 }, + { url = "https://files.pythonhosted.org/packages/74/21/23960627b00ed39643302d81bcda44c9444ebcdc04ee5bedd0757513f259/multidict-6.1.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4867cafcbc6585e4b678876c489b9273b13e9fff9f6d6d66add5e15d11d926cb", size = 121308 }, + { url = "https://files.pythonhosted.org/packages/8b/5c/cf282263ffce4a596ed0bb2aa1a1dddfe1996d6a62d08842a8d4b33dca13/multidict-6.1.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:5b48204e8d955c47c55b72779802b219a39acc3ee3d0116d5080c388970b76e3", size = 132608 }, + { url = "https://files.pythonhosted.org/packages/d7/3e/97e778c041c72063f42b290888daff008d3ab1427f5b09b714f5a8eff294/multidict-6.1.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:d8fff389528cad1618fb4b26b95550327495462cd745d879a8c7c2115248e399", size = 127029 }, + { url = "https://files.pythonhosted.org/packages/47/ac/3efb7bfe2f3aefcf8d103e9a7162572f01936155ab2f7ebcc7c255a23212/multidict-6.1.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:a7a9541cd308eed5e30318430a9c74d2132e9a8cb46b901326272d780bf2d423", size = 137594 }, + { url = "https://files.pythonhosted.org/packages/42/9b/6c6e9e8dc4f915fc90a9b7798c44a30773dea2995fdcb619870e705afe2b/multidict-6.1.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:da1758c76f50c39a2efd5e9859ce7d776317eb1dd34317c8152ac9251fc574a3", size = 134556 }, + { url = "https://files.pythonhosted.org/packages/1d/10/8e881743b26aaf718379a14ac58572a240e8293a1c9d68e1418fb11c0f90/multidict-6.1.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:c943a53e9186688b45b323602298ab727d8865d8c9ee0b17f8d62d14b56f0753", size = 130993 }, + { url = "https://files.pythonhosted.org/packages/45/84/3eb91b4b557442802d058a7579e864b329968c8d0ea57d907e7023c677f2/multidict-6.1.0-cp311-cp311-win32.whl", hash = "sha256:90f8717cb649eea3504091e640a1b8568faad18bd4b9fcd692853a04475a4b80", size = 26405 }, + { url = "https://files.pythonhosted.org/packages/9f/0b/ad879847ecbf6d27e90a6eabb7eff6b62c129eefe617ea45eae7c1f0aead/multidict-6.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:82176036e65644a6cc5bd619f65f6f19781e8ec2e5330f51aa9ada7504cc1926", size = 28795 }, + { url = "https://files.pythonhosted.org/packages/fd/16/92057c74ba3b96d5e211b553895cd6dc7cc4d1e43d9ab8fafc727681ef71/multidict-6.1.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:b04772ed465fa3cc947db808fa306d79b43e896beb677a56fb2347ca1a49c1fa", size = 48713 }, + { url = "https://files.pythonhosted.org/packages/94/3d/37d1b8893ae79716179540b89fc6a0ee56b4a65fcc0d63535c6f5d96f217/multidict-6.1.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:6180c0ae073bddeb5a97a38c03f30c233e0a4d39cd86166251617d1bbd0af436", size = 29516 }, + { url = "https://files.pythonhosted.org/packages/a2/12/adb6b3200c363062f805275b4c1e656be2b3681aada66c80129932ff0bae/multidict-6.1.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:071120490b47aa997cca00666923a83f02c7fbb44f71cf7f136df753f7fa8761", size = 29557 }, + { url = "https://files.pythonhosted.org/packages/47/e9/604bb05e6e5bce1e6a5cf80a474e0f072e80d8ac105f1b994a53e0b28c42/multidict-6.1.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:50b3a2710631848991d0bf7de077502e8994c804bb805aeb2925a981de58ec2e", size = 130170 }, + { url = "https://files.pythonhosted.org/packages/7e/13/9efa50801785eccbf7086b3c83b71a4fb501a4d43549c2f2f80b8787d69f/multidict-6.1.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b58c621844d55e71c1b7f7c498ce5aa6985d743a1a59034c57a905b3f153c1ef", size = 134836 }, + { url = "https://files.pythonhosted.org/packages/bf/0f/93808b765192780d117814a6dfcc2e75de6dcc610009ad408b8814dca3ba/multidict-6.1.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:55b6d90641869892caa9ca42ff913f7ff1c5ece06474fbd32fb2cf6834726c95", size = 133475 }, + { url = "https://files.pythonhosted.org/packages/d3/c8/529101d7176fe7dfe1d99604e48d69c5dfdcadb4f06561f465c8ef12b4df/multidict-6.1.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4b820514bfc0b98a30e3d85462084779900347e4d49267f747ff54060cc33925", size = 131049 }, + { url = "https://files.pythonhosted.org/packages/ca/0c/fc85b439014d5a58063e19c3a158a889deec399d47b5269a0f3b6a2e28bc/multidict-6.1.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:10a9b09aba0c5b48c53761b7c720aaaf7cf236d5fe394cd399c7ba662d5f9966", size = 120370 }, + { url = "https://files.pythonhosted.org/packages/db/46/d4416eb20176492d2258fbd47b4abe729ff3b6e9c829ea4236f93c865089/multidict-6.1.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1e16bf3e5fc9f44632affb159d30a437bfe286ce9e02754759be5536b169b305", size = 125178 }, + { url = "https://files.pythonhosted.org/packages/5b/46/73697ad7ec521df7de5531a32780bbfd908ded0643cbe457f981a701457c/multidict-6.1.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:76f364861c3bfc98cbbcbd402d83454ed9e01a5224bb3a28bf70002a230f73e2", size = 119567 }, + { url = "https://files.pythonhosted.org/packages/cd/ed/51f060e2cb0e7635329fa6ff930aa5cffa17f4c7f5c6c3ddc3500708e2f2/multidict-6.1.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:820c661588bd01a0aa62a1283f20d2be4281b086f80dad9e955e690c75fb54a2", size = 129822 }, + { url = "https://files.pythonhosted.org/packages/df/9e/ee7d1954b1331da3eddea0c4e08d9142da5f14b1321c7301f5014f49d492/multidict-6.1.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:0e5f362e895bc5b9e67fe6e4ded2492d8124bdf817827f33c5b46c2fe3ffaca6", size = 128656 }, + { url = "https://files.pythonhosted.org/packages/77/00/8538f11e3356b5d95fa4b024aa566cde7a38aa7a5f08f4912b32a037c5dc/multidict-6.1.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:3ec660d19bbc671e3a6443325f07263be452c453ac9e512f5eb935e7d4ac28b3", size = 125360 }, + { url = "https://files.pythonhosted.org/packages/be/05/5d334c1f2462d43fec2363cd00b1c44c93a78c3925d952e9a71caf662e96/multidict-6.1.0-cp312-cp312-win32.whl", hash = "sha256:58130ecf8f7b8112cdb841486404f1282b9c86ccb30d3519faf301b2e5659133", size = 26382 }, + { url = "https://files.pythonhosted.org/packages/a3/bf/f332a13486b1ed0496d624bcc7e8357bb8053823e8cd4b9a18edc1d97e73/multidict-6.1.0-cp312-cp312-win_amd64.whl", hash = "sha256:188215fc0aafb8e03341995e7c4797860181562380f81ed0a87ff455b70bf1f1", size = 28529 }, + { url = "https://files.pythonhosted.org/packages/22/67/1c7c0f39fe069aa4e5d794f323be24bf4d33d62d2a348acdb7991f8f30db/multidict-6.1.0-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:d569388c381b24671589335a3be6e1d45546c2988c2ebe30fdcada8457a31008", size = 48771 }, + { url = "https://files.pythonhosted.org/packages/3c/25/c186ee7b212bdf0df2519eacfb1981a017bda34392c67542c274651daf23/multidict-6.1.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:052e10d2d37810b99cc170b785945421141bf7bb7d2f8799d431e7db229c385f", size = 29533 }, + { url = "https://files.pythonhosted.org/packages/67/5e/04575fd837e0958e324ca035b339cea174554f6f641d3fb2b4f2e7ff44a2/multidict-6.1.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:f90c822a402cb865e396a504f9fc8173ef34212a342d92e362ca498cad308e28", size = 29595 }, + { url = "https://files.pythonhosted.org/packages/d3/b2/e56388f86663810c07cfe4a3c3d87227f3811eeb2d08450b9e5d19d78876/multidict-6.1.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b225d95519a5bf73860323e633a664b0d85ad3d5bede6d30d95b35d4dfe8805b", size = 130094 }, + { url = "https://files.pythonhosted.org/packages/6c/ee/30ae9b4186a644d284543d55d491fbd4239b015d36b23fea43b4c94f7052/multidict-6.1.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:23bfd518810af7de1116313ebd9092cb9aa629beb12f6ed631ad53356ed6b86c", size = 134876 }, + { url = "https://files.pythonhosted.org/packages/84/c7/70461c13ba8ce3c779503c70ec9d0345ae84de04521c1f45a04d5f48943d/multidict-6.1.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5c09fcfdccdd0b57867577b719c69e347a436b86cd83747f179dbf0cc0d4c1f3", size = 133500 }, + { url = "https://files.pythonhosted.org/packages/4a/9f/002af221253f10f99959561123fae676148dd730e2daa2cd053846a58507/multidict-6.1.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bf6bea52ec97e95560af5ae576bdac3aa3aae0b6758c6efa115236d9e07dae44", size = 131099 }, + { url = "https://files.pythonhosted.org/packages/82/42/d1c7a7301d52af79d88548a97e297f9d99c961ad76bbe6f67442bb77f097/multidict-6.1.0-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:57feec87371dbb3520da6192213c7d6fc892d5589a93db548331954de8248fd2", size = 120403 }, + { url = "https://files.pythonhosted.org/packages/68/f3/471985c2c7ac707547553e8f37cff5158030d36bdec4414cb825fbaa5327/multidict-6.1.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:0c3f390dc53279cbc8ba976e5f8035eab997829066756d811616b652b00a23a3", size = 125348 }, + { url = "https://files.pythonhosted.org/packages/67/2c/e6df05c77e0e433c214ec1d21ddd203d9a4770a1f2866a8ca40a545869a0/multidict-6.1.0-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:59bfeae4b25ec05b34f1956eaa1cb38032282cd4dfabc5056d0a1ec4d696d3aa", size = 119673 }, + { url = "https://files.pythonhosted.org/packages/c5/cd/bc8608fff06239c9fb333f9db7743a1b2eafe98c2666c9a196e867a3a0a4/multidict-6.1.0-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:b2f59caeaf7632cc633b5cf6fc449372b83bbdf0da4ae04d5be36118e46cc0aa", size = 129927 }, + { url = "https://files.pythonhosted.org/packages/44/8e/281b69b7bc84fc963a44dc6e0bbcc7150e517b91df368a27834299a526ac/multidict-6.1.0-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:37bb93b2178e02b7b618893990941900fd25b6b9ac0fa49931a40aecdf083fe4", size = 128711 }, + { url = "https://files.pythonhosted.org/packages/12/a4/63e7cd38ed29dd9f1881d5119f272c898ca92536cdb53ffe0843197f6c85/multidict-6.1.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:4e9f48f58c2c523d5a06faea47866cd35b32655c46b443f163d08c6d0ddb17d6", size = 125519 }, + { url = "https://files.pythonhosted.org/packages/38/e0/4f5855037a72cd8a7a2f60a3952d9aa45feedb37ae7831642102604e8a37/multidict-6.1.0-cp313-cp313-win32.whl", hash = "sha256:3a37ffb35399029b45c6cc33640a92bef403c9fd388acce75cdc88f58bd19a81", size = 26426 }, + { url = "https://files.pythonhosted.org/packages/7e/a5/17ee3a4db1e310b7405f5d25834460073a8ccd86198ce044dfaf69eac073/multidict-6.1.0-cp313-cp313-win_amd64.whl", hash = "sha256:e9aa71e15d9d9beaad2c6b9319edcdc0a49a43ef5c0a4c8265ca9ee7d6c67774", size = 28531 }, + { url = "https://files.pythonhosted.org/packages/99/b7/b9e70fde2c0f0c9af4cc5277782a89b66d35948ea3369ec9f598358c3ac5/multidict-6.1.0-py3-none-any.whl", hash = "sha256:48e171e52d1c4d33888e529b999e5900356b9ae588c2f09a52dcefb158b27506", size = 10051 }, ] [[package]] @@ -1429,6 +1444,7 @@ dependencies = [ { name = "crcmod" }, { name = "cython" }, { name = "future-fstrings" }, + { name = "inputs" }, { name = "json-rpc" }, { name = "libusb1" }, { name = "numpy" }, @@ -1463,7 +1479,6 @@ dev = [ { name = "azure-storage-blob" }, { name = "dictdiffer" }, { name = "flaky" }, - { name = "inputs" }, { name = "lru-dict" }, { name = "matplotlib" }, { name = "metadrive-simulator", marker = "platform_machine != 'aarch64'" }, @@ -1520,7 +1535,7 @@ requires-dist = [ { name = "flaky", marker = "extra == 'dev'" }, { name = "future-fstrings" }, { name = "hypothesis", marker = "extra == 'testing'", specifier = "==6.47.*" }, - { name = "inputs", marker = "extra == 'dev'" }, + { name = "inputs" }, { name = "jinja2", marker = "extra == 'docs'" }, { name = "json-rpc" }, { name = "libusb1" }, @@ -1740,16 +1755,16 @@ sdist = { url = "https://files.pythonhosted.org/packages/a3/a6/b8e451f6cff1c99b4 [[package]] name = "protobuf" -version = "5.28.0" +version = "5.28.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/5f/d7/331ee1f3b798c34d2257c79d5426ecbe95d46d2b40ba808a29da6947f6d8/protobuf-5.28.0.tar.gz", hash = "sha256:dde74af0fa774fa98892209992295adbfb91da3fa98c8f67a88afe8f5a349add", size = 422388 } +sdist = { url = "https://files.pythonhosted.org/packages/3c/0b/7a997c8939f698d72bdea14d57116e43d3051fffb3b2964c30938c4a08e6/protobuf-5.28.1.tar.gz", hash = "sha256:42597e938f83bb7f3e4b35f03aa45208d49ae8d5bcb4bc10b9fc825e0ab5e423", size = 422422 } wheels = [ - { url = "https://files.pythonhosted.org/packages/66/34/fc43138c93316839080324cb066f35224b75dae56b9f0fdd9d47c988ee9a/protobuf-5.28.0-cp310-abi3-win32.whl", hash = "sha256:66c3edeedb774a3508ae70d87b3a19786445fe9a068dd3585e0cefa8a77b83d0", size = 419672 }, - { url = "https://files.pythonhosted.org/packages/de/f7/e7e03be7e7307123f6467080f283e484de7e892db54dd9a46f057d08c9ee/protobuf-5.28.0-cp310-abi3-win_amd64.whl", hash = "sha256:6d7cc9e60f976cf3e873acb9a40fed04afb5d224608ed5c1a105db4a3f09c5b6", size = 431486 }, - { url = "https://files.pythonhosted.org/packages/ce/ec/34f67d6a3398aa360524d90f75a8c648c99c807b2f1001f5ab16355c1d12/protobuf-5.28.0-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:532627e8fdd825cf8767a2d2b94d77e874d5ddb0adefb04b237f7cc296748681", size = 414744 }, - { url = "https://files.pythonhosted.org/packages/fe/79/636415c84eed9835fed83183db73fd6ea7ba76a85cae321ff2eaad722e85/protobuf-5.28.0-cp38-abi3-manylinux2014_aarch64.whl", hash = "sha256:018db9056b9d75eb93d12a9d35120f97a84d9a919bcab11ed56ad2d399d6e8dd", size = 316527 }, - { url = "https://files.pythonhosted.org/packages/19/15/da43113361db20f2d521bc38d92549edbe06856aeec085c420b2b8af5751/protobuf-5.28.0-cp38-abi3-manylinux2014_x86_64.whl", hash = "sha256:6206afcb2d90181ae8722798dcb56dc76675ab67458ac24c0dd7d75d632ac9bd", size = 316615 }, - { url = "https://files.pythonhosted.org/packages/e3/b2/4df9958122a0377e571972c71692420bafd623d1df3ce506d88c2aba7e12/protobuf-5.28.0-py3-none-any.whl", hash = "sha256:510ed78cd0980f6d3218099e874714cdf0d8a95582e7b059b06cabad855ed0a0", size = 169574 }, + { url = "https://files.pythonhosted.org/packages/5a/d6/6dedb8a2fbbeb4ac92bb9dd830f77800bbe353799eb8b11d2659beffb9f4/protobuf-5.28.1-cp310-abi3-win32.whl", hash = "sha256:fc063acaf7a3d9ca13146fefb5b42ac94ab943ec6e978f543cd5637da2d57957", size = 419673 }, + { url = "https://files.pythonhosted.org/packages/28/ff/6af7b6fad3bd85820f00f3753a2ebd6bdd9dbf29da5a4252e9f402bdfe2a/protobuf-5.28.1-cp310-abi3-win_amd64.whl", hash = "sha256:4c7f5cb38c640919791c9f74ea80c5b82314c69a8409ea36f2599617d03989af", size = 431486 }, + { url = "https://files.pythonhosted.org/packages/99/80/46b61e647a9386f5dc836e9660818f79afd80a4d5802535ec07a7c6aa16e/protobuf-5.28.1-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:4304e4fceb823d91699e924a1fdf95cde0e066f3b1c28edb665bda762ecde10f", size = 414743 }, + { url = "https://files.pythonhosted.org/packages/b3/21/33dbf04427a11c2de5fb835bb37c5d1522e9d5556a92df0acd13644860a9/protobuf-5.28.1-cp38-abi3-manylinux2014_aarch64.whl", hash = "sha256:0dfd86d2b5edf03d91ec2a7c15b4e950258150f14f9af5f51c17fa224ee1931f", size = 316526 }, + { url = "https://files.pythonhosted.org/packages/c0/be/bac52549cab1aaab112d380b3f2a80a348ba7083a80bf4ff4be4fb5a6729/protobuf-5.28.1-cp38-abi3-manylinux2014_x86_64.whl", hash = "sha256:51f09caab818707ab91cf09cc5c156026599cf05a4520779ccbf53c1b352fb25", size = 316613 }, + { url = "https://files.pythonhosted.org/packages/51/3d/71fae0078424ba8ea70b222b6fa56ef771a9918ab91cee806c2abc9d57fa/protobuf-5.28.1-py3-none-any.whl", hash = "sha256:c529535e5c0effcf417682563719e5d8ac8d2b93de07a56108b4c2d436d7a29a", size = 169572 }, ] [[package]] @@ -4508,11 +4523,11 @@ wheels = [ [[package]] name = "pyreadline3" -version = "3.4.1" +version = "3.4.3" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d7/86/3d61a61f36a0067874a00cb4dceb9028d34b6060e47828f7fc86fb9f7ee9/pyreadline3-3.4.1.tar.gz", hash = "sha256:6f3d1f7b8a31ba32b73917cefc1f28cc660562f39aea8646d30bd6eff21f7bae", size = 86465 } +sdist = { url = "https://files.pythonhosted.org/packages/fa/2a/ea766323eb84142ef7c068f9988d0b02c0f8fd21252791b0b6f56eec67db/pyreadline3-3.4.3.tar.gz", hash = "sha256:ebab0baca37f50e2faa1dd99a6da1c75de60e0d68a3b229c134bbd12786250e2", size = 86464 } wheels = [ - { url = "https://files.pythonhosted.org/packages/56/fc/a3c13ded7b3057680c8ae95a9b6cc83e63657c38e0005c400a5d018a33a7/pyreadline3-3.4.1-py3-none-any.whl", hash = "sha256:b0efb6516fd4fb07b45949053826a62fa4cb353db5be2bbb4a7aa1fdd1e345fb", size = 95203 }, + { url = "https://files.pythonhosted.org/packages/2b/19/da2de49e7b9c1f1724003e8adba0e677fdfb3b8237cc637b5f14bfcc33d4/pyreadline3-3.4.3-py3-none-any.whl", hash = "sha256:f832c5898f4f9a0f81d48a8c499b39d0179de1a465ea3def1a7e7231840b4ed6", size = 95320 }, ] [[package]] @@ -4541,7 +4556,7 @@ wheels = [ [[package]] name = "pytest" -version = "8.3.2" +version = "8.3.3" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "colorama", marker = "sys_platform == 'win32'" }, @@ -4549,9 +4564,9 @@ dependencies = [ { name = "packaging" }, { name = "pluggy" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b4/8c/9862305bdcd6020bc7b45b1b5e7397a6caf1a33d3025b9a003b39075ffb2/pytest-8.3.2.tar.gz", hash = "sha256:c132345d12ce551242c87269de812483f5bcc87cdbb4722e48487ba194f9fdce", size = 1439314 } +sdist = { url = "https://files.pythonhosted.org/packages/8b/6c/62bbd536103af674e227c41a8f3dcd022d591f6eed5facb5a0f31ee33bbc/pytest-8.3.3.tar.gz", hash = "sha256:70b98107bd648308a7952b06e6ca9a50bc660be218d53c257cc1fc94fda10181", size = 1442487 } wheels = [ - { url = "https://files.pythonhosted.org/packages/0f/f9/cf155cf32ca7d6fa3601bc4c5dd19086af4b320b706919d48a4c79081cf9/pytest-8.3.2-py3-none-any.whl", hash = "sha256:4ba08f9ae7dcf84ded419494d229b48d0903ea6407b030eaec46df5e6a73bba5", size = 341802 }, + { url = "https://files.pythonhosted.org/packages/6b/77/7440a06a8ead44c7757a64362dd22df5760f9b12dc5f11b6188cd2fc27a0/pytest-8.3.3-py3-none-any.whl", hash = "sha256:a6853c7375b2663155079443d2e45de913a911a11d669df02a50814944db57b2", size = 342341 }, ] [[package]] @@ -5202,11 +5217,11 @@ wheels = [ [[package]] name = "urllib3" -version = "2.2.2" +version = "2.2.3" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/43/6d/fa469ae21497ddc8bc93e5877702dca7cb8f911e337aca7452b5724f1bb6/urllib3-2.2.2.tar.gz", hash = "sha256:dd505485549a7a552833da5e6063639d0d177c04f23bc3864e41e5dc5f612168", size = 292266 } +sdist = { url = "https://files.pythonhosted.org/packages/ed/63/22ba4ebfe7430b76388e7cd448d5478814d3032121827c12a2cc287e2260/urllib3-2.2.3.tar.gz", hash = "sha256:e7d814a81dad81e6caf2ec9fdedb284ecc9c73076b62654547cc64ccdcae26e9", size = 300677 } wheels = [ - { url = "https://files.pythonhosted.org/packages/ca/1c/89ffc63a9605b583d5df2be791a27bc1a42b7c32bab68d3c8f2f73a98cd4/urllib3-2.2.2-py3-none-any.whl", hash = "sha256:a448b2f64d686155468037e1ace9f2d2199776e17f0a46610480d311f73e3472", size = 121444 }, + { url = "https://files.pythonhosted.org/packages/ce/d9/5f4c13cecde62396b0d3fe530a50ccea91e7dfc1ccf0e09c228841bb5ba8/urllib3-2.2.3-py3-none-any.whl", hash = "sha256:ca899ca043dcb1bafa3e262d73aa25c465bfb49e0bd9dd5d59f1d0acba2f8fac", size = 126338 }, ] [[package]] @@ -5261,60 +5276,60 @@ wheels = [ [[package]] name = "yarl" -version = "1.11.0" +version = "1.11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "idna" }, { name = "multidict" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d5/f0/56955b0dde04e8e811ad71a9308dd11cda14a079bf0fb2cdfabfb95f5d9c/yarl-1.11.0.tar.gz", hash = "sha256:f86f4f4a57a29ef08fa70c4667d04c5e3ba513500da95586208b285437cb9592", size = 160812 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/11/49/0895d3532224e99713f483d72f50a23fba35960fc2b579ac011e4f1c1279/yarl-1.11.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:39e3087e1ef70862de81e22af9eb299faee580f41673ef92829949022791b521", size = 188003 }, - { url = "https://files.pythonhosted.org/packages/d6/7b/392f261aefe24ece4e80efc5612b7a28a6399a111900ae976c5ec6181153/yarl-1.11.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:7fd535cc41b81a566ad347081b671ab5c7e5f5b6a15526d85b4e748baf065cf0", size = 113889 }, - { url = "https://files.pythonhosted.org/packages/02/2e/46adc855d159b8898e7c975c467c29a551aa11634d8abe3d56efabd7590e/yarl-1.11.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f7cc02d8e9a612174869f4b983f159e87659096f7e2dc1fe9effd9902e408739", size = 112142 }, - { url = "https://files.pythonhosted.org/packages/12/fc/faa24a0b05f030d8c99d9c72029dde4d1ba2474c2f6105a75c92640b13d2/yarl-1.11.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:30f391ccf4b1b1e0ba4880075ba337d41a619a5350f67053927f67ebe764bf44", size = 484576 }, - { url = "https://files.pythonhosted.org/packages/11/64/fa9c04e685aeb0582e64e541b7b3684190f13ccbdfbee5e89fc597ced727/yarl-1.11.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4c19a0d95943bb2c914b4e71043803be34bc75c08c4a6ca232bdc649a1e9ef1b", size = 504473 }, - { url = "https://files.pythonhosted.org/packages/22/32/d9c8970b09139e701737062fe93927800f2b7204771b8087aa4ecdfaec5a/yarl-1.11.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ead4d89eade0e09b8ef97877664abb0e2e8704787db5564f83658fdee5c36497", size = 498891 }, - { url = "https://files.pythonhosted.org/packages/9c/b7/35577b3ab5dd0cabb5f793a5dd03186b2f10916833d894a1d611ecbe11a8/yarl-1.11.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:195f7791bc23d5f2480efe53f935daf8a61661000dfbfbdd70dbd06397594fff", size = 487450 }, - { url = "https://files.pythonhosted.org/packages/9d/8e/0ca5bfdaacb736f0fb5abd4ef0679b3685ae4a4f1868acef86e5fd4b598e/yarl-1.11.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:01a7905e662665ca8e058635377522bc3c98bdb873be761ff42c86eb72b03914", size = 470089 }, - { url = "https://files.pythonhosted.org/packages/20/5b/468c7f578c004b20b3860cb1270b007268e81eaec9be86aac31bd6d0c1d1/yarl-1.11.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:53c80b1927b75aed208d7fd965a3a705dc8c1db4d50b9112418fa0f7784363e6", size = 484143 }, - { url = "https://files.pythonhosted.org/packages/dc/64/082fd4f2e0b9d38437e8a7443924e4c6e6cbeb63da284034f8b7709061f3/yarl-1.11.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:11af21bbf807688d49b7d4915bb28cbc2e3aa028a2ee194738477eabcc413c65", size = 482014 }, - { url = "https://files.pythonhosted.org/packages/90/4a/0a9b2a817dd8fbd8212d9a5edd96f683eb4f3a5242618a2162bd424339dd/yarl-1.11.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:732d56da00ea7a5da4f0d15adbbd22dcb37da7825510aafde40112e53f6baa52", size = 512557 }, - { url = "https://files.pythonhosted.org/packages/27/12/68fefc9963099946919ca5347619958400902b83460c14068b2222fea07e/yarl-1.11.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:7bd54d79025b59d1dc5fb26a09734d6a9cc651a04bc381966ed264b28331a168", size = 514815 }, - { url = "https://files.pythonhosted.org/packages/af/97/71c0a9f3f028fdc5981c7c01c37d806611518a26deff1cda0107bdc98002/yarl-1.11.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:aacd62ff67efd54cb18cea2aa7ae4fb83cfbca19a07055d4777266b70561defe", size = 496917 }, - { url = "https://files.pythonhosted.org/packages/67/2e/df56566dca0d81cd23d4a168323b9145b4a1b3132d0a67f693de231d6213/yarl-1.11.0-cp311-cp311-win32.whl", hash = "sha256:68e14ae71e5b51c8282ae5db53ccb3baffc40e1551370a8a2361f1c1d8a0bf8c", size = 100817 }, - { url = "https://files.pythonhosted.org/packages/08/c2/d951e737c4ce9f31d5e55b5309db432bd35a33fb16bbccfbf3f82a0b0544/yarl-1.11.0-cp311-cp311-win_amd64.whl", hash = "sha256:3ade2265716667b6bd4123d6f684b5f7cf4a8d83dcf1d5581ac44643466bb00a", size = 110060 }, - { url = "https://files.pythonhosted.org/packages/2c/ef/afb63646e311b4b13a6751fcbb7628b8e935cba7a844d69e39f6d9ce5a7e/yarl-1.11.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:6e73dab98e3c3b5441720153e72a5f28e717aac2d22f1ec4b08ef33417d9987e", size = 188650 }, - { url = "https://files.pythonhosted.org/packages/32/31/fdac2a17133ee5e12ffc5c9266768fa05aa962e739ad35f39e9565a978f5/yarl-1.11.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:4a0d090d296ced05edfe29c6ff34869412fa6a97d0928c12b00939c4842884cd", size = 114472 }, - { url = "https://files.pythonhosted.org/packages/f8/f4/5c1e69c7bfc088a4389fc408fd09539e143edf10333b65c01f032c450131/yarl-1.11.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d29e446cfb0a82d3df7745968b9fa286665a9be8b4d68de46bcc32d917cb218e", size = 112332 }, - { url = "https://files.pythonhosted.org/packages/35/7f/2303b752846f4fb8ec53775545122aee5b854734d9c6d70fff4677ee05fe/yarl-1.11.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4c8dc0efcf8266ecfe057b95e01f43eb62516196a4bbf3918fd1dcb8d0dc0dff", size = 482463 }, - { url = "https://files.pythonhosted.org/packages/c3/71/c40f103724a7e3c4728a0f2952e95b31a4c7b9f101766f4c1e1fd022eb49/yarl-1.11.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:202f5ec49ff163dcc767426deb55020a28078e61d6bbe1f80331d92bca53b236", size = 498245 }, - { url = "https://files.pythonhosted.org/packages/f5/84/63d03c97b620f7a2b7e9c0cc28867db803d18843a0c3ff08ba9c570d904c/yarl-1.11.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8055b0d78ce1cafa657c4b455e22661e8d3b2834de66a0753c3567da47fcc4aa", size = 495761 }, - { url = "https://files.pythonhosted.org/packages/09/fa/9bf50e7c6dd7b1402ac8dc2ee5517f89b26b4df500914ef7600d09da1c74/yarl-1.11.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:60ed3c7f64e820959d7f682ec2f559b4f4df723dc09df619d269853a4214a4b4", size = 488688 }, - { url = "https://files.pythonhosted.org/packages/51/13/9bbd70849d0b1cd3ed5226b3844b8f185dc834a07081c874edfa4844a9fe/yarl-1.11.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2371510367d39d74997acfdcd1dead17938c79c99365482821627f7838a8eba0", size = 467864 }, - { url = "https://files.pythonhosted.org/packages/84/e3/d68f77ea24171e7eb09c1473aea38216fb52712c679691b4b5a6c68e0417/yarl-1.11.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:e24bb6a8be89ccc3ce8c47e8940fdfcb7429e9efbf65ce6fa3e7d122fcf0bcf0", size = 484168 }, - { url = "https://files.pythonhosted.org/packages/61/aa/a132bf6771efd523636998e1cc29d1e235aac1f0d94ec0dc57651973df34/yarl-1.11.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:18ec42da256cfcb9b4cd5d253e04c291f69911a5228d1438a7d431c15ba0ae40", size = 484541 }, - { url = "https://files.pythonhosted.org/packages/ff/60/7b7a3ab71f3df8d82888aac9f9b22097a72de79237ed3f06b86cb005b8b6/yarl-1.11.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:418eeb8f228ea36c368bf6782ebd6016ecebfb1a8b90145ef6726ffcbba65ef8", size = 505193 }, - { url = "https://files.pythonhosted.org/packages/0e/f7/b2714828dc249d915fe0dd9665fee73aac8e546b195308e0d531fe7d0a7b/yarl-1.11.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:07e8cfb1dd7669a129f8fd5df1da65efa73aea77582bde2a3a837412e2863543", size = 515538 }, - { url = "https://files.pythonhosted.org/packages/96/ea/6c7d34a0545ef449288c37607b5483f1a16f49f8dc723aed4013f01ea30f/yarl-1.11.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:3c458483711d393dad51340505c3fab3194748fd06bab311d2f8b5b7a7349e9a", size = 500875 }, - { url = "https://files.pythonhosted.org/packages/2d/8a/46785cee3bc1937c590c7176f140402b8eb8095c4b0bfb1fd46de47d70c7/yarl-1.11.0-cp312-cp312-win32.whl", hash = "sha256:5b008c3127382503e7a1e12b4c3a3236e3dd833a4c62a066f4a0fbd650c655d2", size = 100726 }, - { url = "https://files.pythonhosted.org/packages/b8/e6/f32b225643ee97b78809b7d55880fa69c834be47d3b19211dbd4dde223b6/yarl-1.11.0-cp312-cp312-win_amd64.whl", hash = "sha256:bc94be7472b9f88d7441340534a3ecae05c86ccfec7ba75ce5b6e4778b2bfc6e", size = 110098 }, - { url = "https://files.pythonhosted.org/packages/09/9c/b7d0f71112d2a8de7ea37a4e411364adfcbf679e7e8bd68a0cbf626e1021/yarl-1.11.0-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:a45e51ba3777031e0b20c1e7ab59114ed4e1884b3c1db48962c1d8d08aefb418", size = 184656 }, - { url = "https://files.pythonhosted.org/packages/8d/7f/a9add68784a938e578bd691203329cea2967fcf00c412a6ec00f3d9393aa/yarl-1.11.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:765128029218eade3a01187cdd7f375977cc827505ed31828196c8ae9b622928", size = 112659 }, - { url = "https://files.pythonhosted.org/packages/d2/ce/13b5bdd1187e1deae9efec2d64cecacb5287657fb570fc47da11d316f1a8/yarl-1.11.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:2516e238daf0339c8ac4dfab9d7cda9afad652ff073517f200d653d5d8371f7e", size = 110556 }, - { url = "https://files.pythonhosted.org/packages/73/cb/b27b1be50db78559ad9e1a871fec121a9008d95577480fd7ba491ea6a0ac/yarl-1.11.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d10be62bee117f05b1ad75a6c2538ca9e5367342dc8a4f3c206c87dadbc1189c", size = 469941 }, - { url = "https://files.pythonhosted.org/packages/85/9b/e969d4fa91b18f81076169efae00b54ad2cb642d24f66b980eded9f7913d/yarl-1.11.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:50ceaeda771ee3e382291168c90c7ede62b63ecf3e181024bcfeb35c0ea6c84f", size = 484373 }, - { url = "https://files.pythonhosted.org/packages/1d/88/8500d9dda26f8df114dd78a2230cdd510178c1bf54ac294c9209d666440f/yarl-1.11.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3a601c99fc20fd0eea84e7bc0dc9e7f196f55a0ded67242d724988c754295538", size = 485179 }, - { url = "https://files.pythonhosted.org/packages/b3/e5/b0c46b9e55959d6d0918dcf32eb7c0c4e4cd750990830740a91e86a65897/yarl-1.11.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:42ff79371614764fc0a4ab8eaba9adb493bf9ad856e2a4664f6c754fc907a903", size = 477399 }, - { url = "https://files.pythonhosted.org/packages/74/46/fad292dacca81b54cd9e032ea8cd2effab995c5294c0b9f2d5aadc139d43/yarl-1.11.0-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:93fca4c9f88c17ead902b3f3285b2d039fc8f26d117e1441973ba64315109b54", size = 454973 }, - { url = "https://files.pythonhosted.org/packages/50/17/a0b79bf596175691a7b8cf3918e430d386b206d0dec875d9af03103fd82a/yarl-1.11.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:e7dddf5f41395c84fc59e0ed5493b24bfeb39fb04823e880b52c8c55085d4695", size = 473497 }, - { url = "https://files.pythonhosted.org/packages/2d/55/ad4dbf1861d4677b931d9c433940441a3b152d78ee3c2fc256d01a1734b0/yarl-1.11.0-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:ea501ea07e14ba6364ff2621bfc8b2381e5b1e10353927fa9a607057fd2b98e5", size = 476002 }, - { url = "https://files.pythonhosted.org/packages/a1/8d/506fd44cfdcd70a88bf4639eede14f38814a0e87fb3525b1adc407c4dacc/yarl-1.11.0-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:a4f7e470f2c9c8b8774a5bda72adfb8e9dc4ec32311fe9bdaa4921e36cf6659b", size = 490486 }, - { url = "https://files.pythonhosted.org/packages/e0/8c/618f4f425746d4c1551d488e66c6a9b51e517088871464a6a567506794df/yarl-1.11.0-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:361fdb3993431157302b7104d525092b5df4d7d346df5a5ffeee2d1ca8e0d15b", size = 500692 }, - { url = "https://files.pythonhosted.org/packages/dd/98/370d73e15e56bd825192c90d4c269c6d4b6030eecfe9a11d35aefa3eda28/yarl-1.11.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:e300eaf5e0329ad31b3d53e2f3d26b4b6dff1217207c6ab1d4212967b54b2185", size = 491380 }, - { url = "https://files.pythonhosted.org/packages/81/c0/2c0578852fdc767bced8be44e554cb573e1dc54c6cee5720cfbd40ce4134/yarl-1.11.0-cp313-cp313-win32.whl", hash = "sha256:f1e2d4ce72e06e38a16da3e9c24a0520dbc19018a69ef6ed57b6b38527cb275c", size = 484844 }, - { url = "https://files.pythonhosted.org/packages/7e/a8/9ac6108837df19e46583cde169e20d69c68fbbe26dab8cedae53e41e2c69/yarl-1.11.0-cp313-cp313-win_amd64.whl", hash = "sha256:fa9de2f87be58f714a230bd1f3ef3aad1ed65c9931146e3fc55f85fcbe6bacc3", size = 492185 }, - { url = "https://files.pythonhosted.org/packages/f1/37/f3a2f78f3174d0150257dff57b4b81c562ef1648d0eba4acbe333b534317/yarl-1.11.0-py3-none-any.whl", hash = "sha256:03717a6627e55934b2a1d9caf24f299b461a2e8d048a90920f42ad5c20ae1b82", size = 38246 }, +sdist = { url = "https://files.pythonhosted.org/packages/e4/3d/4924f9ed49698bac5f112bc9b40aa007bbdcd702462c1df3d2e1383fb158/yarl-1.11.1.tar.gz", hash = "sha256:1bb2d9e212fb7449b8fb73bc461b51eaa17cc8430b4a87d87be7b25052d92f53", size = 162095 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/af/f1/f3e6be722461cab1e7c6aea657685897956d6e4743940d685d167914e31c/yarl-1.11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:946eedc12895873891aaceb39bceb484b4977f70373e0122da483f6c38faaa68", size = 188410 }, + { url = "https://files.pythonhosted.org/packages/4b/c1/21cc66b263fdc2ec10b6459aed5b239f07eed91a77438d88f0e1bd70e202/yarl-1.11.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:21a7c12321436b066c11ec19c7e3cb9aec18884fe0d5b25d03d756a9e654edfe", size = 114293 }, + { url = "https://files.pythonhosted.org/packages/31/7a/0ecab63a166a22357772f4a2852c859e2d5a7b02a5c58803458dd516e6b4/yarl-1.11.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c35f493b867912f6fda721a59cc7c4766d382040bdf1ddaeeaa7fa4d072f4675", size = 112548 }, + { url = "https://files.pythonhosted.org/packages/57/5d/78152026864475e841fdae816499345364c8e364b45ea6accd0814a295f0/yarl-1.11.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:25861303e0be76b60fddc1250ec5986c42f0a5c0c50ff57cc30b1be199c00e63", size = 485002 }, + { url = "https://files.pythonhosted.org/packages/d3/70/2e880d74aeb4908d45c6403e46bbd4aa866ae31ddb432318d9b8042fe0f6/yarl-1.11.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e4b53f73077e839b3f89c992223f15b1d2ab314bdbdf502afdc7bb18e95eae27", size = 504850 }, + { url = "https://files.pythonhosted.org/packages/06/58/5676a47b6d2751853f89d1d68b6a54d725366da6a58482f2410fa7eb38af/yarl-1.11.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:327c724b01b8641a1bf1ab3b232fb638706e50f76c0b5bf16051ab65c868fac5", size = 499291 }, + { url = "https://files.pythonhosted.org/packages/4d/e5/b56d535703a63a8d86ac82059e630e5ba9c0d5626d9c5ac6af53eed815c2/yarl-1.11.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4307d9a3417eea87715c9736d050c83e8c1904e9b7aada6ce61b46361b733d92", size = 487818 }, + { url = "https://files.pythonhosted.org/packages/f3/b4/6b95e1e0983593f4145518980b07126a27e2a4938cb6afb8b592ce6fc2c9/yarl-1.11.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:48a28bed68ab8fb7e380775f0029a079f08a17799cb3387a65d14ace16c12e2b", size = 470447 }, + { url = "https://files.pythonhosted.org/packages/a8/e5/5d349b7b04ed4247d4f717f271fce601a79d10e2ac81166c13f97c4973a9/yarl-1.11.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:067b961853c8e62725ff2893226fef3d0da060656a9827f3f520fb1d19b2b68a", size = 484544 }, + { url = "https://files.pythonhosted.org/packages/fa/dc/ce90e9d85ef2233e81148a9658e4ea8372c6de070ce96c5c8bd3ff365144/yarl-1.11.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:8215f6f21394d1f46e222abeb06316e77ef328d628f593502d8fc2a9117bde83", size = 482409 }, + { url = "https://files.pythonhosted.org/packages/4c/a1/17c0a03615b0cd213aee2e318a0fbd3d07259c37976d85af9eec6184c589/yarl-1.11.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:498442e3af2a860a663baa14fbf23fb04b0dd758039c0e7c8f91cb9279799bff", size = 512970 }, + { url = "https://files.pythonhosted.org/packages/6c/ed/1e317799d54c79a3e4846db597510f5c84fb7643bb8703a3848136d40809/yarl-1.11.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:69721b8effdb588cb055cc22f7c5105ca6fdaa5aeb3ea09021d517882c4a904c", size = 515203 }, + { url = "https://files.pythonhosted.org/packages/7a/37/9a4e2d73953956fa686fa0f0c4a0881245f39423fa75875d981b4f680611/yarl-1.11.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1e969fa4c1e0b1a391f3fcbcb9ec31e84440253325b534519be0d28f4b6b533e", size = 497323 }, + { url = "https://files.pythonhosted.org/packages/a3/c3/a25ae9c85c0e50a8722aecc486ac5ba53b28d1384548df99b2145cb69862/yarl-1.11.1-cp311-cp311-win32.whl", hash = "sha256:7d51324a04fc4b0e097ff8a153e9276c2593106a811704025bbc1d6916f45ca6", size = 101226 }, + { url = "https://files.pythonhosted.org/packages/90/6d/c62ba0ae0232a0b0012706a7735a16b44a03216fedfb6ea0bcda79d1e12c/yarl-1.11.1-cp311-cp311-win_amd64.whl", hash = "sha256:15061ce6584ece023457fb8b7a7a69ec40bf7114d781a8c4f5dcd68e28b5c53b", size = 110471 }, + { url = "https://files.pythonhosted.org/packages/3b/05/379002019a0c9d5dc0c4cc6f71e324ea43461ae6f58e94ee87e07b8ffa90/yarl-1.11.1-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:a4264515f9117be204935cd230fb2a052dd3792789cc94c101c535d349b3dab0", size = 189044 }, + { url = "https://files.pythonhosted.org/packages/23/d5/e62cfba5ceaaf92ee4f9af6f9c9ab2f2b47d8ad48687fa69570a93b0872c/yarl-1.11.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:f41fa79114a1d2eddb5eea7b912d6160508f57440bd302ce96eaa384914cd265", size = 114867 }, + { url = "https://files.pythonhosted.org/packages/b1/10/6abc0bd7e7fe7c6b9b9e9ce0ff558912c9ecae65a798f5442020ef9e4177/yarl-1.11.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:02da8759b47d964f9173c8675710720b468aa1c1693be0c9c64abb9d8d9a4867", size = 112737 }, + { url = "https://files.pythonhosted.org/packages/37/a5/ad026afde5efe1849f4f55bd9f9a2cb5b006511b324db430ae5336104fb3/yarl-1.11.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9361628f28f48dcf8b2f528420d4d68102f593f9c2e592bfc842f5fb337e44fd", size = 482887 }, + { url = "https://files.pythonhosted.org/packages/f8/82/b8bee972617b800319b4364cfcd69bfaf7326db052e91a56e63986cc3e05/yarl-1.11.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b91044952da03b6f95fdba398d7993dd983b64d3c31c358a4c89e3c19b6f7aef", size = 498635 }, + { url = "https://files.pythonhosted.org/packages/af/ad/ac688503b134e02e8505415f0b8e94dc8e92a97e82abdd9736658389b5ae/yarl-1.11.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:74db2ef03b442276d25951749a803ddb6e270d02dda1d1c556f6ae595a0d76a8", size = 496198 }, + { url = "https://files.pythonhosted.org/packages/ce/f2/b6cae0ad1afed6e95f82ab2cb9eb5b63e41f1463ece2a80c39d80cf6167a/yarl-1.11.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7e975a2211952a8a083d1b9d9ba26472981ae338e720b419eb50535de3c02870", size = 489068 }, + { url = "https://files.pythonhosted.org/packages/c8/f4/355e69b5563154b40550233ffba8f6099eac0c99788600191967763046cf/yarl-1.11.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8aef97ba1dd2138112890ef848e17d8526fe80b21f743b4ee65947ea184f07a2", size = 468286 }, + { url = "https://files.pythonhosted.org/packages/26/3d/3c37f3f150faf87b086f7915724f2fcb9ff2f7c9d3f6c0f42b7722bd9b77/yarl-1.11.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:a7915ea49b0c113641dc4d9338efa9bd66b6a9a485ffe75b9907e8573ca94b84", size = 484568 }, + { url = "https://files.pythonhosted.org/packages/94/ee/d591abbaea3b14e0f68bdec5cbcb75f27107190c51889d518bafe5d8f120/yarl-1.11.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:504cf0d4c5e4579a51261d6091267f9fd997ef58558c4ffa7a3e1460bd2336fa", size = 484947 }, + { url = "https://files.pythonhosted.org/packages/57/70/ad1c65a13315f03ff0c63fd6359dd40d8198e2a42e61bf86507602a0364f/yarl-1.11.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:3de5292f9f0ee285e6bd168b2a77b2a00d74cbcfa420ed078456d3023d2f6dff", size = 505610 }, + { url = "https://files.pythonhosted.org/packages/4c/8c/6086dec0f8d7df16d136b38f373c49cf3d2fb94464e5a10bf788b36f3f54/yarl-1.11.1-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:a34e1e30f1774fa35d37202bbeae62423e9a79d78d0874e5556a593479fdf239", size = 515951 }, + { url = "https://files.pythonhosted.org/packages/49/79/e0479e9a3bbb7bdcb82779d89711b97cea30902a4bfe28d681463b7071ce/yarl-1.11.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:66b63c504d2ca43bf7221a1f72fbe981ff56ecb39004c70a94485d13e37ebf45", size = 501273 }, + { url = "https://files.pythonhosted.org/packages/8e/85/eab962453e81073276b22f3d1503dffe6bfc3eb9cd0f31899970de05d490/yarl-1.11.1-cp312-cp312-win32.whl", hash = "sha256:a28b70c9e2213de425d9cba5ab2e7f7a1c8ca23a99c4b5159bf77b9c31251447", size = 101139 }, + { url = "https://files.pythonhosted.org/packages/5d/de/618b3e5cab10af8a2ed3eb625dac61c1d16eb155d1f56f9fdb3500786c12/yarl-1.11.1-cp312-cp312-win_amd64.whl", hash = "sha256:17b5a386d0d36fb828e2fb3ef08c8829c1ebf977eef88e5367d1c8c94b454639", size = 110504 }, + { url = "https://files.pythonhosted.org/packages/07/b7/948e4f427817e0178f3737adf6712fea83f76921e11e2092f403a8a9dc4a/yarl-1.11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:1fa2e7a406fbd45b61b4433e3aa254a2c3e14c4b3186f6e952d08a730807fa0c", size = 185061 }, + { url = "https://files.pythonhosted.org/packages/f3/67/8d91ad79a3b907b4fef27fafa912350554443ba53364fff3c347b41105cb/yarl-1.11.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:750f656832d7d3cb0c76be137ee79405cc17e792f31e0a01eee390e383b2936e", size = 113056 }, + { url = "https://files.pythonhosted.org/packages/a1/77/6b2348a753702fa87f435cc33dcec21981aaca8ef98a46566a7b29940b4a/yarl-1.11.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:0b8486f322d8f6a38539136a22c55f94d269addb24db5cb6f61adc61eabc9d93", size = 110958 }, + { url = "https://files.pythonhosted.org/packages/8e/3e/6eadf32656741549041f549a392f3b15245d3a0a0b12a9bc22bd6b69621f/yarl-1.11.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3fce4da3703ee6048ad4138fe74619c50874afe98b1ad87b2698ef95bf92c96d", size = 470326 }, + { url = "https://files.pythonhosted.org/packages/3d/a4/1b641a8c7899eeaceec45ff105a2e7206ec0eb0fb9d86403963cc8521c5e/yarl-1.11.1-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8ed653638ef669e0efc6fe2acb792275cb419bf9cb5c5049399f3556995f23c7", size = 484778 }, + { url = "https://files.pythonhosted.org/packages/8a/f5/80c142f34779a5c26002b2bf1f73b9a9229aa9e019ee6f9fd9d3e9704e78/yarl-1.11.1-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:18ac56c9dd70941ecad42b5a906820824ca72ff84ad6fa18db33c2537ae2e089", size = 485568 }, + { url = "https://files.pythonhosted.org/packages/f8/f2/6b40ffea2d5d3a11f514ab23c30d14f52600c36a3210786f5974b6701bb8/yarl-1.11.1-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:688654f8507464745ab563b041d1fb7dab5d9912ca6b06e61d1c4708366832f5", size = 477801 }, + { url = "https://files.pythonhosted.org/packages/4c/1a/e60c116f3241e4842ed43c104eb2751abe02f6bac0301cdae69e4fda9c3a/yarl-1.11.1-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4973eac1e2ff63cf187073cd4e1f1148dcd119314ab79b88e1b3fad74a18c9d5", size = 455361 }, + { url = "https://files.pythonhosted.org/packages/b9/98/fe0aeee425a4bc5cd3ed86e867661d2bfa782544fa07a8e3dcd97d51ae3d/yarl-1.11.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:964a428132227edff96d6f3cf261573cb0f1a60c9a764ce28cda9525f18f7786", size = 473893 }, + { url = "https://files.pythonhosted.org/packages/6b/9b/677455d146bd3cecd350673f0e4bb28854af66726493ace3b640e9c5552b/yarl-1.11.1-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:6d23754b9939cbab02c63434776df1170e43b09c6a517585c7ce2b3d449b7318", size = 476407 }, + { url = "https://files.pythonhosted.org/packages/33/ca/ce85766247a9a9b56654428fb78a3e14ea6947a580a9c4e891b3aa7da322/yarl-1.11.1-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:c2dc4250fe94d8cd864d66018f8344d4af50e3758e9d725e94fecfa27588ff82", size = 490848 }, + { url = "https://files.pythonhosted.org/packages/6d/d6/717f0f19bcf2c4705ad95550b4b6319a0d8d1d4f137ea5e223207f00df50/yarl-1.11.1-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:09696438cb43ea6f9492ef237761b043f9179f455f405279e609f2bc9100212a", size = 501084 }, + { url = "https://files.pythonhosted.org/packages/14/b5/b93c70d9a462b802c8df65c64b85f49d86b4ba70c393fbad95cf7ec053cb/yarl-1.11.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:999bfee0a5b7385a0af5ffb606393509cfde70ecca4f01c36985be6d33e336da", size = 491776 }, + { url = "https://files.pythonhosted.org/packages/03/0f/5a52eaa402a6a93265ba82f42c6f6085ccbe483e1b058ad34207e75812b1/yarl-1.11.1-cp313-cp313-win32.whl", hash = "sha256:ce928c9c6409c79e10f39604a7e214b3cb69552952fbda8d836c052832e6a979", size = 485250 }, + { url = "https://files.pythonhosted.org/packages/dd/97/946d26a5d82706a6769399cabd472c59f9a3227ce1432afb4739b9c29572/yarl-1.11.1-cp313-cp313-win_amd64.whl", hash = "sha256:501c503eed2bb306638ccb60c174f856cc3246c861829ff40eaa80e2f0330367", size = 492590 }, + { url = "https://files.pythonhosted.org/packages/5b/b3/841f7d706137bdc8b741c6826106b6f703155076d58f1830f244da857451/yarl-1.11.1-py3-none-any.whl", hash = "sha256:72bf26f66456baa0584eff63e44545c9f0eaed9b73cb6601b647c91f14c11f38", size = 38648 }, ] [[package]] From d414f8c3b6a4243b2d0d529aad512ae57a2d24fb Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 12 Sep 2024 17:18:34 -0700 Subject: [PATCH 053/214] log alertDebug to qlog --- cereal/services.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal/services.py b/cereal/services.py index d94c3f11fb..40d9b38c05 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -75,7 +75,7 @@ _services: dict[str, tuple] = { # debug "uiDebug": (True, 0., 1), - "alertDebug": (True, 0.), + "alertDebug": (True, 0., 1.), "roadEncodeData": (False, 20.), "driverEncodeData": (False, 20.), "wideRoadEncodeData": (False, 20.), From 5fc79bda64717c9c018794e72f21d5fb517fdbd7 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 12 Sep 2024 17:34:12 -0700 Subject: [PATCH 054/214] decimate alertDebug (#33550) * decimate alertDebug * int --- cereal/services.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal/services.py b/cereal/services.py index 40d9b38c05..e56f8f0c1b 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -75,7 +75,7 @@ _services: dict[str, tuple] = { # debug "uiDebug": (True, 0., 1), - "alertDebug": (True, 0., 1.), + "alertDebug": (True, 20., 5), "roadEncodeData": (False, 20.), "driverEncodeData": (False, 20.), "wideRoadEncodeData": (False, 20.), From 03ea2b180faa0521e7ab48b9e87881058940d11c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 12 Sep 2024 20:25:22 -0700 Subject: [PATCH 055/214] longitudinal maneuver report improvements (#33551) * switch to route name * add car params and relative time * separate plots, easier to read --- .../longitudinal_maneuvers/generate_report.py | 23 ++++++++++++++----- 1 file changed, 17 insertions(+), 6 deletions(-) diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py index 262ea93ef3..b3ab8d9a7a 100755 --- a/tools/longitudinal_maneuvers/generate_report.py +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -3,7 +3,7 @@ import argparse import base64 import io import os -import time +import json from pathlib import Path import matplotlib.pyplot as plt @@ -11,15 +11,21 @@ from openpilot.tools.lib.logreader import LogReader from openpilot.system.hardware.hw import Paths -def report(platform, maneuvers): +def format_car_params(CP): + return json.dumps({k: v for k, v in CP.to_dict().items() if not k.endswith('DEPRECATED')}, indent=2) + + +def report(platform, route, CP, maneuvers): output_path = Path(__file__).resolve().parent / "longitudinal_reports" - output_fn = output_path / f"{platform}_{time.strftime('%Y%m%d-%H_%M_%S')}.html" + output_fn = output_path / f"{platform}_{route}.html" output_path.mkdir(exist_ok=True) with open(output_fn, "w") as f: f.write("

Longitudinal maneuver report

\n") f.write(f"

{platform}

\n") + f.write(f"

{route}

\n") + f.write(f"

CarParams

{format_car_params(CP)}
\n") for description, runs in maneuvers: - print('plotting maneuver:', description, 'runs:', len(runs)) + print(f'plotting maneuver: {description}, runs: {len(runs)}') f.write("
\n") f.write(f"

{description}

\n") for run, msgs in enumerate(runs): @@ -28,6 +34,11 @@ def report(platform, maneuvers): t_carState, carState = zip(*[(m.logMonoTime, m.carState) for m in msgs if m.which() == 'carState'], strict=True) t_longitudinalPlan, longitudinalPlan = zip(*[(m.logMonoTime, m.longitudinalPlan) for m in msgs if m.which() == 'longitudinalPlan'], strict=True) + t_carControl = [(t - t_carControl[0]) / 1e9 for t in t_carControl] + t_carOutput = [(t - t_carOutput[0]) / 1e9 for t in t_carOutput] + t_carState = [(t - t_carState[0]) / 1e9 for t in t_carState] + t_longitudinalPlan = [(t - t_longitudinalPlan[0]) / 1e9 for t in t_longitudinalPlan] + longActive = [m.longActive for m in carControl] gasPressed = [m.gasPressed for m in carState] brakePressed = [m.brakePressed for m in carState] @@ -41,7 +52,7 @@ def report(platform, maneuvers): plt.rcParams['font.size'] = 40 fig = plt.figure(figsize=(30, 25)) - ax = fig.subplots(4, 1, sharex=True, gridspec_kw={'hspace': 0, 'height_ratios': [5, 3, 1, 1]}) + ax = fig.subplots(4, 1, sharex=True, gridspec_kw={'height_ratios': [5, 3, 1, 1]}) ax[0].grid(linewidth=4) ax[0].plot(t_carControl, [m.actuators.accel for m in carControl], label='carControl.actuators.accel', linewidth=6) @@ -112,4 +123,4 @@ if __name__ == '__main__': if active_prev: maneuvers[-1][1][-1].append(msg) - report(platform, maneuvers) + report(platform, args.route, CP, maneuvers) From f89b59baa88ec5a2e3512bb18d7cdb985e9155c3 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 12 Sep 2024 21:17:28 -0700 Subject: [PATCH 056/214] Long maneuver report markers (#33552) * check for overrides as well * only used twice * longActive is false for gas pressed * label cross time * love pycharm --- .../longitudinal_maneuvers/generate_report.py | 35 +++++++++++++------ tools/longitudinal_maneuvers/maneuversd.py | 9 +++-- 2 files changed, 29 insertions(+), 15 deletions(-) diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py index b3ab8d9a7a..1592a97d65 100755 --- a/tools/longitudinal_maneuvers/generate_report.py +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -3,7 +3,7 @@ import argparse import base64 import io import os -import json +import pprint from pathlib import Path import matplotlib.pyplot as plt @@ -12,12 +12,12 @@ from openpilot.system.hardware.hw import Paths def format_car_params(CP): - return json.dumps({k: v for k, v in CP.to_dict().items() if not k.endswith('DEPRECATED')}, indent=2) + return pprint.pformat({k: v for k, v in CP.to_dict().items() if not k.endswith('DEPRECATED')}, indent=2) def report(platform, route, CP, maneuvers): output_path = Path(__file__).resolve().parent / "longitudinal_reports" - output_fn = output_path / f"{platform}_{route}.html" + output_fn = output_path / f"{platform}_{route.replace('/', '_')}.html" output_path.mkdir(exist_ok=True) with open(output_fn, "w") as f: f.write("

Longitudinal maneuver report

\n") @@ -34,24 +34,36 @@ def report(platform, route, CP, maneuvers): t_carState, carState = zip(*[(m.logMonoTime, m.carState) for m in msgs if m.which() == 'carState'], strict=True) t_longitudinalPlan, longitudinalPlan = zip(*[(m.logMonoTime, m.longitudinalPlan) for m in msgs if m.which() == 'longitudinalPlan'], strict=True) + # make time relative seconds t_carControl = [(t - t_carControl[0]) / 1e9 for t in t_carControl] t_carOutput = [(t - t_carOutput[0]) / 1e9 for t in t_carOutput] t_carState = [(t - t_carState[0]) / 1e9 for t in t_carState] t_longitudinalPlan = [(t - t_longitudinalPlan[0]) / 1e9 for t in t_longitudinalPlan] + # maneuver validity longActive = [m.longActive for m in carControl] - gasPressed = [m.gasPressed for m in carState] - brakePressed = [m.brakePressed for m in carState] - - maneuver_valid = all(longActive) and not (any(gasPressed) or any(brakePressed)) + maneuver_valid = all(longActive) _open = 'open' if maneuver_valid else '' title = f'Run #{int(run)+1}' + (' (invalid maneuver!)' if not maneuver_valid else '') f.write(f"

{title}

\n") + # get first acceleration target and first intersection + aTarget = longitudinalPlan[0].aTarget + target_cross_time = None + f.write(f'

Initial aTarget: {aTarget} m/s^2') + for t, cs in zip(t_carState, carState, strict=True): + if (0 < aTarget < cs.aEgo) or (0 > aTarget > cs.aEgo): + f.write(f', crossed in {t:.3f}s') + target_cross_time = t + break + else: + f.write(', not crossed') + f.write('

') + plt.rcParams['font.size'] = 40 - fig = plt.figure(figsize=(30, 25)) + fig = plt.figure(figsize=(30, 26)) ax = fig.subplots(4, 1, sharex=True, gridspec_kw={'height_ratios': [5, 3, 1, 1]}) ax[0].grid(linewidth=4) @@ -64,14 +76,17 @@ def report(platform, route, CP, maneuvers): #ax[0].set_ylim(-6.5, 6.5) ax[0].legend() + if target_cross_time is not None: + ax[0].plot(target_cross_time, aTarget, marker='o', markersize=50, markeredgewidth=7, markeredgecolor='black', markerfacecolor='None') + ax[1].grid(linewidth=4) ax[1].plot(t_carState, [m.vEgo for m in carState], 'g', label='vEgo', linewidth=6) ax[1].set_ylabel('Velocity (m/s)') ax[1].legend() ax[2].plot(t_carControl, longActive, label='longActive', linewidth=6) - ax[3].plot(t_carState, gasPressed, label='gasPressed', linewidth=6) - ax[3].plot(t_carState, brakePressed, label='brakePressed', linewidth=6) + ax[3].plot(t_carState, [m.gasPressed for m in carState], label='gasPressed', linewidth=6) + ax[3].plot(t_carState, [m.brakePressed for m in carState], label='brakePressed', linewidth=6) for i in (2, 3): ax[i].set_yticks([0, 1], minor=False) ax[i].set_ylim(-1, 2) diff --git a/tools/longitudinal_maneuvers/maneuversd.py b/tools/longitudinal_maneuvers/maneuversd.py index 30304a37c2..15f0c7a4e8 100755 --- a/tools/longitudinal_maneuvers/maneuversd.py +++ b/tools/longitudinal_maneuvers/maneuversd.py @@ -28,8 +28,8 @@ class Maneuver: _ready_cnt: int = 0 _repeated: int = 0 - def get_accel(self, v_ego: float, enabled: bool, standstill: bool) -> float: - ready = abs(v_ego - self.initial_speed) < 0.3 and enabled and not standstill + def get_accel(self, v_ego: float, long_active: bool, standstill: bool) -> float: + ready = abs(v_ego - self.initial_speed) < 0.3 and long_active and not standstill self._ready_cnt = (self._ready_cnt + 1) if ready else 0 if self._ready_cnt > (3. / DT_MDL): @@ -132,11 +132,10 @@ def main(): longitudinalPlan = plan_send.longitudinalPlan accel = 0 - cs = sm['carState'] - v_ego = max(cs.vEgo, 0) + v_ego = max(sm['carState'].vEgo, 0) if maneuver is not None: - accel = maneuver.get_accel(v_ego, cs.cruiseState.enabled, cs.cruiseState.standstill) + accel = maneuver.get_accel(v_ego, sm['carControl'].longActive, sm['carState'].cruiseState.standstill) if maneuver.active: alert_msg.alertDebug.alertText1 = f'Maneuver Active: {accel:0.2f} m/s^2' From fa892a97557d119a75e2b1c442f1eec8bc4ac015 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 12 Sep 2024 22:29:00 -0700 Subject: [PATCH 057/214] Simple longitudinal maneuver summary (#33553) * check for overrides as well * only used twice * longActive is false for gas pressed * label cross time * love pycharm * quick summary * add min/max * show unreached maneuvers --- tools/longitudinal_maneuvers/generate_report.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py index 1592a97d65..88f78416b4 100755 --- a/tools/longitudinal_maneuvers/generate_report.py +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -4,6 +4,7 @@ import base64 import io import os import pprint +from collections import defaultdict from pathlib import Path import matplotlib.pyplot as plt @@ -19,6 +20,7 @@ def report(platform, route, CP, maneuvers): output_path = Path(__file__).resolve().parent / "longitudinal_reports" output_fn = output_path / f"{platform}_{route.replace('/', '_')}.html" output_path.mkdir(exist_ok=True) + target_cross_times = defaultdict(list) with open(output_fn, "w") as f: f.write("

Longitudinal maneuver report

\n") f.write(f"

{platform}

\n") @@ -57,6 +59,8 @@ def report(platform, route, CP, maneuvers): if (0 < aTarget < cs.aEgo) or (0 > aTarget > cs.aEgo): f.write(f', crossed in {t:.3f}s') target_cross_time = t + if maneuver_valid: + target_cross_times[description].append(t) break else: f.write(', not crossed') @@ -101,6 +105,14 @@ def report(platform, route, CP, maneuvers): f.write(f"\n") f.write("
\n") + f.write("

Summary

\n") + for description, runs in maneuvers: + times = target_cross_times[description] + f.write(f"

{description}

\n") + f.write(f"

Target crossed {len(times)} out of {len(runs)} runs

\n") + if len(times): + f.write(f"

Mean time to cross: {sum(times) / len(times):.3f}s, min: {min(times):.3f}s, max: {max(times):.3f}s

\n") + print(f"\nReport written to {output_fn}\n") From 50b0089602bbc0f600d360c40d3fb307579b41f8 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 14 Sep 2024 02:13:47 +0800 Subject: [PATCH 058/214] panda: using reference in loop (#33554) using reference in loop --- selfdrive/pandad/panda.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/pandad/panda.cc b/selfdrive/pandad/panda.cc index bc81d7de91..4376d85795 100644 --- a/selfdrive/pandad/panda.cc +++ b/selfdrive/pandad/panda.cc @@ -47,7 +47,7 @@ std::vector Panda::list(bool usb_only) { #ifndef __APPLE__ if (!usb_only) { - for (auto s : PandaSpiHandle::list()) { + for (const auto &s : PandaSpiHandle::list()) { if (std::find(serials.begin(), serials.end(), s) == serials.end()) { serials.push_back(s); } @@ -169,7 +169,7 @@ void Panda::pack_can_buffer(const capnp::List::Reader &can_data int32_t pos = 0; uint8_t send_buf[2 * USB_TX_SOFT_LIMIT]; - for (auto cmsg : can_data_list) { + for (const auto &cmsg : can_data_list) { // check if the message is intended for this panda uint8_t bus = cmsg.getSrc(); if (bus < bus_offset || bus >= (bus_offset + PANDA_BUS_OFFSET)) { From 4897c9821dc71884a392ca5fca209fd7d0e2d3eb Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 14 Sep 2024 02:13:59 +0800 Subject: [PATCH 059/214] panda.cc: pass capnp list by reference (#33555) pass by reference --- selfdrive/pandad/panda.cc | 2 +- selfdrive/pandad/panda.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/pandad/panda.cc b/selfdrive/pandad/panda.cc index 4376d85795..5372e54aef 100644 --- a/selfdrive/pandad/panda.cc +++ b/selfdrive/pandad/panda.cc @@ -206,7 +206,7 @@ void Panda::pack_can_buffer(const capnp::List::Reader &can_data if (pos > 0) write_func(send_buf, pos); } -void Panda::can_send(capnp::List::Reader can_data_list) { +void Panda::can_send(const capnp::List::Reader &can_data_list) { pack_can_buffer(can_data_list, [=](uint8_t* data, size_t size) { handle->bulk_write(3, data, size, 5); }); diff --git a/selfdrive/pandad/panda.h b/selfdrive/pandad/panda.h index 26ad4dc32c..af31c2316e 100644 --- a/selfdrive/pandad/panda.h +++ b/selfdrive/pandad/panda.h @@ -79,7 +79,7 @@ public: void set_can_speed_kbps(uint16_t bus, uint16_t speed); void set_data_speed_kbps(uint16_t bus, uint16_t speed); void set_canfd_non_iso(uint16_t bus, bool non_iso); - void can_send(capnp::List::Reader can_data_list); + void can_send(const capnp::List::Reader &can_data_list); bool can_receive(std::vector& out_vec); void can_reset_communications(); From 3da5ddae71ad8d7c1637653646532219d90cb39d Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 13 Sep 2024 14:47:04 -0700 Subject: [PATCH 060/214] fix maneuversd.py --- tools/longitudinal_maneuvers/maneuversd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/longitudinal_maneuvers/maneuversd.py b/tools/longitudinal_maneuvers/maneuversd.py index 15f0c7a4e8..892d58da00 100755 --- a/tools/longitudinal_maneuvers/maneuversd.py +++ b/tools/longitudinal_maneuvers/maneuversd.py @@ -112,7 +112,7 @@ def main(): cloudlog.info("joystickd is waiting for CarParams") CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) - sm = messaging.SubMaster(['carState', 'controlsState', 'selfdriveState', 'modelV2'], poll='modelV2') + sm = messaging.SubMaster(['carState', 'carControl', 'controlsState', 'selfdriveState', 'modelV2'], poll='modelV2') pm = messaging.PubMaster(['longitudinalPlan', 'driverAssistance', 'alertDebug']) maneuvers = iter(MANEUVERS) From 6ec603872b9c4e73cf3e377e6060c75605cb199d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 13 Sep 2024 15:58:00 -0700 Subject: [PATCH 061/214] long maneuvers: add start from stop (#33556) * long maneuvers: add start from stop * fix * git ignore --- tools/longitudinal_maneuvers/.gitignore | 1 + tools/longitudinal_maneuvers/maneuversd.py | 16 ++++++++++++---- 2 files changed, 13 insertions(+), 4 deletions(-) create mode 100644 tools/longitudinal_maneuvers/.gitignore diff --git a/tools/longitudinal_maneuvers/.gitignore b/tools/longitudinal_maneuvers/.gitignore new file mode 100644 index 0000000000..e819fa6268 --- /dev/null +++ b/tools/longitudinal_maneuvers/.gitignore @@ -0,0 +1 @@ +/longitudinal_reports/ diff --git a/tools/longitudinal_maneuvers/maneuversd.py b/tools/longitudinal_maneuvers/maneuversd.py index 892d58da00..5096c19a0b 100755 --- a/tools/longitudinal_maneuvers/maneuversd.py +++ b/tools/longitudinal_maneuvers/maneuversd.py @@ -28,8 +28,10 @@ class Maneuver: _ready_cnt: int = 0 _repeated: int = 0 - def get_accel(self, v_ego: float, long_active: bool, standstill: bool) -> float: - ready = abs(v_ego - self.initial_speed) < 0.3 and long_active and not standstill + def get_accel(self, v_ego: float, long_active: bool, standstill: bool, cruise_standstill: bool) -> float: + ready = abs(v_ego - self.initial_speed) < 0.3 and long_active and not cruise_standstill + if self.initial_speed < 0.01: + ready = v_ego < 0.1 and standstill self._ready_cnt = (self._ready_cnt + 1) if ready else 0 if self._ready_cnt > (3. / DT_MDL): @@ -70,6 +72,12 @@ class Maneuver: MANEUVERS = [ + Maneuver( + "start from stop", + [Action(1.5, 3)], + repeat=3, + initial_speed=0., + ), Maneuver( "creep: alternate between +1m/s^2 and -1m/s^2", [ @@ -135,12 +143,12 @@ def main(): v_ego = max(sm['carState'].vEgo, 0) if maneuver is not None: - accel = maneuver.get_accel(v_ego, sm['carControl'].longActive, sm['carState'].cruiseState.standstill) + accel = maneuver.get_accel(v_ego, sm['carControl'].longActive, sm['carState'].standstill, sm['carState'].cruiseState.standstill) if maneuver.active: alert_msg.alertDebug.alertText1 = f'Maneuver Active: {accel:0.2f} m/s^2' else: - alert_msg.alertDebug.alertText1 = f'Reaching Speed: {maneuver.initial_speed * CV.MS_TO_MPH:0.2f} mph' + alert_msg.alertDebug.alertText1 = f'Setting up to {maneuver.initial_speed * CV.MS_TO_MPH:0.2f} mph' alert_msg.alertDebug.alertText2 = f'{maneuver.description}' else: alert_msg.alertDebug.alertText1 = 'Maneuvers Finished' From dcbeda1e85cccb5884c0bc8033fafe5b560110c6 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 13 Sep 2024 19:34:27 -0700 Subject: [PATCH 062/214] deprecate controlsState.aTarget (#33558) deprecate --- cereal/log.capnp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal/log.capnp b/cereal/log.capnp index 6cd7fe7534..ddde5e4d16 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -735,7 +735,6 @@ struct ControlsState @0x97ff69c53601abf1 { upAccelCmd @4 :Float32; uiAccelCmd @5 :Float32; ufAccelCmd @33 :Float32; - aTarget @35 :Float32; curvature @37 :Float32; # path curvature from vehicle model desiredCurvature @61 :Float32; # lag adjusted curvatures used by lateral controllers forceDecel @51 :Bool; @@ -881,6 +880,7 @@ struct ControlsState @0x97ff69c53601abf1 { vCruiseClusterDEPRECATED @63 :Float32; # set speed to display in the UI startMonoTimeDEPRECATED @48 :UInt64; cumLagMsDEPRECATED @15 :Float32; + aTargetDEPRECATED @35 :Float32; } struct DrivingModelData { From fd893dfcb760fa097133c7c9bd964bd3e292fdbd Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 17 Sep 2024 00:45:15 +0800 Subject: [PATCH 063/214] replay: optimize decompressZST with pre-allocated buffer (#33562) improve decompressZST --- tools/replay/util.cc | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/tools/replay/util.cc b/tools/replay/util.cc index 81e87b7dd3..0ae0c05f9b 100644 --- a/tools/replay/util.cc +++ b/tools/replay/util.cc @@ -329,8 +329,17 @@ std::string decompressZST(const std::byte *in, size_t in_size, std::atomic // Initialize input and output buffers ZSTD_inBuffer input = {in, in_size, 0}; + + // Estimate and reserve memory for decompressed data + size_t estimatedDecompressedSize = ZSTD_getFrameContentSize(in, in_size); + if (estimatedDecompressedSize == ZSTD_CONTENTSIZE_ERROR || estimatedDecompressedSize == ZSTD_CONTENTSIZE_UNKNOWN) { + estimatedDecompressedSize = in_size * 2; // Use a fallback size + } + std::string decompressedData; - const size_t bufferSize = ZSTD_DStreamOutSize(); // recommended output buffer size + decompressedData.reserve(estimatedDecompressedSize); + + const size_t bufferSize = ZSTD_DStreamOutSize(); // Recommended output buffer size std::string outputBuffer(bufferSize, '\0'); while (input.pos < input.size && !(abort && *abort)) { From 01bf17a8ca0f24bb0ee2c5708eb116953d462719 Mon Sep 17 00:00:00 2001 From: commaci-public <60409688+commaci-public@users.noreply.github.com> Date: Mon, 16 Sep 2024 11:45:35 -0700 Subject: [PATCH 064/214] [bot] Update Python packages (#33566) Update Python packages Co-authored-by: Vehicle Researcher --- opendbc_repo | 2 +- panda | 2 +- uv.lock | 78 ++++++++++++++++++++++++++-------------------------- 3 files changed, 41 insertions(+), 41 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index b43d3003c5..57ebdbfa05 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit b43d3003c50d88f4b9d5735b48a101f77a577c54 +Subproject commit 57ebdbfa0553d4002bf1fd654e4631931f2b676c diff --git a/panda b/panda index b8a2a8678f..2526d1ee4b 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit b8a2a8678fc201d7c02453a4fb819389d0fbf53b +Subproject commit 2526d1ee4b7b740b5f5786c25638ee1528d425be diff --git a/uv.lock b/uv.lock index aec5037de8..3775b4e288 100644 --- a/uv.lock +++ b/uv.lock @@ -773,11 +773,11 @@ wheels = [ [[package]] name = "idna" -version = "3.8" +version = "3.10" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e8/ac/e349c5e6d4543326c6883ee9491e3921e0d07b55fdf3cce184b40d63e72a/idna-3.8.tar.gz", hash = "sha256:d838c2c0ed6fced7693d5e8ab8e734d5f8fda53a039c0164afb0b82e771e3603", size = 189467 } +sdist = { url = "https://files.pythonhosted.org/packages/f1/70/7703c29685631f5a7590aa73f1f1d3fa9a380e654b86af429e0934a32f7d/idna-3.10.tar.gz", hash = "sha256:12f65c9b470abda6dc35cf8e63cc574b1c52b11df2c86030af0ac09b01b13ea9", size = 190490 } wheels = [ - { url = "https://files.pythonhosted.org/packages/22/7e/d71db821f177828df9dea8c42ac46473366f191be53080e552e628aad991/idna-3.8-py3-none-any.whl", hash = "sha256:050b4e5baadcd44d760cedbd2b8e639f2ff89bbc7a5730fcc662954303377aac", size = 66894 }, + { url = "https://files.pythonhosted.org/packages/76/c6/c88e154df9c4e1a2a66ccf0005a88dfb2650c1dffb6f5ce603dfbd452ce3/idna-3.10-py3-none-any.whl", hash = "sha256:946d195a0d259cbba61165e88e65941f16e9b36ea6ddb97f00452bae8b1287d3", size = 70442 }, ] [[package]] @@ -1707,11 +1707,11 @@ wheels = [ [[package]] name = "platformdirs" -version = "4.3.2" +version = "4.3.3" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/75/a0/d7cab8409cdc7d39b037c85ac46d92434fb6595432e069251b38e5c8dd0e/platformdirs-4.3.2.tar.gz", hash = "sha256:9e5e27a08aa095dd127b9f2e764d74254f482fef22b0970773bfba79d091ab8c", size = 21276 } +sdist = { url = "https://files.pythonhosted.org/packages/f5/19/f7bee3a71decedd8d7bc4d3edb7970b8e899f3caef257b0f0d623f2f7b11/platformdirs-4.3.3.tar.gz", hash = "sha256:d4e0b7d8ec176b341fb03cb11ca12d0276faa8c485f9cd218f613840463fc2c0", size = 21304 } wheels = [ - { url = "https://files.pythonhosted.org/packages/da/8b/d497999c4017b80678017ddce745cf675489c110681ad3c84a55eddfd3e7/platformdirs-4.3.2-py3-none-any.whl", hash = "sha256:eb1c8582560b34ed4ba105009a4badf7f6f85768b30126f351328507b2beb617", size = 18417 }, + { url = "https://files.pythonhosted.org/packages/69/e6/7c8e8c326903bd97c6c0c47e0a3c5de815faaae986cab7defdeddf5fddcd/platformdirs-4.3.3-py3-none-any.whl", hash = "sha256:50a5450e2e84f44539718293cbb1da0a0885c9d14adf21b77bae4e66fc99d9b5", size = 18437 }, ] [[package]] @@ -4523,11 +4523,11 @@ wheels = [ [[package]] name = "pyreadline3" -version = "3.4.3" +version = "3.5.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/fa/2a/ea766323eb84142ef7c068f9988d0b02c0f8fd21252791b0b6f56eec67db/pyreadline3-3.4.3.tar.gz", hash = "sha256:ebab0baca37f50e2faa1dd99a6da1c75de60e0d68a3b229c134bbd12786250e2", size = 86464 } +sdist = { url = "https://files.pythonhosted.org/packages/e2/59/0ec5d342dcc3ce475781ca1a76080b9acaa187f85a52cf021bdfe86089a4/pyreadline3-3.5.2.tar.gz", hash = "sha256:ba82292e52c5a3bb256b291af0c40b457c1e8699cac9a873abbcaac8aef3a1bb", size = 90396 } wheels = [ - { url = "https://files.pythonhosted.org/packages/2b/19/da2de49e7b9c1f1724003e8adba0e677fdfb3b8237cc637b5f14bfcc33d4/pyreadline3-3.4.3-py3-none-any.whl", hash = "sha256:f832c5898f4f9a0f81d48a8c499b39d0179de1a465ea3def1a7e7231840b4ed6", size = 95320 }, + { url = "https://files.pythonhosted.org/packages/9f/f9/c59c7bc50c3c4d6875b35e278b3e16e957d883fb2d7518d76f2c4a37fb97/pyreadline3-3.5.2-py3-none-any.whl", hash = "sha256:a87d56791e2965b2b187e2ea33dcf664600842c997c0623c95cf8ef07db83de9", size = 80399 }, ] [[package]] @@ -4960,27 +4960,27 @@ wheels = [ [[package]] name = "ruff" -version = "0.6.4" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/a4/55/9f485266e6326cab707369601b13e3e72eb90ba3eee2d6779549a00a0d58/ruff-0.6.4.tar.gz", hash = "sha256:ac3b5bfbee99973f80aa1b7cbd1c9cbce200883bdd067300c22a6cc1c7fba212", size = 2469375 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/e3/78/307591f81d09c8721b5e64539f287c82c81a46f46d16278eb27941ac17f9/ruff-0.6.4-py3-none-linux_armv6l.whl", hash = "sha256:c4b153fc152af51855458e79e835fb6b933032921756cec9af7d0ba2aa01a258", size = 9692673 }, - { url = "https://files.pythonhosted.org/packages/69/63/ef398fcacdbd3995618ed30b5a6c809a1ebbf112ba604b3f5b8c3be464cf/ruff-0.6.4-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:bedff9e4f004dad5f7f76a9d39c4ca98af526c9b1695068198b3bda8c085ef60", size = 9481182 }, - { url = "https://files.pythonhosted.org/packages/a6/fd/8784e3bbd79bc17de0a62de05fe5165f494ff7d77cb06630d6428c2f10d2/ruff-0.6.4-py3-none-macosx_11_0_arm64.whl", hash = "sha256:d02a4127a86de23002e694d7ff19f905c51e338c72d8e09b56bfb60e1681724f", size = 9174356 }, - { url = "https://files.pythonhosted.org/packages/6d/bc/c69db2d68ac7bfbb222c81dc43a86e0402d0063e20b13e609f7d17d81d3f/ruff-0.6.4-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7862f42fc1a4aca1ea3ffe8a11f67819d183a5693b228f0bb3a531f5e40336fc", size = 10129365 }, - { url = "https://files.pythonhosted.org/packages/3b/10/8ed14ff60a4e5eb08cac0a04a9b4e8590c72d1ce4d29ef22cef97d19536d/ruff-0.6.4-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:eebe4ff1967c838a1a9618a5a59a3b0a00406f8d7eefee97c70411fefc353617", size = 9483351 }, - { url = "https://files.pythonhosted.org/packages/a9/69/13316b8d64ffd6a43627cf0753339a7f95df413450c301a60904581bee6e/ruff-0.6.4-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:932063a03bac394866683e15710c25b8690ccdca1cf192b9a98260332ca93408", size = 10301099 }, - { url = "https://files.pythonhosted.org/packages/42/00/9623494087272643e8f02187c266638306c6829189a5bf1446968bbe438b/ruff-0.6.4-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:50e30b437cebef547bd5c3edf9ce81343e5dd7c737cb36ccb4fe83573f3d392e", size = 11033216 }, - { url = "https://files.pythonhosted.org/packages/c5/31/e0c9d881db42ea1267e075c29aafe0db5a8a3024b131f952747f6234f858/ruff-0.6.4-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c44536df7b93a587de690e124b89bd47306fddd59398a0fb12afd6133c7b3818", size = 10618140 }, - { url = "https://files.pythonhosted.org/packages/5b/35/f1d8b746aedd4c8fde4f83397e940cc4c8fc619860ebbe3073340381a34d/ruff-0.6.4-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:0ea086601b22dc5e7693a78f3fcfc460cceabfdf3bdc36dc898792aba48fbad6", size = 11606672 }, - { url = "https://files.pythonhosted.org/packages/c5/70/899b03cbb3eb48ed0507d4b32b6f7aee562bc618ef9ffda855ec98c0461a/ruff-0.6.4-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0b52387d3289ccd227b62102c24714ed75fbba0b16ecc69a923a37e3b5e0aaaa", size = 10288013 }, - { url = "https://files.pythonhosted.org/packages/17/c6/906bf895640521ca5115ccdd857b2bac42bd61facde6620fdc2efc0a4806/ruff-0.6.4-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:0308610470fcc82969082fc83c76c0d362f562e2f0cdab0586516f03a4e06ec6", size = 10109473 }, - { url = "https://files.pythonhosted.org/packages/28/da/1284eb04172f8a5d42eb52fce9d643dd747ac59a4ed6c5d42729f72e934d/ruff-0.6.4-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:803b96dea21795a6c9d5bfa9e96127cc9c31a1987802ca68f35e5c95aed3fc0d", size = 9568817 }, - { url = "https://files.pythonhosted.org/packages/6c/e2/f8250b54edbb2e9222e22806e1bcc35a192ac18d1793ea556fa4977a843a/ruff-0.6.4-py3-none-musllinux_1_2_i686.whl", hash = "sha256:66dbfea86b663baab8fcae56c59f190caba9398df1488164e2df53e216248baa", size = 9910840 }, - { url = "https://files.pythonhosted.org/packages/9c/7c/dcf2c10562346ecdf6f0e5f6669b2ddc9a74a72956c3f419abd6820c2aff/ruff-0.6.4-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:34d5efad480193c046c86608dbba2bccdc1c5fd11950fb271f8086e0c763a5d1", size = 10354263 }, - { url = "https://files.pythonhosted.org/packages/f1/94/c39d7ac5729e94788110503d928c98c203488664b0fb92c2b801cb832bec/ruff-0.6.4-py3-none-win32.whl", hash = "sha256:f0f8968feea5ce3777c0d8365653d5e91c40c31a81d95824ba61d871a11b8523", size = 7958602 }, - { url = "https://files.pythonhosted.org/packages/6b/d2/2dee8c547bee3d4cfdd897f7b8e38510383acaff2c8130ea783b67631d72/ruff-0.6.4-py3-none-win_amd64.whl", hash = "sha256:549daccee5227282289390b0222d0fbee0275d1db6d514550d65420053021a58", size = 8795059 }, - { url = "https://files.pythonhosted.org/packages/07/1a/23280818aa4fa89bd0552aab10857154e1d3b90f27b5b745f09ec1ac6ad8/ruff-0.6.4-py3-none-win_arm64.whl", hash = "sha256:ac4b75e898ed189b3708c9ab3fc70b79a433219e1e87193b4f2b77251d058d14", size = 8239636 }, +version = "0.6.5" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/96/3f/29b2d3d90f811f6fb5b90242309f4668cd8c2482aab86ffc23099000545b/ruff-0.6.5.tar.gz", hash = "sha256:4d32d87fab433c0cf285c3683dd4dae63be05fd7a1d65b3f5bf7cdd05a6b96fb", size = 2476127 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/64/05/cc62df44b5a0271b29f11d687aa89e85943e0d26e5bb773dbc1456d9885d/ruff-0.6.5-py3-none-linux_armv6l.whl", hash = "sha256:7e4e308f16e07c95fc7753fc1aaac690a323b2bb9f4ec5e844a97bb7fbebd748", size = 9770988 }, + { url = "https://files.pythonhosted.org/packages/09/3d/89dac56ab7053d5b7cba723c9cae1a29b7a2978174c67e2441525ee00343/ruff-0.6.5-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:932cd69eefe4daf8c7d92bd6689f7e8182571cb934ea720af218929da7bd7d69", size = 9423303 }, + { url = "https://files.pythonhosted.org/packages/70/76/dc04654d26beace866a3c9e0c87112304e3d6406e1ee8ca0d9bebbd82d91/ruff-0.6.5-py3-none-macosx_11_0_arm64.whl", hash = "sha256:3a8d42d11fff8d3143ff4da41742a98f8f233bf8890e9fe23077826818f8d680", size = 9134078 }, + { url = "https://files.pythonhosted.org/packages/da/52/6a492cffcd2c6e243043937ab52811b6ebb10cb5b77a68cc98e7676ceaef/ruff-0.6.5-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a50af6e828ee692fb10ff2dfe53f05caecf077f4210fae9677e06a808275754f", size = 10105094 }, + { url = "https://files.pythonhosted.org/packages/59/7c/fd76a583ae59a276537d71921d616a83ec7774027d0812049afb6af8a07f/ruff-0.6.5-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:794ada3400a0d0b89e3015f1a7e01f4c97320ac665b7bc3ade24b50b54cb2972", size = 9542751 }, + { url = "https://files.pythonhosted.org/packages/56/5b/4e8928fa11412b16ecf7d7755fe45db6dfa7abce32841f6aec33bae3a7da/ruff-0.6.5-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:381413ec47f71ce1d1c614f7779d88886f406f1fd53d289c77e4e533dc6ea200", size = 10358844 }, + { url = "https://files.pythonhosted.org/packages/bd/a8/315ea8f71b111c8fb2b681c88a3e7a707d74308eb1435dc6ee3e6637a286/ruff-0.6.5-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:52e75a82bbc9b42e63c08d22ad0ac525117e72aee9729a069d7c4f235fc4d276", size = 11075199 }, + { url = "https://files.pythonhosted.org/packages/d9/1c/3a3728d42db52bfe418d8c913b453531766be1383719573f2458e8b59990/ruff-0.6.5-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:09c72a833fd3551135ceddcba5ebdb68ff89225d30758027280968c9acdc7810", size = 10661186 }, + { url = "https://files.pythonhosted.org/packages/d4/0c/ae25e213461aab274822081923d747f02929d71843c42b8f56018a7ec636/ruff-0.6.5-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:800c50371bdcb99b3c1551d5691e14d16d6f07063a518770254227f7f6e8c178", size = 11747444 }, + { url = "https://files.pythonhosted.org/packages/c4/e3/9d0ff218c7663ab9d53abe02911bec03d32b8ced7f78c1c49c2af84903a2/ruff-0.6.5-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8e25ddd9cd63ba1f3bd51c1f09903904a6adf8429df34f17d728a8fa11174253", size = 10266302 }, + { url = "https://files.pythonhosted.org/packages/ac/03/f158cc24120bf277b0cd7906ba509a2db74531003663500a0d1781cd7448/ruff-0.6.5-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:7291e64d7129f24d1b0c947ec3ec4c0076e958d1475c61202497c6aced35dd19", size = 10104976 }, + { url = "https://files.pythonhosted.org/packages/91/d0/0bacdffc234e588ec05834186ad11ec8281a6ca598d0106892497bbcfa44/ruff-0.6.5-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:9ad7dfbd138d09d9a7e6931e6a7e797651ce29becd688be8a0d4d5f8177b4b0c", size = 9625374 }, + { url = "https://files.pythonhosted.org/packages/1a/ad/721003cde8abd9f50bff74acbcb21852531036451d48a1abddba4dd84025/ruff-0.6.5-py3-none-musllinux_1_2_i686.whl", hash = "sha256:005256d977021790cc52aa23d78f06bb5090dc0bfbd42de46d49c201533982ae", size = 9959661 }, + { url = "https://files.pythonhosted.org/packages/37/84/8d70a3eacaacb65b4bb1461fc1a59e37ff165152b7e507692109117c877f/ruff-0.6.5-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:482c1e6bfeb615eafc5899127b805d28e387bd87db38b2c0c41d271f5e58d8cc", size = 10327408 }, + { url = "https://files.pythonhosted.org/packages/54/7e/6b0a9ab30428a9e3d9607f6dd2e4fb743594d42bd1b6ba7b7b239acda921/ruff-0.6.5-py3-none-win32.whl", hash = "sha256:cf4d3fa53644137f6a4a27a2b397381d16454a1566ae5335855c187fbf67e4f5", size = 8012512 }, + { url = "https://files.pythonhosted.org/packages/d8/88/176f50162a219e3039f21e9e4323869fc62bf8d3afb4147a390d6c744bd8/ruff-0.6.5-py3-none-win_amd64.whl", hash = "sha256:3e42a57b58e3612051a636bc1ac4e6b838679530235520e8f095f7c44f706ff9", size = 8804438 }, + { url = "https://files.pythonhosted.org/packages/67/a0/1b488bbe35a7ff8296fdea1ec1a9c2676cecc7e42bda63860f9397d59140/ruff-0.6.5-py3-none-win_arm64.whl", hash = "sha256:51935067740773afdf97493ba9b8231279e9beef0f2a8079188c4776c25688e0", size = 8179780 }, ] [[package]] @@ -5039,11 +5039,11 @@ wheels = [ [[package]] name = "setuptools" -version = "74.1.2" +version = "75.1.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/3e/2c/f0a538a2f91ce633a78daaeb34cbfb93a54bd2132a6de1f6cec028eee6ef/setuptools-74.1.2.tar.gz", hash = "sha256:95b40ed940a1c67eb70fc099094bd6e99c6ee7c23aa2306f4d2697ba7916f9c6", size = 1356467 } +sdist = { url = "https://files.pythonhosted.org/packages/27/b8/f21073fde99492b33ca357876430822e4800cdf522011f18041351dfa74b/setuptools-75.1.0.tar.gz", hash = "sha256:d59a21b17a275fb872a9c3dae73963160ae079f1049ed956880cd7c09b120538", size = 1348057 } wheels = [ - { url = "https://files.pythonhosted.org/packages/cb/9c/9ad11ac06b97e55ada655f8a6bea9d1d3f06e120b178cd578d80e558191d/setuptools-74.1.2-py3-none-any.whl", hash = "sha256:5f4c08aa4d3ebcb57a50c33b1b07e94315d7fc7230f7115e47fc99776c8ce308", size = 1262071 }, + { url = "https://files.pythonhosted.org/packages/ff/ae/f19306b5a221f6a436d8f2238d5b80925004093fa3edea59835b514d9057/setuptools-75.1.0-py3-none-any.whl", hash = "sha256:35ab7fd3bcd95e6b7fd704e4a1539513edad446c097797f2985e0e4b960772f2", size = 1248506 }, ] [[package]] @@ -5187,14 +5187,14 @@ wheels = [ [[package]] name = "types-requests" -version = "2.32.0.20240907" +version = "2.32.0.20240914" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/9f/94/b6f90e5f09e1d621d5cd6d1057d5d28d4019d95f06eab205afa743ba1907/types-requests-2.32.0.20240907.tar.gz", hash = "sha256:ff33935f061b5e81ec87997e91050f7b4af4f82027a7a7a9d9aaea04a963fdf8", size = 18004 } +sdist = { url = "https://files.pythonhosted.org/packages/9b/9e/aea33405c230cc3984c9f1065012d3a2003cef910730c367a0e91e7a4901/types-requests-2.32.0.20240914.tar.gz", hash = "sha256:2850e178db3919d9bf809e434eef65ba49d0e7e33ac92d588f4a5e295fffd405", size = 18030 } wheels = [ - { url = "https://files.pythonhosted.org/packages/5f/6e/425219be1dfc954c3e129b3ea70407abc78c1bd6414d0c7180df9940ca1f/types_requests-2.32.0.20240907-py3-none-any.whl", hash = "sha256:1d1e79faeaf9d42def77f3c304893dea17a97cae98168ac69f3cb465516ee8da", size = 15828 }, + { url = "https://files.pythonhosted.org/packages/8f/55/ea44dad71b9d92f86198f7448f5ba46ac919355f4f69bb1c0fa1af02b1b4/types_requests-2.32.0.20240914-py3-none-any.whl", hash = "sha256:59c2f673eb55f32a99b2894faf6020e1a9f4a402ad0f192bfee0b64469054310", size = 15838 }, ] [[package]] @@ -5334,11 +5334,11 @@ wheels = [ [[package]] name = "zipp" -version = "3.20.1" +version = "3.20.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d3/8b/1239a3ef43a0d0ebdca623fb6413bc7702c321400c5fdd574f0b7aa0fbb4/zipp-3.20.1.tar.gz", hash = "sha256:c22b14cc4763c5a5b04134207736c107db42e9d3ef2d9779d465f5f1bcba572b", size = 23848 } +sdist = { url = "https://files.pythonhosted.org/packages/54/bf/5c0000c44ebc80123ecbdddba1f5dcd94a5ada602a9c225d84b5aaa55e86/zipp-3.20.2.tar.gz", hash = "sha256:bc9eb26f4506fda01b81bcde0ca78103b6e62f991b381fec825435c836edbc29", size = 24199 } wheels = [ - { url = "https://files.pythonhosted.org/packages/07/9e/c96f7a4cd0bf5625bb409b7e61e99b1130dc63a98cb8b24aeabae62d43e8/zipp-3.20.1-py3-none-any.whl", hash = "sha256:9960cd8967c8f85a56f920d5d507274e74f9ff813a0ab8889a5b5be2daf44064", size = 8988 }, + { url = "https://files.pythonhosted.org/packages/62/8b/5ba542fa83c90e09eac972fc9baca7a88e7e7ca4b221a89251954019308b/zipp-3.20.2-py3-none-any.whl", hash = "sha256:a817ac80d6cf4b23bf7f2828b7cabf326f15a001bea8b1f9b49631780ba28350", size = 9200 }, ] [[package]] From ea532c7a7c00ad0270ab978a05094d247bebfad7 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 17 Sep 2024 05:05:57 +0800 Subject: [PATCH 065/214] cabana: improve isMessageActive (#33563) improve isMessageActive --- tools/cabana/messageswidget.cc | 21 +++++++++------------ tools/cabana/messageswidget.h | 1 - 2 files changed, 9 insertions(+), 13 deletions(-) diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index d6c2fd0ea9..5c0c2eaba6 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -14,16 +14,18 @@ #include "tools/cabana/commands.h" static bool isMessageActive(const MessageId &id) { - if (auto dummy_stream = dynamic_cast(can)) { - return true; - } if (id.source == INVALID_SOURCE) { return false; } // Check if the message is active based on time difference and frequency const auto &m = can->lastMessage(id); float delta = can->currentSec() - m.ts; - return (m.freq == 0 && delta < 1.5) || (m.freq > 0 && ((delta - 1.0 / settings.fps) < (5.0 / m.freq))); + + if (m.freq < std::numeric_limits::epsilon()) { + return delta < 1.5; + } + + return delta < (5.0 / m.freq) + (1.0 / settings.fps); } MessagesWidget::MessagesWidget(QWidget *parent) : menu(new QMenu(this)), QWidget(parent) { @@ -215,8 +217,8 @@ QVariant MessageListModel::data(const QModelIndex &index, int role) const { return QVariant::fromValue((void*)(&can->lastMessage(item.id).colors)); } else if (role == BytesRole && index.column() == Column::DATA && item.id.source != INVALID_SOURCE) { return QVariant::fromValue((void*)(&can->lastMessage(item.id).dat)); - } else if (role == Qt::ForegroundRole && !item.active) { - return settings.theme == DARK_THEME ? QApplication::palette().color(QPalette::Text).darker(150) : QColor(Qt::gray); + } else if (role == Qt::ForegroundRole && !isMessageActive(item.id)) { + return QApplication::palette().color(QPalette::Disabled, QPalette::Text); } else if (role == Qt::ToolTipRole && index.column() == Column::NAME) { auto msg = dbc()->msg(item.id); auto tooltip = item.name; @@ -335,11 +337,9 @@ bool MessageListModel::filterAndSort() { std::vector items; items.reserve(all_messages.size()); for (const auto &id : all_messages) { - bool active = isMessageActive(id); - if (active || show_inactive_messages) { + if (show_inactive_messages || isMessageActive(id)) { auto msg = dbc()->msg(id); Item item = {.id = id, - .active = active, .name = msg ? msg->name : UNTITLED, .node = msg ? msg->transmitter : QString()}; if (match(item)) @@ -364,9 +364,6 @@ void MessageListModel::msgsReceived(const std::set *new_msgs, bool ha if (filterAndSort()) return; } - for (auto &item : items_) { - item.active = isMessageActive(item.id); - } // Update viewport emit dataChanged(index(0, 0), index(rowCount() - 1, columnCount() - 1)); } diff --git a/tools/cabana/messageswidget.h b/tools/cabana/messageswidget.h index 823fcb74e3..0fc09519a3 100644 --- a/tools/cabana/messageswidget.h +++ b/tools/cabana/messageswidget.h @@ -45,7 +45,6 @@ public: MessageId id; QString name; QString node; - bool active; bool operator==(const Item &other) const { return id == other.id && name == other.name && node == other.node; } From 782d959b4c7ed9b86d01deec3ea426cf1c43051c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 17 Sep 2024 06:47:15 +0800 Subject: [PATCH 066/214] CI: continuously send messages to keep them active during alert screenshots (#33544) keep alive --- selfdrive/ui/tests/test_ui/run.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 4ae9e4e611..b6e99190fc 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -10,9 +10,9 @@ import os import pywinctl import time -from cereal import messaging, log +from cereal import log from msgq.visionipc import VisionIpcServer, VisionStreamType -from cereal.messaging import PubMaster +from cereal.messaging import PubMaster, log_from_bytes from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params from openpilot.common.prefix import OpenpilotPrefix @@ -94,16 +94,16 @@ def setup_driver_camera(click, pm: PubMaster): def setup_onroad_alert(click, pm: PubMaster, text1, text2, size, status=log.SelfdriveState.AlertStatus.normal): print(f'setup onroad alert, size: {size}') - setup_onroad(click, pm) - dat = messaging.new_message('selfdriveState') - cs = dat.selfdriveState + state = DATA['selfdriveState'] + origin_state_bytes = state.to_bytes() + cs = state.selfdriveState cs.alertText1 = text1 cs.alertText2 = text2 cs.alertSize = size cs.alertStatus = status cs.alertType = "test_onroad_alert" - pm.send('selfdriveState', dat) - time.sleep(UI_DELAY) + setup_onroad(click, pm) + DATA['selfdriveState'] = log_from_bytes(origin_state_bytes).as_builder() def setup_onroad_alert_small(click, pm: PubMaster): setup_onroad_alert(click, pm, 'This is a small alert message', '', log.SelfdriveState.AlertSize.small) From 5be53a39f05339c95a5bfcc2ea9b95bb9ba1a65b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 16 Sep 2024 15:47:59 -0700 Subject: [PATCH 067/214] Cruise speed: 0 is considered unset (#33449) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * give 10 frames of tolerance to reset -- WARNING: hacks inside old-commit-hash: d72ac9e53d211074b059f049f8ebc89b9cff1c58 * comment old-commit-hash: adf1ef88b692132c37d865fc973189fdf971464f * more conventional old-commit-hash: 552aa2c159fc535682d098425e827d8cb56911c1 * move old-commit-hash: fe88ac0afc5aa7438d5b36908744124bc1cb68c9 * oh tf old-commit-hash: 98d8659bd0f61dd512693807ea29d2f0c78f7514 * better old-commit-hash: 5ddda806a008cc189758491f91a4a4d0aeb8d343 * this is fine 🔥 * INIT NOT UNINIT * only vCruise changes here * update refs --- selfdrive/car/cruise.py | 3 +++ selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/cruise.py b/selfdrive/car/cruise.py index e2d83033d6..b92d0c7465 100644 --- a/selfdrive/car/cruise.py +++ b/selfdrive/car/cruise.py @@ -53,6 +53,9 @@ class VCruiseHelper: else: self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH self.v_cruise_cluster_kph = CS.cruiseState.speedCluster * CV.MS_TO_KPH + if CS.cruiseState.speed == 0: + self.v_cruise_kph = V_CRUISE_UNSET + self.v_cruise_cluster_kph = V_CRUISE_UNSET else: self.v_cruise_kph = V_CRUISE_UNSET self.v_cruise_cluster_kph = V_CRUISE_UNSET diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 49d920fe2a..e08f65f499 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -13d947375a5908d68b33bf3b51b799f8021a35a6 \ No newline at end of file +dbaa29106eb93267699c822e4937126b4307805a \ No newline at end of file From 2e6e977c934aa81995945461667ad7ece6fbc434 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 16 Sep 2024 16:06:02 -0700 Subject: [PATCH 068/214] Longitudinal planner: wait for valid cruise speed (#33568) * Revert "only vCruise changes here" This reverts commit 4f5659b5d53e9bac3357781bce262a29d3b1d14e. * less nonsense --- selfdrive/controls/lib/longitudinal_planner.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 103d3f7047..0b65119383 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -13,7 +13,7 @@ from openpilot.selfdrive.controls.lib.longcontrol import LongCtrlState from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, get_speed_error -from openpilot.selfdrive.car.cruise import V_CRUISE_MAX +from openpilot.selfdrive.car.cruise import V_CRUISE_MAX, V_CRUISE_UNSET from openpilot.common.swaglog import cloudlog LON_MPC_STEP = 0.2 # first step is 0.2s @@ -101,12 +101,15 @@ class LongitudinalPlanner: v_ego = sm['carState'].vEgo v_cruise_kph = min(sm['carState'].vCruise, V_CRUISE_MAX) v_cruise = v_cruise_kph * CV.KPH_TO_MS + v_cruise_initialized = sm['carState'].vCruise != V_CRUISE_UNSET long_control_off = sm['controlsState'].longControlState == LongCtrlState.off force_slow_decel = sm['controlsState'].forceDecel # Reset current state when not engaged, or user is controlling the speed reset_state = long_control_off if self.CP.openpilotLongitudinalControl else not sm['selfdriveState'].enabled + # PCM cruise speed may be updated a few cycles later, check if initialized + reset_state = reset_state or not v_cruise_initialized # No change cost when user is controlling the speed, or when standstill prev_accel_constraint = not (reset_state or sm['carState'].standstill) From df5b45a2850a70cec2256bcbce91fbbe650e9161 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 16 Sep 2024 18:05:07 -0700 Subject: [PATCH 069/214] modeld has gone up a bit --- selfdrive/test/test_onroad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index d4ec3c2fff..21fd4b1f11 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -46,7 +46,7 @@ PROCS = { "selfdrive.locationd.paramsd": 9.0, "./sensord": 7.0, "selfdrive.controls.radard": 2.0, - "selfdrive.modeld.modeld": 13.0, + "selfdrive.modeld.modeld": 17.0, "selfdrive.modeld.dmonitoringmodeld": 8.0, "system.hardware.hardwared": 3.87, "selfdrive.locationd.calibrationd": 2.0, From 6b7996de911837009bdc0fa55dcea8959459695d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 16 Sep 2024 18:05:20 -0700 Subject: [PATCH 070/214] jenkins fixups for agnos 11 (#33569) * jenkins fixups for agnos 11 * just do this for now --- selfdrive/test/setup_device_ci.sh | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index fdc222e7e7..fff01d260b 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -1,6 +1,7 @@ #!/usr/bin/env bash set -e +set -x if [ -z "$SOURCE_DIR" ]; then echo "SOURCE_DIR must be set" @@ -17,9 +18,11 @@ if [ -z "$TEST_DIR" ]; then exit 1 fi -umount /data/safe_staging/merged/ || true -sudo umount /data/safe_staging/merged/ || true -rm -rf /data/safe_staging/* || true +rm -rf /data/safe_staging/ || true +if [ -d /data/safe_staging/ ]; then + sudo umount /data/safe_staging/merged/ || true + rm -rf /data/safe_staging/ || true +fi CONTINUE_PATH="/data/continue.sh" tee $CONTINUE_PATH << EOF From f294162b2c18c06987ef18a287d3862aea32080d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 16 Sep 2024 19:23:04 -0700 Subject: [PATCH 071/214] bump up cpu budget --- selfdrive/test/test_onroad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 21fd4b1f11..5bc6bff1c2 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -32,7 +32,7 @@ CPU usage budget * total CPU usage of openpilot (sum(PROCS.values()) should not exceed MAX_TOTAL_CPU """ -MAX_TOTAL_CPU = 260. # total for all 8 cores +MAX_TOTAL_CPU = 265. # total for all 8 cores PROCS = { # Baseline CPU usage by process "selfdrive.controls.controlsd": 18.0, From a3d587b93d08bc850350f57199ed302a2b8e657f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 16 Sep 2024 22:27:29 -0700 Subject: [PATCH 072/214] maneuversd: check for longActive again --- tools/longitudinal_maneuvers/maneuversd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/longitudinal_maneuvers/maneuversd.py b/tools/longitudinal_maneuvers/maneuversd.py index 5096c19a0b..6100a7ca89 100755 --- a/tools/longitudinal_maneuvers/maneuversd.py +++ b/tools/longitudinal_maneuvers/maneuversd.py @@ -31,7 +31,7 @@ class Maneuver: def get_accel(self, v_ego: float, long_active: bool, standstill: bool, cruise_standstill: bool) -> float: ready = abs(v_ego - self.initial_speed) < 0.3 and long_active and not cruise_standstill if self.initial_speed < 0.01: - ready = v_ego < 0.1 and standstill + ready = ready and standstill self._ready_cnt = (self._ready_cnt + 1) if ready else 0 if self._ready_cnt > (3. / DT_MDL): From 23716986011814e4ef1c4ea72c5e2d2afc8184b0 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 16 Sep 2024 22:59:37 -0700 Subject: [PATCH 073/214] maneuver report: use livePose acceleration and add description --- tools/longitudinal_maneuvers/generate_report.py | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py index 88f78416b4..f487225054 100755 --- a/tools/longitudinal_maneuvers/generate_report.py +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -16,7 +16,7 @@ def format_car_params(CP): return pprint.pformat({k: v for k, v in CP.to_dict().items() if not k.endswith('DEPRECATED')}, indent=2) -def report(platform, route, CP, maneuvers): +def report(platform, route, _description, CP, maneuvers): output_path = Path(__file__).resolve().parent / "longitudinal_reports" output_fn = output_path / f"{platform}_{route.replace('/', '_')}.html" output_path.mkdir(exist_ok=True) @@ -25,6 +25,8 @@ def report(platform, route, CP, maneuvers): f.write("

Longitudinal maneuver report

\n") f.write(f"

{platform}

\n") f.write(f"

{route}

\n") + if _description is not None: + f.write(f"

Description: {_description}

\n") f.write(f"

CarParams

{format_car_params(CP)}
\n") for description, runs in maneuvers: print(f'plotting maneuver: {description}, runs: {len(runs)}') @@ -34,17 +36,19 @@ def report(platform, route, CP, maneuvers): t_carControl, carControl = zip(*[(m.logMonoTime, m.carControl) for m in msgs if m.which() == 'carControl'], strict=True) t_carOutput, carOutput = zip(*[(m.logMonoTime, m.carOutput) for m in msgs if m.which() == 'carOutput'], strict=True) t_carState, carState = zip(*[(m.logMonoTime, m.carState) for m in msgs if m.which() == 'carState'], strict=True) + t_livePose, livePose = zip(*[(m.logMonoTime, m.livePose) for m in msgs if m.which() == 'livePose'], strict=True) t_longitudinalPlan, longitudinalPlan = zip(*[(m.logMonoTime, m.longitudinalPlan) for m in msgs if m.which() == 'longitudinalPlan'], strict=True) # make time relative seconds t_carControl = [(t - t_carControl[0]) / 1e9 for t in t_carControl] t_carOutput = [(t - t_carOutput[0]) / 1e9 for t in t_carOutput] t_carState = [(t - t_carState[0]) / 1e9 for t in t_carState] + t_livePose = [(t - t_livePose[0]) / 1e9 for t in t_livePose] t_longitudinalPlan = [(t - t_longitudinalPlan[0]) / 1e9 for t in t_longitudinalPlan] # maneuver validity longActive = [m.longActive for m in carControl] - maneuver_valid = all(longActive) + maneuver_valid = all(longActive) and not any(cs.cruiseState.standstill for cs in carState) _open = 'open' if maneuver_valid else '' title = f'Run #{int(run)+1}' + (' (invalid maneuver!)' if not maneuver_valid else '') @@ -55,8 +59,8 @@ def report(platform, route, CP, maneuvers): aTarget = longitudinalPlan[0].aTarget target_cross_time = None f.write(f'

Initial aTarget: {aTarget} m/s^2') - for t, cs in zip(t_carState, carState, strict=True): - if (0 < aTarget < cs.aEgo) or (0 > aTarget > cs.aEgo): + for t, lp in zip(t_livePose, livePose, strict=True): + if (0 < aTarget < lp.accelerationDevice.x) or (0 > aTarget > lp.accelerationDevice.x): f.write(f', crossed in {t:.3f}s') target_cross_time = t if maneuver_valid: @@ -75,6 +79,7 @@ def report(platform, route, CP, maneuvers): ax[0].plot(t_carOutput, [m.actuatorsOutput.accel for m in carOutput], label='carOutput.actuatorsOutput.accel', linewidth=6) ax[0].plot(t_longitudinalPlan, [m.aTarget for m in longitudinalPlan], label='longitudinalPlan.aTarget', linewidth=6) ax[0].plot(t_carState, [m.aEgo for m in carState], label='carState.aEgo', linewidth=6) + ax[0].plot(t_livePose, [m.accelerationDevice.x for m in livePose], label='livePose.accelerationDevice.x', linewidth=6) # TODO localizer accel ax[0].set_ylabel('Acceleration (m/s^2)') #ax[0].set_ylim(-6.5, 6.5) @@ -119,6 +124,7 @@ def report(platform, route, CP, maneuvers): if __name__ == '__main__': parser = argparse.ArgumentParser(description='Generate longitudinal maneuver report from route') parser.add_argument('route', type=str, help='Route name (e.g. 00000000--5f742174be)') + parser.add_argument('description', type=str, default=None) args = parser.parse_args() @@ -150,4 +156,4 @@ if __name__ == '__main__': if active_prev: maneuvers[-1][1][-1].append(msg) - report(platform, args.route, CP, maneuvers) + report(platform, args.route, args.description, CP, maneuvers) From 306316755b73835112c322144368fbeeb3515dac Mon Sep 17 00:00:00 2001 From: Andrei Radulescu Date: Tue, 17 Sep 2024 20:03:25 +0300 Subject: [PATCH 074/214] agnos: move metadrive-simulator & rerun-sdk to a separate tools group (#33570) --- pyproject.toml | 7 +++++-- uv.lock | 10 ++++++---- 2 files changed, 11 insertions(+), 6 deletions(-) diff --git a/pyproject.toml b/pyproject.toml index 2f4ce136b6..8ed4ff855b 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -101,7 +101,6 @@ dev = [ "flaky", "lru-dict", "matplotlib", - "metadrive-simulator @ https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal/metadrive_simulator-0.4.2.3-py3-none-any.whl ; (platform_machine != 'aarch64')", "parameterized >=0.8, <0.9", #"pprofile", "pyautogui", @@ -109,7 +108,6 @@ dev = [ "pytools < 2024.1.11; platform_machine != 'aarch64'", # pyopencl use a broken version "pywinctl", "pyprof2calltree", - "rerun-sdk >= 0.18", "tabulate", "types-requests", "types-tabulate", @@ -118,6 +116,11 @@ dev = [ "pyqt5 ==5.15.2; platform_machine == 'x86_64'", # no aarch64 wheels for macOS/linux ] +tools = [ + "metadrive-simulator @ https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal/metadrive_simulator-0.4.2.3-py3-none-any.whl ; (platform_machine != 'aarch64')", + "rerun-sdk >= 0.18", +] + [project.urls] Homepage = "https://comma.ai" diff --git a/uv.lock b/uv.lock index 3775b4e288..16207cf26e 100644 --- a/uv.lock +++ b/uv.lock @@ -1481,7 +1481,6 @@ dev = [ { name = "flaky" }, { name = "lru-dict" }, { name = "matplotlib" }, - { name = "metadrive-simulator", marker = "platform_machine != 'aarch64'" }, { name = "parameterized" }, { name = "pyautogui" }, { name = "pyopencl", marker = "platform_machine != 'aarch64'" }, @@ -1489,7 +1488,6 @@ dev = [ { name = "pyqt5", marker = "platform_machine == 'x86_64'" }, { name = "pytools", marker = "platform_machine != 'aarch64'" }, { name = "pywinctl" }, - { name = "rerun-sdk" }, { name = "tabulate" }, { name = "types-requests" }, { name = "types-tabulate" }, @@ -1517,6 +1515,10 @@ testing = [ { name = "pytest-xdist" }, { name = "ruff" }, ] +tools = [ + { name = "metadrive-simulator", marker = "platform_machine != 'aarch64'" }, + { name = "rerun-sdk" }, +] [package.metadata] requires-dist = [ @@ -1541,7 +1543,7 @@ requires-dist = [ { name = "libusb1" }, { name = "lru-dict", marker = "extra == 'dev'" }, { name = "matplotlib", marker = "extra == 'dev'" }, - { name = "metadrive-simulator", marker = "platform_machine != 'aarch64' and extra == 'dev'", url = "https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal/metadrive_simulator-0.4.2.3-py3-none-any.whl" }, + { name = "metadrive-simulator", marker = "platform_machine != 'aarch64' and extra == 'tools'", url = "https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal/metadrive_simulator-0.4.2.3-py3-none-any.whl" }, { name = "mkdocs", marker = "extra == 'docs'" }, { name = "mypy", marker = "extra == 'testing'" }, { name = "natsort", marker = "extra == 'docs'" }, @@ -1575,7 +1577,7 @@ requires-dist = [ { name = "pywinctl", marker = "extra == 'dev'" }, { name = "pyzmq" }, { name = "requests" }, - { name = "rerun-sdk", marker = "extra == 'dev'", specifier = ">=0.18" }, + { name = "rerun-sdk", marker = "extra == 'tools'", specifier = ">=0.18" }, { name = "ruff", marker = "extra == 'testing'" }, { name = "scons" }, { name = "sentry-sdk" }, From 3e0ec64e9a235794a910723798912fce57ccb2ff Mon Sep 17 00:00:00 2001 From: Nelson Chen Date: Tue, 17 Sep 2024 13:37:41 -0700 Subject: [PATCH 075/214] Longitudinal manuever docs (#33561) * Make output longitudinal maneuvers HTML smaller so users can throw them onto jsfiddle and etc. * Add an initial meaty readme for longitudinal maneuver tool Feel free to trim! * simplify instructions * revert revert * remove broken video, better image * details * discord * final --------- Co-authored-by: Shane Smiskol --- tools/longitudinal_maneuvers/README.md | 43 ++++++++++++++++++++++++++ 1 file changed, 43 insertions(+) create mode 100644 tools/longitudinal_maneuvers/README.md diff --git a/tools/longitudinal_maneuvers/README.md b/tools/longitudinal_maneuvers/README.md new file mode 100644 index 0000000000..b0f5897d08 --- /dev/null +++ b/tools/longitudinal_maneuvers/README.md @@ -0,0 +1,43 @@ +# Longitudinal Maneuvers Testing Tool + +Test your vehicle's longitudinal control with this tool. The tool will test the vehicle's ability to follow a few longitudinal maneuvers and includes a tool to generate a report from the route. + +
Sample snapshot of a report.
+ +## Instructions + +1. Check out a development branch such as `master` on your comma device. +2. Locate either a large empty parking lot or road devoid of any car or foot traffic. Flat, straight road is preferred. The full maneuver suite can take 1 mile or more if left running, however it is recommended to disengage openpilot between maneuvers and turn around if there is not enough space. +3. Turn off the vehicle and set this parameter which will signal to openpilot to start the longitudinal maneuver daemon: + + ```sh + echo -n 1 > /data/params/d/LongitudinalManeuverMode + ``` + +4. Turn your vehicle back on. You will see the "Longitudinal Maneuver Mode" alert: + + ![videoframe_6652](https://github.com/user-attachments/assets/e9d4c95a-cd76-4ab7-933e-19937792fa0f) + +5. Ensure the road ahead is clear, as openpilot will not brake for any obstructions in this mode. If so, press "Set" on your steering wheel to start the tests. The tests will run for about 4 minutes. If you need to pause the tests, press "Cancel" on your steering wheel. You can resume the tests by pressing "Resume" on your steering wheel. +6. When the testing is complete, you'll see an alert that says "Maneuvers Finished," complete the route by pulling over and turning off the vehicle. + + ![fin2](https://github.com/user-attachments/assets/c06960ae-7cfb-44af-beaa-4dc28848e49d) + +7. Visit https://connect.comma.ai and locate the route(s). They will stand out with lots of orange intervals in their timeline. Ensure "All logs" show as "uploaded." + + ![image](https://github.com/user-attachments/assets/cfe4c6d9-752f-4b24-b421-4b90a01933dc) + +8. Gather the route ID and then run the report generator. The file will be exported to the same directory: + + ```sh + $ python tools/longitudinal_maneuvers/generate_report.py 57048cfce01d9625/0000010e--5b26bc3be7 'pcm accel compensation' + + processing report for LEXUS_ES_TSS2 + plotting maneuver: start from stop, runs: 4 + plotting maneuver: creep: alternate between +1m/s^2 and -1m/s^2, runs: 2 + plotting maneuver: gas step response: +1m/s^2 from 20mph, runs: 2 + + Report written to /home/batman/openpilot/tools/longitudinal_maneuvers/longitudinal_reports/LEXUS_ES_TSS2_57048cfce01d9625_0000010e--5b26bc3be7.html + ``` + +You can reach out on [Discord](https://discord.comma.ai) if you have any questions about these instructions or the tool itself. From e549f7af45e49390b38f66d1894167091f867479 Mon Sep 17 00:00:00 2001 From: Jason Wen Date: Tue, 17 Sep 2024 19:23:27 -0400 Subject: [PATCH 076/214] tests: fix selfdrive state machine import (#33571) * selfdrive: Fix state machine test imports * it's the same file * Update selfdrive/selfdrived/tests/test_state_machine.py * Update selfdrive/selfdrived/tests/test_state_machine.py --------- Co-authored-by: Shane Smiskol --- selfdrive/selfdrived/tests/test_state_machine.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/selfdrived/tests/test_state_machine.py b/selfdrive/selfdrived/tests/test_state_machine.py index 4274ba9f67..b720f48f1e 100644 --- a/selfdrive/selfdrived/tests/test_state_machine.py +++ b/selfdrive/selfdrived/tests/test_state_machine.py @@ -1,6 +1,6 @@ from cereal import log from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.controls.lib.selfdrive import StateMachine, SOFT_DISABLE_TIME +from openpilot.selfdrive.selfdrived.state import StateMachine, SOFT_DISABLE_TIME from openpilot.selfdrive.selfdrived.events import Events, ET, EVENTS, NormalPermanentAlert State = log.SelfdriveState.OpenpilotState From fe2bd2e0e3ecd43fba2eeb2ddd52620325a0b4c1 Mon Sep 17 00:00:00 2001 From: Nelson Chen Date: Tue, 17 Sep 2024 16:42:24 -0700 Subject: [PATCH 077/214] Add clip to longitudinal_maneuvers README (#33574) Added to step 5, really ties together the images from step 4 and 6. --- tools/longitudinal_maneuvers/README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/tools/longitudinal_maneuvers/README.md b/tools/longitudinal_maneuvers/README.md index b0f5897d08..f1981d9b1e 100644 --- a/tools/longitudinal_maneuvers/README.md +++ b/tools/longitudinal_maneuvers/README.md @@ -19,6 +19,9 @@ Test your vehicle's longitudinal control with this tool. The tool will test the ![videoframe_6652](https://github.com/user-attachments/assets/e9d4c95a-cd76-4ab7-933e-19937792fa0f) 5. Ensure the road ahead is clear, as openpilot will not brake for any obstructions in this mode. If so, press "Set" on your steering wheel to start the tests. The tests will run for about 4 minutes. If you need to pause the tests, press "Cancel" on your steering wheel. You can resume the tests by pressing "Resume" on your steering wheel. + + ![cog-clip-00 01 11 250-00 01 22 250](https://github.com/user-attachments/assets/c312c1cc-76e8-46e1-a05e-bb9dfb58994f) + 6. When the testing is complete, you'll see an alert that says "Maneuvers Finished," complete the route by pulling over and turning off the vehicle. ![fin2](https://github.com/user-attachments/assets/c06960ae-7cfb-44af-beaa-4dc28848e49d) From 163e7406c2cfe6e4f75be1a5e70e44b3f19c0adf Mon Sep 17 00:00:00 2001 From: commaci-public <60409688+commaci-public@users.noreply.github.com> Date: Tue, 17 Sep 2024 17:54:24 -0700 Subject: [PATCH 078/214] [bot] Update Python packages (#33576) Update Python packages Co-authored-by: Vehicle Researcher --- opendbc_repo | 2 +- panda | 2 +- uv.lock | 25 ++++++++++++------------- 3 files changed, 14 insertions(+), 15 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index 57ebdbfa05..c8beb979ec 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 57ebdbfa0553d4002bf1fd654e4631931f2b676c +Subproject commit c8beb979ecd675adeae0c35df7ba4b71f90685d6 diff --git a/panda b/panda index 2526d1ee4b..93aedd987b 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 2526d1ee4b7b740b5f5786c25638ee1528d425be +Subproject commit 93aedd987bda7e267210689b877eb87f288fc6ab diff --git a/uv.lock b/uv.lock index 16207cf26e..3d60cefd68 100644 --- a/uv.lock +++ b/uv.lock @@ -190,7 +190,7 @@ wheels = [ [[package]] name = "azure-storage-blob" -version = "12.22.0" +version = "12.23.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "azure-core" }, @@ -198,9 +198,9 @@ dependencies = [ { name = "isodate" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/92/de/9cea85c0d5fc21f99bcf9f060fc2287cb95236b70431fa63cb69890a121e/azure-storage-blob-12.22.0.tar.gz", hash = "sha256:b3804bb4fe8ab1c32771fa464053da772a682c2737b19da438a3f4e5e3b3736e", size = 564873 } +sdist = { url = "https://files.pythonhosted.org/packages/6b/64/eb0fbd7865463d9551bcfd6a92947d235f2128aa0b12b6f0254959aa31eb/azure_storage_blob-12.23.0.tar.gz", hash = "sha256:2fadbceda1d99c4a72dfd32e0122d7bca8b5e8d2563f5c624d634aeaff49c9df", size = 566106 } wheels = [ - { url = "https://files.pythonhosted.org/packages/a8/52/b578c94048469fbf9f6378e2b2a46a2d0ccba3d59a7845dbed22ebf61601/azure_storage_blob-12.22.0-py3-none-any.whl", hash = "sha256:bb7d2d824ce3f11f14a27ee7d9281289f7e072ac8311c52e3652672455b7d5e8", size = 404892 }, + { url = "https://files.pythonhosted.org/packages/60/02/024b71fc0af7a361cfaecbd96120615ef53787e0b4213285e18eb259d198/azure_storage_blob-12.23.0-py3-none-any.whl", hash = "sha256:8ac4b34624ed075eda1e38f0c6dadb601e1b199e27a09aa63edc429bf4a23329", size = 405594 }, ] [[package]] @@ -603,11 +603,11 @@ wheels = [ [[package]] name = "filelock" -version = "3.16.0" +version = "3.16.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e6/76/3981447fd369539aba35797db99a8e2ff7ed01d9aa63e9344a31658b8d81/filelock-3.16.0.tar.gz", hash = "sha256:81de9eb8453c769b63369f87f11131a7ab04e367f8d97ad39dc230daa07e3bec", size = 18008 } +sdist = { url = "https://files.pythonhosted.org/packages/9d/db/3ef5bb276dae18d6ec2124224403d1d67bccdbefc17af4cc8f553e341ab1/filelock-3.16.1.tar.gz", hash = "sha256:c249fbfcd5db47e5e2d6d62198e565475ee65e4831e2561c8e313fa7eb961435", size = 18037 } wheels = [ - { url = "https://files.pythonhosted.org/packages/2f/95/f9310f35376024e1086c59cbb438d319fc9a4ef853289ce7c661539edbd4/filelock-3.16.0-py3-none-any.whl", hash = "sha256:f6ed4c963184f4c84dd5557ce8fece759a3724b37b80c6c4f20a2f63a4dc6609", size = 16170 }, + { url = "https://files.pythonhosted.org/packages/b9/f8/feced7779d755758a52d1f6635d990b8d98dc0a29fa568bbe0625f18fdf3/filelock-3.16.1-py3-none-any.whl", hash = "sha256:2082e5703d51fbf98ea75855d9d5527e33d8ff23099bec374a134febee6946b0", size = 16163 }, ] [[package]] @@ -1709,11 +1709,11 @@ wheels = [ [[package]] name = "platformdirs" -version = "4.3.3" +version = "4.3.6" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/f5/19/f7bee3a71decedd8d7bc4d3edb7970b8e899f3caef257b0f0d623f2f7b11/platformdirs-4.3.3.tar.gz", hash = "sha256:d4e0b7d8ec176b341fb03cb11ca12d0276faa8c485f9cd218f613840463fc2c0", size = 21304 } +sdist = { url = "https://files.pythonhosted.org/packages/13/fc/128cc9cb8f03208bdbf93d3aa862e16d376844a14f9a0ce5cf4507372de4/platformdirs-4.3.6.tar.gz", hash = "sha256:357fb2acbc885b0419afd3ce3ed34564c13c9b95c89360cd9563f73aa5e2b907", size = 21302 } wheels = [ - { url = "https://files.pythonhosted.org/packages/69/e6/7c8e8c326903bd97c6c0c47e0a3c5de815faaae986cab7defdeddf5fddcd/platformdirs-4.3.3-py3-none-any.whl", hash = "sha256:50a5450e2e84f44539718293cbb1da0a0885c9d14adf21b77bae4e66fc99d9b5", size = 18437 }, + { url = "https://files.pythonhosted.org/packages/3c/a6/bc1012356d8ece4d66dd75c4b9fc6c1f6650ddd5991e421177d9f8f671be/platformdirs-4.3.6-py3-none-any.whl", hash = "sha256:73e575e1408ab8103900836b97580d5307456908a03e92031bab39e4554cc3fb", size = 18439 }, ] [[package]] @@ -4598,15 +4598,14 @@ wheels = [ [[package]] name = "pytest-cpp" -version = "2.5.0" +version = "2.6.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "colorama" }, { name = "pytest" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/0f/72/6da4fd6ea5afd44e10dbed76ef666c0732e27317a753099bc163f3330a91/pytest-cpp-2.5.0.tar.gz", hash = "sha256:695604baa21bc95291bb4ea7263a7aa960753de57c2d17d224c4652fbcf65cdc", size = 465039 } +sdist = { url = "https://files.pythonhosted.org/packages/cf/a1/c2679d7ff2da20a0f89c7820ae2739cde739eac9b43c192531117b31b5f4/pytest_cpp-2.6.0.tar.gz", hash = "sha256:c2f49d3c038539ac84786a94d852e4f4619c34c95979c2bc69c20b3bdf051d85", size = 465490 } wheels = [ - { url = "https://files.pythonhosted.org/packages/32/d5/b7b5c75dc2e11555898fbec78f88970c43f27439436ac83e65de6afcd2c6/pytest_cpp-2.5.0-py3-none-any.whl", hash = "sha256:137bcaa6487307b4c362245fcd4abf35de64ee85e6375f4d06cd31e6a64f9701", size = 15064 }, + { url = "https://files.pythonhosted.org/packages/2a/44/dc2f5d53165264ae5831f361fe7723c45da05718a97015b2eddc452cf503/pytest_cpp-2.6.0-py3-none-any.whl", hash = "sha256:b33de94609450feea2fba9efff3558b8ac8f1fdf40a99e263b395d4798b911bb", size = 15074 }, ] [[package]] From 45b887a08e6dac09a47264dd9936bf3602cb65bd Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 18 Sep 2024 12:04:08 +0800 Subject: [PATCH 079/214] ci: add toggles to ui report (#33577) add toggles --- .github/workflows/ui_preview.yaml | 2 +- selfdrive/ui/tests/test_ui/run.py | 6 ++++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ui_preview.yaml b/.github/workflows/ui_preview.yaml index 877951f623..7880ecdea6 100644 --- a/.github/workflows/ui_preview.yaml +++ b/.github/workflows/ui_preview.yaml @@ -84,7 +84,7 @@ jobs: run: >- sudo apt-get install -y imagemagick - scenes="homescreen settings_device offroad_alert update_available prime onroad onroad_sidebar onroad_wide onroad_wide_sidebar onroad_alert_small onroad_alert_mid onroad_alert_full driver_camera body keyboard" + scenes="homescreen settings_device settings_toggles offroad_alert update_available prime onroad onroad_sidebar onroad_wide onroad_wide_sidebar onroad_alert_small onroad_alert_mid onroad_alert_full driver_camera body keyboard" A=($scenes) DIFF="" diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index b6e99190fc..6f8acb1a53 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -40,6 +40,11 @@ def setup_homescreen(click, pm: PubMaster): def setup_settings_device(click, pm: PubMaster): click(100, 100) +def setup_settings_toggles(click, pm: PubMaster): + setup_settings_device(click, pm) + click(278, 760) + time.sleep(UI_DELAY) + def setup_onroad(click, pm: PubMaster): vipc_server = VisionIpcServer("camerad") for stream_type, cam, _ in STREAMS: @@ -141,6 +146,7 @@ CASES = { "prime": setup_homescreen, "pair_device": setup_pair_device, "settings_device": setup_settings_device, + "settings_toggles": setup_settings_toggles, "onroad": setup_onroad, "onroad_sidebar": setup_onroad_sidebar, "onroad_alert_small": setup_onroad_alert_small, From 41a7fa06235cc4ad58921b18d40f199cdf9205bb Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Wed, 18 Sep 2024 13:57:02 -0400 Subject: [PATCH 080/214] FCA Giorgio: Reserve safety ID (#33580) reserve safety ID for FCA Giorgio --- cereal/car.capnp | 1 + 1 file changed, 1 insertion(+) diff --git a/cereal/car.capnp b/cereal/car.capnp index 2c18c7c617..d08d89c1d9 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -619,6 +619,7 @@ struct CarParams { volkswagenMqbEvo @29; chryslerCusw @30; psa @31; + fcaGiorgio @32; } enum SteerControlType { From b733b875f8e06195c89511717031d1fcfc880fd2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 18 Sep 2024 15:51:03 -0700 Subject: [PATCH 081/214] camerad: ci -> sensor rename (#33582) * camerad: ci -> sensor rename * no behavior change for now --- system/camerad/cameras/camera_common.cc | 22 +-- system/camerad/cameras/camera_common.h | 3 +- system/camerad/cameras/camera_qcom2.cc | 211 +++++++++++------------- system/camerad/cameras/camera_qcom2.h | 27 +-- system/camerad/cameras/camera_util.cc | 15 +- system/camerad/sensors/ar0231.cc | 6 +- 6 files changed, 138 insertions(+), 146 deletions(-) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index 6c745e1cde..e99b4168bc 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -19,15 +19,15 @@ class ImgProc { public: ImgProc(cl_device_id device_id, cl_context context, const CameraBuf *b, const CameraState *s, int buf_width, int uv_offset) { char args[4096]; - const SensorInfo *ci = s->ci.get(); + const SensorInfo *sensor = s->sensor.get(); snprintf(args, sizeof(args), "-cl-fast-relaxed-math -cl-denorms-are-zero -Isensors " "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d " "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DYUV_STRIDE=%d -DUV_OFFSET=%d " "-DSENSOR_ID=%hu -DHDR_OFFSET=%d -DVIGNETTING=%d ", - ci->frame_width, ci->frame_height, ci->hdr_offset > 0 ? ci->frame_stride * 2 : ci->frame_stride, ci->frame_offset, + sensor->frame_width, sensor->frame_height, sensor->hdr_offset > 0 ? sensor->frame_stride * 2 : sensor->frame_stride, sensor->frame_offset, b->rgb_width, b->rgb_height, buf_width, uv_offset, - static_cast(ci->image_sensor), ci->hdr_offset, s->camera_num == 1); + static_cast(sensor->image_sensor), sensor->hdr_offset, s->cc.camera_num == 1); const char *cl_file = "cameras/process_raw.cl"; cl_program prg_imgproc = cl_program_from_file(context, device_id, cl_file, args); krnl_ = CL_CHECK_ERR(clCreateKernel(prg_imgproc, "process_raw", &err)); @@ -67,9 +67,9 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, stream_type = type; frame_buf_count = frame_cnt; - const SensorInfo *ci = s->ci.get(); + const SensorInfo *sensor = s->sensor.get(); // RAW frame - const int frame_size = (ci->frame_height + ci->extra_height) * ci->frame_stride; + const int frame_size = (sensor->frame_height + sensor->extra_height) * sensor->frame_stride; camera_bufs = std::make_unique(frame_buf_count); camera_bufs_metadata = std::make_unique(frame_buf_count); @@ -79,8 +79,8 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, } LOGD("allocated %d CL buffers", frame_buf_count); - rgb_width = ci->frame_width; - rgb_height = ci->hdr_offset > 0 ? (ci->frame_height - ci->hdr_offset) / 2 : ci->frame_height; + rgb_width = sensor->frame_width; + rgb_height = sensor->hdr_offset > 0 ? (sensor->frame_height - sensor->hdr_offset) / 2 : sensor->frame_height; int nv12_width = VENUS_Y_STRIDE(COLOR_FMT_NV12, rgb_width); int nv12_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, rgb_height); @@ -151,9 +151,9 @@ void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &fr framed.setProcessingTime(frame_data.processing_time); const float ev = c->cur_ev[frame_data.frame_id % 3]; - const float perc = util::map_val(ev, c->ci->min_ev, c->ci->max_ev, 0.0f, 100.0f); + const float perc = util::map_val(ev, c->sensor->min_ev, c->sensor->max_ev, 0.0f, 100.0f); framed.setExposureValPercent(perc); - framed.setSensor(c->ci->image_sensor); + framed.setSensor(c->sensor->image_sensor); } kj::Array get_raw_frame_image(const CameraBuf *b) { @@ -294,10 +294,10 @@ void camerad_thread() { { MultiCameraState cameras; + cameras.pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); VisionIpcServer vipc_server("camerad", device_id, context); - cameras_open(&cameras); - cameras_init(&vipc_server, &cameras, device_id, context); + cameras_init(&cameras, &vipc_server, device_id, context); vipc_server.start_listener(); diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 7c2fbaeec8..03d9cfd6ae 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -71,8 +71,7 @@ void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &fr kj::Array get_raw_frame_image(const CameraBuf *b); float set_exposure_target(const CameraBuf *b, Rect ae_xywh, int x_skip, int y_skip); void publish_thumbnail(PubMaster *pm, const CameraBuf *b); -void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx); -void cameras_open(MultiCameraState *s); +void cameras_init(MultiCameraState *s, VisionIpcServer *v, cl_device_id device_id, cl_context ctx); void cameras_run(MultiCameraState *s); void cameras_close(MultiCameraState *s); void camerad_thread(); diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 0648ddf4de..a2c836c730 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -17,25 +17,27 @@ #include "media/cam_req_mgr.h" #include "media/cam_sensor_cmn_header.h" #include "media/cam_sync.h" + +#include "common/params.h" #include "common/swaglog.h" const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py -// For debugging: -// echo "4294967295" > /sys/module/cam_debug_util/parameters/debug_mdl - ExitHandler do_exit; CameraState::CameraState(MultiCameraState *multi_camera_state, const CameraConfig &config) : multi_cam_state(multi_camera_state), - camera_num(config.camera_num), - stream_type(config.stream_type), - focal_len(config.focal_len), - publish_name(config.publish_name), - init_camera_state(config.init_camera_state), - enabled(config.enabled) { + enabled(config.enabled) , + cc(config) { +} + +CameraState::~CameraState() { + if (open) { + camera_close(); + } } + int CameraState::clear_req_queue() { struct cam_req_mgr_flush_info req_mgr_flush_request = {0}; req_mgr_flush_request.session_hdl = session_handle; @@ -50,8 +52,8 @@ int CameraState::clear_req_queue() { void CameraState::sensors_start() { if (!enabled) return; - LOGD("starting sensor %d", camera_num); - sensors_i2c(ci->start_reg_array.data(), ci->start_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, ci->data_word); + LOGD("starting sensor %d", cc.camera_num); + sensors_i2c(sensor->start_reg_array.data(), sensor->start_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, sensor->data_word); } void CameraState::sensors_poke(int request_id) { @@ -66,7 +68,7 @@ void CameraState::sensors_poke(int request_id) { int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); if (ret != 0) { - LOGE("** sensor %d FAILED poke, disabling", camera_num); + LOGE("** sensor %d FAILED poke, disabling", cc.camera_num); enabled = false; return; } @@ -96,7 +98,7 @@ void CameraState::sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); if (ret != 0) { - LOGE("** sensor %d FAILED i2c, disabling", camera_num); + LOGE("** sensor %d FAILED i2c, disabling", cc.camera_num); enabled = false; return; } @@ -125,8 +127,8 @@ int CameraState::sensors_init() { auto i2c_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); auto probe = (struct cam_cmd_probe *)(i2c_info.get() + 1); - probe->camera_id = camera_num; - i2c_info->slave_addr = ci->getSlaveAddress(camera_num); + probe->camera_id = cc.camera_num; + i2c_info->slave_addr = sensor->getSlaveAddress(cc.camera_num); // 0(I2C_STANDARD_MODE) = 100khz, 1(I2C_FAST_MODE) = 400khz //i2c_info->i2c_freq_mode = I2C_STANDARD_MODE; i2c_info->i2c_freq_mode = I2C_FAST_MODE; @@ -136,8 +138,8 @@ int CameraState::sensors_init() { probe->addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; probe->op_code = 3; // don't care? probe->cmd_type = CAMERA_SENSOR_CMD_TYPE_PROBE; - probe->reg_addr = ci->probe_reg_addr; - probe->expected_data = ci->probe_expected_data; + probe->reg_addr = sensor->probe_reg_addr; + probe->expected_data = sensor->probe_expected_data; probe->data_mask = 0; //buf_desc[1].size = buf_desc[1].length = 148; @@ -159,7 +161,7 @@ int CameraState::sensors_init() { power->count = 1; power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; power->power_settings[0].power_seq_type = 0; - power->power_settings[0].config_val_low = ci->mclk_frequency; + power->power_settings[0].config_val_low = sensor->mclk_frequency; power = power_set_wait(power, 1); // reset high @@ -312,10 +314,10 @@ void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int b if (io_mem_handle != 0) { io_cfg[0].mem_handle[0] = io_mem_handle; io_cfg[0].planes[0] = (struct cam_plane_cfg){ - .width = ci->frame_width, - .height = ci->frame_height + ci->extra_height, - .plane_stride = ci->frame_stride, - .slice_height = ci->frame_height + ci->extra_height, + .width = sensor->frame_width, + .height = sensor->frame_height + sensor->extra_height, + .plane_stride = sensor->frame_stride, + .slice_height = sensor->frame_height + sensor->extra_height, .meta_stride = 0x0, // YUV has meta(stride=0x400, size=0x5000) .meta_size = 0x0, .meta_offset = 0x0, @@ -325,10 +327,10 @@ void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int b .h_init = 0x0, .v_init = 0x0, }; - io_cfg[0].format = ci->mipi_format; // CAM_FORMAT_UBWC_TP10 for YUV + io_cfg[0].format = sensor->mipi_format; // CAM_FORMAT_UBWC_TP10 for YUV io_cfg[0].color_space = CAM_COLOR_SPACE_BASE; // CAM_COLOR_SPACE_BT601_FULL for YUV io_cfg[0].color_pattern = 0x5; // 0x0 for YUV - io_cfg[0].bpp = (ci->mipi_format == CAM_FORMAT_MIPI_RAW_10 ? 0xa : 0xc); // bits per pixel + io_cfg[0].bpp = (sensor->mipi_format == CAM_FORMAT_MIPI_RAW_10 ? 0xa : 0xc); // bits per pixel io_cfg[0].resource_type = CAM_ISP_IFE_OUT_RES_RDI_0; // CAM_ISP_IFE_OUT_RES_FULL for YUV io_cfg[0].fence = fence; io_cfg[0].direction = CAM_BUF_OUTPUT; @@ -409,9 +411,9 @@ void CameraState::set_exposure_rect() { // set areas for each camera, shouldn't be changed std::vector> ae_targets = { // (Rect, F) - std::make_pair((Rect){96, 250, 1734, 524}, 567.0), // wide + std::make_pair((Rect){96, 250, 1734, 524}, 567.0), // wide std::make_pair((Rect){96, 160, 1734, 986}, 2648.0), // road - std::make_pair((Rect){96, 242, 1736, 906}, 567.0) // driver + std::make_pair((Rect){96, 242, 1736, 906}, 567.0) // driver }; int h_ref = 1208; /* @@ -422,7 +424,7 @@ void CameraState::set_exposure_rect() { [0, 0, 1] ] */ - auto ae_target = ae_targets[camera_num]; + auto ae_target = ae_targets[cc.camera_num]; Rect xywh_ref = ae_target.first; float fl_ref = ae_target.second; @@ -435,9 +437,9 @@ void CameraState::set_exposure_rect() { } void CameraState::sensor_set_parameters() { - dc_gain_weight = ci->dc_gain_min_weight; - gain_idx = ci->analog_gain_rec_idx; - cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight) * ci->sensor_analog_gains[gain_idx] * exposure_time; + dc_gain_weight = sensor->dc_gain_min_weight; + gain_idx = sensor->analog_gain_rec_idx; + cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight) * sensor->sensor_analog_gains[gain_idx] * exposure_time; } void CameraState::camera_map_bufs() { @@ -458,11 +460,11 @@ void CameraState::camera_map_bufs() { void CameraState::camera_init(VisionIpcServer * v, cl_device_id device_id, cl_context ctx) { if (!enabled) return; - LOGD("camera init %d", camera_num); - buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, stream_type); + LOGD("camera init %d", cc.camera_num); + buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, cc.stream_type); camera_map_bufs(); - fl_pix = focal_len / ci->pixel_size_mm; + fl_pix = cc.focal_len / sensor->pixel_size_mm; set_exposure_rect(); } @@ -473,23 +475,24 @@ void CameraState::camera_open() { return; } + open = true; configISP(); configCSIPHY(); linkDevices(); } bool CameraState::openSensor() { - sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", camera_num); + sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", cc.camera_num); assert(sensor_fd >= 0); - LOGD("opened sensor for %d", camera_num); + LOGD("opened sensor for %d", cc.camera_num); // init memorymanager for this camera mm.init(multi_cam_state->video0_fd); - LOGD("-- Probing sensor %d", camera_num); + LOGD("-- Probing sensor %d", cc.camera_num); - auto init_sensor_lambda = [this](SensorInfo *sensor) { - ci.reset(sensor); + auto init_sensor_lambda = [this](SensorInfo *s) { + sensor.reset(s); int ret = sensors_init(); if (ret == 0) { sensor_set_parameters(); @@ -501,11 +504,11 @@ bool CameraState::openSensor() { if (!init_sensor_lambda(new AR0231) && !init_sensor_lambda(new OX03C10) && !init_sensor_lambda(new OS04C10)) { - LOGE("** sensor %d FAILED bringup, disabling", camera_num); + LOGE("** sensor %d FAILED bringup, disabling", cc.camera_num); enabled = false; return false; } - LOGD("-- Probing sensor %d success", camera_num); + LOGD("-- Probing sensor %d success", cc.camera_num); // create session struct cam_req_mgr_session_info session_info = {}; @@ -521,7 +524,7 @@ bool CameraState::openSensor() { LOGD("acquire sensor dev"); LOG("-- Configuring sensor"); - sensors_i2c(ci->init_reg_array.data(), ci->init_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, ci->data_word); + sensors_i2c(sensor->init_reg_array.data(), sensor->init_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, sensor->data_word); return true; } @@ -531,30 +534,29 @@ void CameraState::configISP() { if (!enabled) return; struct cam_isp_in_port_info in_port_info = { - .res_type = (uint32_t[]){CAM_ISP_IFE_IN_RES_PHY_0, CAM_ISP_IFE_IN_RES_PHY_1, CAM_ISP_IFE_IN_RES_PHY_2}[camera_num], - + .res_type = cc.phy, .lane_type = CAM_ISP_LANE_TYPE_DPHY, .lane_num = 4, .lane_cfg = 0x3210, .vc = 0x0, - .dt = ci->frame_data_type, - .format = ci->mipi_format, + .dt = sensor->frame_data_type, + .format = sensor->mipi_format, .test_pattern = 0x2, // 0x3? .usage_type = 0x0, .left_start = 0, - .left_stop = ci->frame_width - 1, - .left_width = ci->frame_width, + .left_stop = sensor->frame_width - 1, + .left_width = sensor->frame_width, .right_start = 0, - .right_stop = ci->frame_width - 1, - .right_width = ci->frame_width, + .right_stop = sensor->frame_width - 1, + .right_width = sensor->frame_width, .line_start = 0, - .line_stop = ci->frame_height + ci->extra_height - 1, - .height = ci->frame_height + ci->extra_height, + .line_stop = sensor->frame_height + sensor->extra_height - 1, + .height = sensor->frame_height + sensor->extra_height, .pixel_clk = 0x0, .batch_size = 0x0, @@ -565,9 +567,9 @@ void CameraState::configISP() { .num_out_res = 0x1, .data[0] = (struct cam_isp_out_port_info){ .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, - .format = ci->mipi_format, - .width = ci->frame_width, - .height = ci->frame_height + ci->extra_height, + .format = sensor->mipi_format, + .width = sensor->frame_width, + .height = sensor->frame_height + sensor->extra_height, .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, }, }; @@ -590,9 +592,9 @@ void CameraState::configISP() { } void CameraState::configCSIPHY() { - csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", camera_num); + csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", cc.camera_num); assert(csiphy_fd >= 0); - LOGD("opened csiphy for %d", camera_num); + LOGD("opened csiphy for %d", cc.camera_num); struct cam_csiphy_acquire_dev_info csiphy_acquire_dev_info = {.combo_mode = 0}; auto csiphy_dev_handle_ = device_acquire(csiphy_fd, session_handle, &csiphy_acquire_dev_info); @@ -659,15 +661,7 @@ void CameraState::linkDevices() { //LOGD("start sensor: %d", ret); } -void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { - s->driver_cam.camera_init(v, device_id, ctx); - s->road_cam.camera_init(v, device_id, ctx); - s->wide_road_cam.camera_init(v, device_id, ctx); - - s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); -} - -void cameras_open(MultiCameraState *s) { +void cameras_init(MultiCameraState *s, VisionIpcServer *v, cl_device_id device_id, cl_context ctx) { LOG("-- Opening devices"); // video0 is req_mgr, the target of many ioctls s->video0_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-soc:qcom_cam-req-mgr-video-index0", O_RDWR | O_NONBLOCK)); @@ -706,17 +700,23 @@ void cameras_open(MultiCameraState *s) { ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); LOGD("req mgr subscribe: %d", ret); + // open s->driver_cam.camera_open(); LOGD("driver camera opened"); s->road_cam.camera_open(); LOGD("road camera opened"); s->wide_road_cam.camera_open(); LOGD("wide road camera opened"); + + // init + s->driver_cam.camera_init(v, device_id, ctx); + s->road_cam.camera_init(v, device_id, ctx); + s->wide_road_cam.camera_init(v, device_id, ctx); } void CameraState::camera_close() { // stop devices - LOG("-- Stop devices %d", camera_num); + LOG("-- Stop devices %d", cc.camera_num); if (enabled) { // ret = device_control(sensor_fd, CAM_STOP_DEV, session_handle, sensor_dev_handle); @@ -762,15 +762,7 @@ void CameraState::camera_close() { // destroyed session struct cam_req_mgr_session_info session_info = {.session_hdl = session_handle}; ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_DESTROY_SESSION, &session_info, sizeof(session_info)); - LOGD("destroyed session %d: %d", camera_num, ret); -} - -void cameras_close(MultiCameraState *s) { - s->driver_cam.camera_close(); - s->road_cam.camera_close(); - s->wide_road_cam.camera_close(); - - delete s->pm; + LOGD("destroyed session %d: %d", cc.camera_num, ret); } void CameraState::handle_camera_event(void *evdat) { @@ -789,7 +781,7 @@ void CameraState::handle_camera_event(void *evdat) { // check for skipped frames if (main_id > frame_id_last + 1 && !skipped) { - LOGE("camera %d realign", camera_num); + LOGE("camera %d realign", cc.camera_num); clear_req_queue(); enqueue_req_multi(real_id + 1, FRAME_BUF_COUNT - 1, 0); skipped = true; @@ -799,7 +791,7 @@ void CameraState::handle_camera_event(void *evdat) { // check for dropped requests if (real_id > request_id_last + 1) { - LOGE("camera %d dropped requests %ld %ld", camera_num, real_id, request_id_last); + LOGE("camera %d dropped requests %ld %ld", cc.camera_num, real_id, request_id_last); enqueue_req_multi(request_id_last + 1 + FRAME_BUF_COUNT, real_id - (request_id_last + 1), 0); } @@ -812,7 +804,7 @@ void CameraState::handle_camera_event(void *evdat) { meta_data.request_id = real_id; meta_data.timestamp_sof = timestamp; exp_lock.lock(); - meta_data.gain = analog_gain_frac * (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight); + meta_data.gain = analog_gain_frac * (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight); meta_data.high_conversion_gain = dc_gain_enabled; meta_data.integ_lines = exposure_time; meta_data.measured_grey_fraction = measured_grey_fraction; @@ -823,7 +815,7 @@ void CameraState::handle_camera_event(void *evdat) { enqueue_req_multi(real_id + FRAME_BUF_COUNT, 1, 1); } else { // not ready if (main_id > frame_id_last + 10) { - LOGE("camera %d reset after half second of no response", camera_num); + LOGE("camera %d reset after half second of no response", cc.camera_num); clear_req_queue(); enqueue_req_multi(request_id_last + 1, FRAME_BUF_COUNT, 0); frame_id_last = main_id; @@ -833,7 +825,7 @@ void CameraState::handle_camera_event(void *evdat) { } void CameraState::update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain) { - float score = ci->getExposureScore(desired_ev, exp_t, exp_g_idx, exp_gain, gain_idx); + float score = sensor->getExposureScore(desired_ev, exp_t, exp_g_idx, exp_gain, gain_idx); if (score < best_ev_score) { new_exp_t = exp_t; new_exp_g = exp_g_idx; @@ -859,10 +851,10 @@ void CameraState::set_camera_exposure(float grey_frac) { const float cur_ev_ = cur_ev[buf.cur_frame_data.frame_id % 3]; // Scale target grey between 0.1 and 0.4 depending on lighting conditions - float new_target_grey = std::clamp(0.4 - 0.3 * log2(1.0 + ci->target_grey_factor*cur_ev_) / log2(6000.0), 0.1, 0.4); + float new_target_grey = std::clamp(0.4 - 0.3 * log2(1.0 + sensor->target_grey_factor*cur_ev_) / log2(6000.0), 0.1, 0.4); float target_grey = (1.0 - k_grey) * target_grey_fraction + k_grey * new_target_grey; - float desired_ev = std::clamp(cur_ev_ * target_grey / grey_frac, ci->min_ev, ci->max_ev); + float desired_ev = std::clamp(cur_ev_ * target_grey / grey_frac, sensor->min_ev, sensor->max_ev); float k = (1.0 - k_ev) / 3.0; desired_ev = (k * cur_ev[0]) + (k * cur_ev[1]) + (k * cur_ev[2]) + (k_ev * desired_ev); @@ -873,19 +865,20 @@ void CameraState::set_camera_exposure(float grey_frac) { // Hysteresis around high conversion gain // We usually want this on since it results in lower noise, but turn off in very bright day scenes bool enable_dc_gain = dc_gain_enabled; - if (!enable_dc_gain && target_grey < ci->dc_gain_on_grey) { + if (!enable_dc_gain && target_grey < sensor->dc_gain_on_grey) { enable_dc_gain = true; - dc_gain_weight = ci->dc_gain_min_weight; - } else if (enable_dc_gain && target_grey > ci->dc_gain_off_grey) { + dc_gain_weight = sensor->dc_gain_min_weight; + } else if (enable_dc_gain && target_grey > sensor->dc_gain_off_grey) { enable_dc_gain = false; - dc_gain_weight = ci->dc_gain_max_weight; + dc_gain_weight = sensor->dc_gain_max_weight; } - if (enable_dc_gain && dc_gain_weight < ci->dc_gain_max_weight) {dc_gain_weight += 1;} - if (!enable_dc_gain && dc_gain_weight > ci->dc_gain_min_weight) {dc_gain_weight -= 1;} + if (enable_dc_gain && dc_gain_weight < sensor->dc_gain_max_weight) {dc_gain_weight += 1;} + if (!enable_dc_gain && dc_gain_weight > sensor->dc_gain_min_weight) {dc_gain_weight -= 1;} std::string gain_bytes, time_bytes; if (env_ctrl_exp_from_params) { + static Params params; gain_bytes = params.get("CameraDebugExpGain"); time_bytes = params.get("CameraDebugExpTime"); } @@ -901,14 +894,14 @@ void CameraState::set_camera_exposure(float grey_frac) { } else { // Simple brute force optimizer to choose sensor parameters // to reach desired EV - for (int g = std::max((int)ci->analog_gain_min_idx, gain_idx - 1); g <= std::min((int)ci->analog_gain_max_idx, gain_idx + 1); g++) { - float gain = ci->sensor_analog_gains[g] * (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight); + for (int g = std::max((int)sensor->analog_gain_min_idx, gain_idx - 1); g <= std::min((int)sensor->analog_gain_max_idx, gain_idx + 1); g++) { + float gain = sensor->sensor_analog_gains[g] * (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight); // Compute optimal time for given gain - int t = std::clamp(int(std::round(desired_ev / gain)), ci->exposure_time_min, ci->exposure_time_max); + int t = std::clamp(int(std::round(desired_ev / gain)), sensor->exposure_time_min, sensor->exposure_time_max); // Only go below recommended gain when absolutely necessary to not overexpose - if (g < ci->analog_gain_rec_idx && t > 20 && g < gain_idx) { + if (g < sensor->analog_gain_rec_idx && t > 20 && g < gain_idx) { continue; } @@ -921,12 +914,12 @@ void CameraState::set_camera_exposure(float grey_frac) { measured_grey_fraction = grey_frac; target_grey_fraction = target_grey; - analog_gain_frac = ci->sensor_analog_gains[new_exp_g]; + analog_gain_frac = sensor->sensor_analog_gains[new_exp_g]; gain_idx = new_exp_g; exposure_time = new_exp_t; dc_gain_enabled = enable_dc_gain; - float gain = analog_gain_frac * (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight); + float gain = analog_gain_frac * (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight); cur_ev[buf.cur_frame_data.frame_id % 3] = exposure_time * gain; exp_lock.unlock(); @@ -937,39 +930,35 @@ void CameraState::set_camera_exposure(float grey_frac) { if (ms < 60) { util::sleep_for(60 - ms); } - // LOGE("ae - camera %d, cur_t %.5f, sof %.5f, dt %.5f", camera_num, 1e-9 * nanos_since_boot(), 1e-9 * buf.cur_frame_data.timestamp_sof, 1e-9 * (nanos_since_boot() - buf.cur_frame_data.timestamp_sof)); + // LOGE("ae - camera %d, cur_t %.5f, sof %.5f, dt %.5f", cc.camera_num, 1e-9 * nanos_since_boot(), 1e-9 * buf.cur_frame_data.timestamp_sof, 1e-9 * (nanos_since_boot() - buf.cur_frame_data.timestamp_sof)); - auto exp_reg_array = ci->getExposureRegisters(exposure_time, new_exp_g, dc_gain_enabled); - sensors_i2c(exp_reg_array.data(), exp_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, ci->data_word); + auto exp_reg_array = sensor->getExposureRegisters(exposure_time, new_exp_g, dc_gain_enabled); + sensors_i2c(exp_reg_array.data(), exp_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, sensor->data_word); } void CameraState::run() { - util::set_thread_name(publish_name); + util::set_thread_name(cc.publish_name); for (uint32_t cnt = 0; !do_exit; ++cnt) { // Acquire the buffer; continue if acquisition fails if (!buf.acquire()) continue; MessageBuilder msg; - auto framed = (msg.initEvent().*init_camera_state)(); + auto framed = (msg.initEvent().*cc.init_camera_state)(); fill_frame_data(framed, buf.cur_frame_data, this); // Log raw frames for road camera - if (env_log_raw_frames && stream_type == VISION_STREAM_ROAD && cnt % 100 == 5) { // no overlap with qlog decimation + if (env_log_raw_frames && cc.stream_type == VISION_STREAM_ROAD && cnt % 100 == 5) { // no overlap with qlog decimation framed.setImage(get_raw_frame_image(&buf)); } - // Log frame id for road and wide road cameras - if (stream_type != VISION_STREAM_DRIVER) { - LOGT(buf.cur_frame_data.frame_id, "%s: Image set", publish_name); - } // Process camera registers and set camera exposure - ci->processRegisters(this, framed); - set_camera_exposure(set_exposure_target(&buf, ae_xywh, 2, stream_type != VISION_STREAM_DRIVER ? 2 : 4)); + sensor->processRegisters(this, framed); + set_camera_exposure(set_exposure_target(&buf, ae_xywh, 2, cc.stream_type != VISION_STREAM_DRIVER ? 2 : 4)); // Send the message - multi_cam_state->pm->send(publish_name, msg); - if (stream_type == VISION_STREAM_ROAD && cnt % 100 == 3) { + multi_cam_state->pm->send(cc.publish_name, msg); + if (cc.stream_type == VISION_STREAM_ROAD && cnt % 100 == 3) { publish_thumbnail(multi_cam_state->pm, &buf); // this takes 10ms??? } } @@ -1019,11 +1008,9 @@ void cameras_run(MultiCameraState *s) { if (env_debug_frames) { printf("sess_hdl 0x%6X, link_hdl 0x%6X, frame_id %lu, req_id %lu, timestamp %.2f ms, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp/1e6, event_data->u.frame_msg.sof_status); + do_exit = do_exit || event_data->u.frame_msg.frame_id > (1*20); } - // for debugging - //do_exit = do_exit || event_data->u.frame_msg.frame_id > (30*20); - if (event_data->session_hdl == s->road_cam.session_handle) { s->road_cam.handle_camera_event(event_data); } else if (event_data->session_hdl == s->wide_road_cam.session_handle) { @@ -1045,6 +1032,4 @@ void cameras_run(MultiCameraState *s) { LOG(" ************** STOPPING **************"); for (auto &t : threads) t.join(); - - cameras_close(s); } diff --git a/system/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h index 02ebeb71f3..bd53a326f3 100644 --- a/system/camerad/cameras/camera_qcom2.h +++ b/system/camerad/cameras/camera_qcom2.h @@ -3,10 +3,11 @@ #include #include +#include "media/cam_isp_ife.h" + #include "system/camerad/cameras/camera_common.h" #include "system/camerad/cameras/camera_util.h" #include "system/camerad/sensors/sensor.h" -#include "common/params.h" #include "common/util.h" #define FRAME_BUF_COUNT 4 @@ -18,6 +19,7 @@ struct CameraConfig { const char *publish_name; cereal::FrameData::Builder (cereal::Event::Builder::*init_camera_state)(); bool enabled; + uint32_t phy; }; const CameraConfig WIDE_ROAD_CAMERA_CONFIG = { @@ -27,6 +29,7 @@ const CameraConfig WIDE_ROAD_CAMERA_CONFIG = { .publish_name = "wideRoadCameraState", .init_camera_state = &cereal::Event::Builder::initWideRoadCameraState, .enabled = !getenv("DISABLE_WIDE_ROAD"), + .phy = CAM_ISP_IFE_IN_RES_PHY_0, }; const CameraConfig ROAD_CAMERA_CONFIG = { @@ -36,6 +39,7 @@ const CameraConfig ROAD_CAMERA_CONFIG = { .publish_name = "roadCameraState", .init_camera_state = &cereal::Event::Builder::initRoadCameraState, .enabled = !getenv("DISABLE_ROAD"), + .phy = CAM_ISP_IFE_IN_RES_PHY_1, }; const CameraConfig DRIVER_CAMERA_CONFIG = { @@ -45,17 +49,16 @@ const CameraConfig DRIVER_CAMERA_CONFIG = { .publish_name = "driverCameraState", .init_camera_state = &cereal::Event::Builder::initDriverCameraState, .enabled = !getenv("DISABLE_DRIVER"), + .phy = CAM_ISP_IFE_IN_RES_PHY_2, }; class CameraState { public: + CameraConfig cc; MultiCameraState *multi_cam_state = nullptr; - std::unique_ptr ci; + std::unique_ptr sensor; bool enabled = true; - VisionStreamType stream_type; - const char *publish_name = nullptr; - cereal::FrameData::Builder (cereal::Event::Builder::*init_camera_state)() = nullptr; - float focal_len = 0; + bool open = false; std::mutex exp_lock; @@ -77,10 +80,10 @@ public: unique_fd sensor_fd; unique_fd csiphy_fd; - int camera_num = 0; float fl_pix = 0; CameraState(MultiCameraState *multi_camera_state, const CameraConfig &config); + ~CameraState(); void handle_camera_event(void *evdat); void update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain); void set_camera_exposure(float grey_frac); @@ -128,14 +131,16 @@ private: void configISP(); void configCSIPHY(); void linkDevices(); - - // for debugging - Params params; }; class MultiCameraState { public: MultiCameraState(); + ~MultiCameraState() { + if (pm != nullptr) { + delete pm; + } + }; unique_fd video0_fd; unique_fd cam_sync_fd; @@ -147,5 +152,5 @@ public: CameraState wide_road_cam; CameraState driver_cam; - PubMaster *pm; + PubMaster *pm = nullptr; }; diff --git a/system/camerad/cameras/camera_util.cc b/system/camerad/cameras/camera_util.cc index 7bd23fd9fe..4d78556800 100644 --- a/system/camerad/cameras/camera_util.cc +++ b/system/camerad/cameras/camera_util.cc @@ -10,6 +10,9 @@ #include "common/swaglog.h" #include "common/util.h" +// For debugging: +// echo "4294967295" > /sys/module/cam_debug_util/parameters/debug_mdl + // ************** low level camera helpers **************** int do_cam_control(int fd, int op_code, void *handle, int size) { struct cam_control camcontrol = {0}; @@ -93,11 +96,7 @@ void release(int video0_fd, uint32_t handle) { assert(ret == 0); } -void release_fd(int video0_fd, uint32_t handle) { - // handle to fd - close(handle>>16); - release(video0_fd, handle); -} +// *** MemoryManager *** void *MemoryManager::alloc_buf(int size, uint32_t *handle) { lock.lock(); @@ -129,7 +128,11 @@ MemoryManager::~MemoryManager() { x.second.pop(); LOGD("freeing cached allocation %p with size %d", ptr, size_lookup[ptr]); munmap(ptr, size_lookup[ptr]); - release_fd(video0_fd, handle_lookup[ptr]); + + // release fd + close(handle_lookup[ptr] >> 16); + release(video0_fd, handle_lookup[ptr]); + handle_lookup.erase(ptr); size_lookup.erase(ptr); } diff --git a/system/camerad/sensors/ar0231.cc b/system/camerad/sensors/ar0231.cc index 9b688389c4..143e04c0b3 100644 --- a/system/camerad/sensors/ar0231.cc +++ b/system/camerad/sensors/ar0231.cc @@ -33,7 +33,7 @@ std::map> ar0231_build_register_lut(CameraState *c std::map> registers; for (int register_row = 0; register_row < 2; register_row++) { - uint8_t *registers_raw = data + c->ci->frame_stride * register_row; + uint8_t *registers_raw = data + c->sensor->frame_stride * register_row; assert(registers_raw[0] == 0x0a); // Start of line int value_tag_count = 0; @@ -58,7 +58,7 @@ std::map> ar0231_build_register_lut(CameraState *c cur_addr += 2; first_val_idx = val_idx; } else { - registers[cur_addr] = std::make_pair(first_val_idx + c->ci->frame_stride * register_row, val_idx + c->ci->frame_stride * register_row); + registers[cur_addr] = std::make_pair(first_val_idx + c->sensor->frame_stride * register_row, val_idx + c->sensor->frame_stride * register_row); } value_tag_count++; @@ -121,7 +121,7 @@ AR0231::AR0231() { void AR0231::processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const { const uint8_t expected_preamble[] = {0x0a, 0xaa, 0x55, 0x20, 0xa5, 0x55}; - uint8_t *data = (uint8_t *)c->buf.cur_camera_buf->addr + c->ci->registers_offset; + uint8_t *data = (uint8_t *)c->buf.cur_camera_buf->addr + c->sensor->registers_offset; if (memcmp(data, expected_preamble, std::size(expected_preamble)) != 0) { LOGE("unexpected register data found"); From 5378e63812dc3775e673dadc629b59ae282c60cf Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 18 Sep 2024 21:01:38 -0700 Subject: [PATCH 082/214] it's not really rgb --- system/camerad/cameras/camera_common.cc | 24 ++++++++++++------------ system/camerad/cameras/camera_common.h | 2 +- system/camerad/cameras/camera_qcom2.cc | 8 ++++---- system/camerad/test/test_ae_gray.cc | 6 +++--- 4 files changed, 20 insertions(+), 20 deletions(-) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index e99b4168bc..c89fc7f83a 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -26,7 +26,7 @@ public: "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DYUV_STRIDE=%d -DUV_OFFSET=%d " "-DSENSOR_ID=%hu -DHDR_OFFSET=%d -DVIGNETTING=%d ", sensor->frame_width, sensor->frame_height, sensor->hdr_offset > 0 ? sensor->frame_stride * 2 : sensor->frame_stride, sensor->frame_offset, - b->rgb_width, b->rgb_height, buf_width, uv_offset, + b->out_img_width, b->out_img_height, buf_width, uv_offset, static_cast(sensor->image_sensor), sensor->hdr_offset, s->cc.camera_num == 1); const char *cl_file = "cameras/process_raw.cl"; cl_program prg_imgproc = cl_program_from_file(context, device_id, cl_file, args); @@ -79,20 +79,20 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, } LOGD("allocated %d CL buffers", frame_buf_count); - rgb_width = sensor->frame_width; - rgb_height = sensor->hdr_offset > 0 ? (sensor->frame_height - sensor->hdr_offset) / 2 : sensor->frame_height; + out_img_width = sensor->frame_width; + out_img_height = sensor->hdr_offset > 0 ? (sensor->frame_height - sensor->hdr_offset) / 2 : sensor->frame_height; - int nv12_width = VENUS_Y_STRIDE(COLOR_FMT_NV12, rgb_width); - int nv12_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, rgb_height); - assert(nv12_width == VENUS_UV_STRIDE(COLOR_FMT_NV12, rgb_width)); - assert(nv12_height/2 == VENUS_UV_SCANLINES(COLOR_FMT_NV12, rgb_height)); + int nv12_width = VENUS_Y_STRIDE(COLOR_FMT_NV12, out_img_width); + int nv12_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, out_img_height); + assert(nv12_width == VENUS_UV_STRIDE(COLOR_FMT_NV12, out_img_width)); + assert(nv12_height/2 == VENUS_UV_SCANLINES(COLOR_FMT_NV12, out_img_height)); size_t nv12_uv_offset = nv12_width * nv12_height; // the encoder HW tells us the size it wants after setting it up. // TODO: VENUS_BUFFER_SIZE should give the size, but it's too small. dependent on encoder settings? - size_t nv12_size = (rgb_width <= 1344 ? 2900 : 2346)*nv12_width; + size_t nv12_size = (out_img_width <= 1344 ? 2900 : 2346)*nv12_width; - vipc_server->create_buffers_with_sizes(stream_type, YUV_BUFFER_COUNT, false, rgb_width, rgb_height, nv12_size, nv12_width, nv12_uv_offset); + vipc_server->create_buffers_with_sizes(stream_type, YUV_BUFFER_COUNT, false, out_img_width, out_img_height, nv12_size, nv12_width, nv12_uv_offset); LOGD("created %d YUV vipc buffers with size %dx%d", YUV_BUFFER_COUNT, nv12_width, nv12_height); imgproc = new ImgProc(device_id, context, this, s, nv12_width, nv12_uv_offset); @@ -118,7 +118,7 @@ bool CameraBuf::acquire() { cur_camera_buf = &camera_bufs[cur_buf_idx]; double start_time = millis_since_boot(); - imgproc->runKernel(camera_bufs[cur_buf_idx].buf_cl, cur_yuv_buf->buf_cl, rgb_width, rgb_height, cur_frame_data.integ_lines); + imgproc->runKernel(camera_bufs[cur_buf_idx].buf_cl, cur_yuv_buf->buf_cl, out_img_width, out_img_height, cur_frame_data.integ_lines); cur_frame_data.processing_time = (millis_since_boot() - start_time) / 1000.0; VisionIpcBufExtra extra = { @@ -244,7 +244,7 @@ static kj::Array yuv420_to_jpeg(const CameraBuf *b, int thumbnail_w } void publish_thumbnail(PubMaster *pm, const CameraBuf *b) { - auto thumbnail = yuv420_to_jpeg(b, b->rgb_width / 4, b->rgb_height / 4); + auto thumbnail = yuv420_to_jpeg(b, b->out_img_width / 4, b->out_img_height / 4); if (thumbnail.size() == 0) return; MessageBuilder msg; @@ -264,7 +264,7 @@ float set_exposure_target(const CameraBuf *b, Rect ae_xywh, int x_skip, int y_sk unsigned int lum_total = 0; for (int y = ae_xywh.y; y < ae_xywh.y + ae_xywh.h; y += y_skip) { for (int x = ae_xywh.x; x < ae_xywh.x + ae_xywh.w; x += x_skip) { - uint8_t lum = pix_ptr[(y * b->rgb_width) + x]; + uint8_t lum = pix_ptr[(y * b->out_img_width) + x]; lum_binning[lum]++; lum_total += 1; } diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 03d9cfd6ae..567a03c193 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -58,7 +58,7 @@ public: VisionBuf *cur_camera_buf; std::unique_ptr camera_bufs; std::unique_ptr camera_bufs_metadata; - int rgb_width, rgb_height; + int out_img_width, out_img_height; CameraBuf() = default; ~CameraBuf(); diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index a2c836c730..aa787dea8f 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -429,10 +429,10 @@ void CameraState::set_exposure_rect() { float fl_ref = ae_target.second; ae_xywh = (Rect){ - std::max(0, buf.rgb_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), - std::max(0, buf.rgb_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), - std::min((int)(fl_pix / fl_ref * xywh_ref.w), buf.rgb_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), - std::min((int)(fl_pix / fl_ref * xywh_ref.h), buf.rgb_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) + std::max(0, buf.out_img_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), + std::max(0, buf.out_img_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), + std::min((int)(fl_pix / fl_ref * xywh_ref.w), buf.out_img_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), + std::min((int)(fl_pix / fl_ref * xywh_ref.h), buf.out_img_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) }; } diff --git a/system/camerad/test/test_ae_gray.cc b/system/camerad/test/test_ae_gray.cc index be9a0cc59f..0620551ec6 100644 --- a/system/camerad/test/test_ae_gray.cc +++ b/system/camerad/test/test_ae_gray.cc @@ -34,11 +34,11 @@ TEST_CASE("camera.test_set_exposure_target") { uint8_t * fb_y = new uint8_t[W*H]; vb.y = fb_y; cb.cur_yuv_buf = &vb; - cb.rgb_width = W; - cb.rgb_height = H; + cb.out_img_width = W; + cb.out_img_height = H; Rect rect = {0, 0, W-1, H-1}; - printf("AE test patterns %dx%d\n", cb.rgb_width, cb.rgb_height); + printf("AE test patterns %dx%d\n", cb.out_img_width, cb.out_img_height); // mix of 5 tones uint8_t l[5] = {0, 24, 48, 96, 235}; // 235 is yuv max From 718835a825ec77d25d6d95dd58a719c16f14a3fb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 18 Sep 2024 21:10:45 -0700 Subject: [PATCH 083/214] camerad: prep part 2 (#33584) * no camerastate in sensors * bring this over * and encoder --- system/camerad/cameras/camera_qcom2.cc | 2 +- system/camerad/cameras/camera_util.h | 30 +++++++++++++------------- system/camerad/sensors/ar0231.cc | 13 ++++++----- system/camerad/sensors/sensor.h | 4 ++-- system/loggerd/encoder/encoder.h | 6 ++++-- 5 files changed, 28 insertions(+), 27 deletions(-) diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index aa787dea8f..6febbf36a9 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -953,7 +953,7 @@ void CameraState::run() { } // Process camera registers and set camera exposure - sensor->processRegisters(this, framed); + sensor->processRegisters((uint8_t *)buf.cur_camera_buf->addr, framed); set_camera_exposure(set_exposure_target(&buf, ae_xywh, 2, cc.stream_type != VISION_STREAM_DRIVER ? 2 : 4)); // Send the message diff --git a/system/camerad/cameras/camera_util.h b/system/camerad/cameras/camera_util.h index 891ce3e793..a2e7bfb434 100644 --- a/system/camerad/cameras/camera_util.h +++ b/system/camerad/cameras/camera_util.h @@ -18,22 +18,22 @@ void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, i void release(int video0_fd, uint32_t handle); class MemoryManager { - public: - void init(int _video0_fd) { video0_fd = _video0_fd; } - ~MemoryManager(); +public: + void init(int _video0_fd) { video0_fd = _video0_fd; } + ~MemoryManager(); - template - auto alloc(int len, uint32_t *handle) { - return std::unique_ptr>((T*)alloc_buf(len, handle), [this](void *ptr) { this->free(ptr); }); - } + template + auto alloc(int len, uint32_t *handle) { + return std::unique_ptr>((T*)alloc_buf(len, handle), [this](void *ptr) { this->free(ptr); }); + } - private: - void *alloc_buf(int len, uint32_t *handle); - void free(void *ptr); +private: + void *alloc_buf(int len, uint32_t *handle); + void free(void *ptr); - std::mutex lock; - std::map handle_lookup; - std::map size_lookup; - std::map > cached_allocations; - int video0_fd; + std::mutex lock; + std::map handle_lookup; + std::map size_lookup; + std::map > cached_allocations; + int video0_fd; }; diff --git a/system/camerad/sensors/ar0231.cc b/system/camerad/sensors/ar0231.cc index 143e04c0b3..74f09dfa61 100644 --- a/system/camerad/sensors/ar0231.cc +++ b/system/camerad/sensors/ar0231.cc @@ -2,7 +2,6 @@ #include "common/swaglog.h" #include "system/camerad/cameras/camera_common.h" -#include "system/camerad/cameras/camera_qcom2.h" #include "system/camerad/sensors/sensor.h" namespace { @@ -17,7 +16,7 @@ const float sensor_analog_gains_AR0231[] = { 5.0 / 4.0, 6.0 / 4.0, 6.0 / 3.0, 7.0 / 3.0, // 8, 9, 10, 11 7.0 / 2.0, 8.0 / 2.0, 8.0 / 1.0}; // 12, 13, 14, 15 = bypass -std::map> ar0231_build_register_lut(CameraState *c, uint8_t *data) { +std::map> ar0231_build_register_lut(const AR0231 *s, uint8_t *data) { // This function builds a lookup table from register address, to a pair of indices in the // buffer where to read this address. The buffer contains padding bytes, // as well as markers to indicate the type of the next byte. @@ -33,7 +32,7 @@ std::map> ar0231_build_register_lut(CameraState *c std::map> registers; for (int register_row = 0; register_row < 2; register_row++) { - uint8_t *registers_raw = data + c->sensor->frame_stride * register_row; + uint8_t *registers_raw = data + s->frame_stride * register_row; assert(registers_raw[0] == 0x0a); // Start of line int value_tag_count = 0; @@ -58,7 +57,7 @@ std::map> ar0231_build_register_lut(CameraState *c cur_addr += 2; first_val_idx = val_idx; } else { - registers[cur_addr] = std::make_pair(first_val_idx + c->sensor->frame_stride * register_row, val_idx + c->sensor->frame_stride * register_row); + registers[cur_addr] = std::make_pair(first_val_idx + s->frame_stride * register_row, val_idx + s->frame_stride * register_row); } value_tag_count++; @@ -119,9 +118,9 @@ AR0231::AR0231() { target_grey_factor = 1.0; } -void AR0231::processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const { +void AR0231::processRegisters(uint8_t *cur_buf, cereal::FrameData::Builder &framed) const { const uint8_t expected_preamble[] = {0x0a, 0xaa, 0x55, 0x20, 0xa5, 0x55}; - uint8_t *data = (uint8_t *)c->buf.cur_camera_buf->addr + c->sensor->registers_offset; + uint8_t *data = cur_buf + registers_offset; if (memcmp(data, expected_preamble, std::size(expected_preamble)) != 0) { LOGE("unexpected register data found"); @@ -129,7 +128,7 @@ void AR0231::processRegisters(CameraState *c, cereal::FrameData::Builder &framed } if (ar0231_register_lut.empty()) { - ar0231_register_lut = ar0231_build_register_lut(c, data); + ar0231_register_lut = ar0231_build_register_lut(this, data); } std::map registers; for (uint16_t addr : {0x2000, 0x2002, 0x20b0, 0x20b2, 0x30c6, 0x30c8, 0x30ca, 0x30cc}) { diff --git a/system/camerad/sensors/sensor.h b/system/camerad/sensors/sensor.h index add514b117..22083eb62b 100644 --- a/system/camerad/sensors/sensor.h +++ b/system/camerad/sensors/sensor.h @@ -19,7 +19,7 @@ public: virtual std::vector getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { return {}; } virtual float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const {return 0; } virtual int getSlaveAddress(int port) const { assert(0); } - virtual void processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const {} + virtual void processRegisters(uint8_t *cur_buf, cereal::FrameData::Builder &framed) const {} cereal::FrameData::ImageSensor image_sensor = cereal::FrameData::ImageSensor::UNKNOWN; float pixel_size_mm; @@ -68,7 +68,7 @@ public: std::vector getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const override; float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const override; int getSlaveAddress(int port) const override; - void processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const override; + void processRegisters(uint8_t *cur_buf, cereal::FrameData::Builder &framed) const override; private: mutable std::map> ar0231_register_lut; diff --git a/system/loggerd/encoder/encoder.h b/system/loggerd/encoder/encoder.h index 72848609ef..20352ac093 100644 --- a/system/loggerd/encoder/encoder.h +++ b/system/loggerd/encoder/encoder.h @@ -1,5 +1,9 @@ #pragma once +// has to be in this order +#include "third_party/linux/include/v4l2-controls.h" +#include + #include #include #include @@ -12,8 +16,6 @@ #include "system/camerad/cameras/camera_common.h" #include "system/loggerd/loggerd.h" -#define V4L2_BUF_FLAG_KEYFRAME 8 - class VideoEncoder { public: VideoEncoder(const EncoderInfo &encoder_info, int in_width, int in_height); From 102f1b0d85d5dae73882dd45e2659414c2849fd3 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 18 Sep 2024 22:16:25 -0700 Subject: [PATCH 084/214] loggerd: fix mac build --- system/loggerd/encoder/encoder.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/system/loggerd/encoder/encoder.h b/system/loggerd/encoder/encoder.h index 20352ac093..96ad4ffeb0 100644 --- a/system/loggerd/encoder/encoder.h +++ b/system/loggerd/encoder/encoder.h @@ -1,8 +1,12 @@ #pragma once // has to be in this order +#ifdef __linux__ #include "third_party/linux/include/v4l2-controls.h" #include +#else +#define V4L2_BUF_FLAG_KEYFRAME 8 +#endif #include #include From aca0ee3eea88b2493e62f9eb6c48776f76e54279 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 19 Sep 2024 13:19:57 +0800 Subject: [PATCH 085/214] locationd: replaced the loop and setattr with direct attribute assignment (#33466) replaced the loop and setattr with direct attribute assignment --- selfdrive/locationd/locationd.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 14a315da85..4cde1e5ad4 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -31,9 +31,8 @@ POSENET_STD_HIST_HALF = 20 def init_xyz_measurement(measurement: capnp._DynamicStructBuilder, values: np.ndarray, stds: np.ndarray, valid: bool): assert len(values) == len(stds) == 3 - for i, d in enumerate(("x", "y", "z")): - setattr(measurement, d, float(values[i])) - setattr(measurement, f"{d}Std", float(stds[i])) + measurement.x, measurement.y, measurement.z = map(float, values) + measurement.xStd, measurement.yStd, measurement.zStd = map(float, stds) measurement.valid = valid From 80013219fea02e2f5ced149d8304524aa4227901 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 18 Sep 2024 22:24:53 -0700 Subject: [PATCH 086/214] camerad: abstract out ISP handling (#33583) * spectra and tici * master * move the rest * rm stupid indirection * start move * multi cam state is dead * rest is moved * lil more * mv that * lil more * fix pc build * we haven't done rgb for a while * bring this stuff back * fix mac? * no camera in ui! * i remember why we always cut mac * fix mac build --------- Co-authored-by: Comma Device --- selfdrive/ui/qt/widgets/cameraview.h | 2 - system/camerad/SConscript | 2 +- system/camerad/cameras/camera_common.cc | 60 +- system/camerad/cameras/camera_common.h | 12 +- system/camerad/cameras/camera_qcom2.cc | 883 ++++-------------------- system/camerad/cameras/camera_qcom2.h | 156 ----- system/camerad/cameras/spectra.cc | 695 +++++++++++++++++++ system/camerad/cameras/spectra.h | 87 +++ system/camerad/cameras/tici.h | 49 ++ system/camerad/sensors/ar0231.cc | 1 - system/camerad/sensors/sensor.h | 3 +- 11 files changed, 971 insertions(+), 979 deletions(-) delete mode 100644 system/camerad/cameras/camera_qcom2.h create mode 100644 system/camerad/cameras/spectra.cc create mode 100644 system/camerad/cameras/spectra.h create mode 100644 system/camerad/cameras/tici.h diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 73f4858c4b..29aa8493c7 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -23,11 +23,9 @@ #endif #include "msgq/visionipc/visionipc_client.h" -#include "system/camerad/cameras/camera_common.h" #include "selfdrive/ui/ui.h" const int FRAME_BUFFER_SIZE = 5; -static_assert(FRAME_BUFFER_SIZE <= YUV_BUFFER_COUNT); class CameraWidget : public QOpenGLWidget, protected QOpenGLFunctions { Q_OBJECT diff --git a/system/camerad/SConscript b/system/camerad/SConscript index 511664c275..4e2eddeb42 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -3,7 +3,7 @@ Import('env', 'arch', 'messaging', 'common', 'gpucommon', 'visionipc') libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', messaging, visionipc, gpucommon, 'atomic'] camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc', - 'sensors/ar0231.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc']) + 'cameras/spectra.cc', 'sensors/ar0231.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc']) env.Program('camerad', ['main.cc', camera_obj], LIBS=libs) if GetOption("extras") and arch == "x86_64": diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index c89fc7f83a..a4ac385440 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -10,16 +10,13 @@ #include "common/swaglog.h" #include "third_party/linux/include/msm_media_info.h" -#include "system/camerad/cameras/camera_qcom2.h" -#ifdef QCOM2 -#include "CL/cl_ext_qcom.h" -#endif +#include "system/camerad/cameras/spectra.h" + class ImgProc { public: - ImgProc(cl_device_id device_id, cl_context context, const CameraBuf *b, const CameraState *s, int buf_width, int uv_offset) { + ImgProc(cl_device_id device_id, cl_context context, const CameraBuf *b, const SensorInfo *sensor, int camera_num, int buf_width, int uv_offset) { char args[4096]; - const SensorInfo *sensor = s->sensor.get(); snprintf(args, sizeof(args), "-cl-fast-relaxed-math -cl-denorms-are-zero -Isensors " "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d " @@ -27,7 +24,7 @@ public: "-DSENSOR_ID=%hu -DHDR_OFFSET=%d -DVIGNETTING=%d ", sensor->frame_width, sensor->frame_height, sensor->hdr_offset > 0 ? sensor->frame_stride * 2 : sensor->frame_stride, sensor->frame_offset, b->out_img_width, b->out_img_height, buf_width, uv_offset, - static_cast(sensor->image_sensor), sensor->hdr_offset, s->cc.camera_num == 1); + static_cast(sensor->image_sensor), sensor->hdr_offset, camera_num == 1); const char *cl_file = "cameras/process_raw.cl"; cl_program prg_imgproc = cl_program_from_file(context, device_id, cl_file, args); krnl_ = CL_CHECK_ERR(clCreateKernel(prg_imgproc, "process_raw", &err)); @@ -62,12 +59,13 @@ private: cl_command_queue queue; }; -void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType type) { +void CameraBuf::init(cl_device_id device_id, cl_context context, SpectraCamera *cam, VisionIpcServer * v, int frame_cnt, VisionStreamType type) { vipc_server = v; stream_type = type; frame_buf_count = frame_cnt; - const SensorInfo *sensor = s->sensor.get(); + const SensorInfo *sensor = cam->sensor.get(); + // RAW frame const int frame_size = (sensor->frame_height + sensor->extra_height) * sensor->frame_stride; camera_bufs = std::make_unique(frame_buf_count); @@ -95,7 +93,7 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, vipc_server->create_buffers_with_sizes(stream_type, YUV_BUFFER_COUNT, false, out_img_width, out_img_height, nv12_size, nv12_width, nv12_uv_offset); LOGD("created %d YUV vipc buffers with size %dx%d", YUV_BUFFER_COUNT, nv12_width, nv12_height); - imgproc = new ImgProc(device_id, context, this, s, nv12_width, nv12_uv_offset); + imgproc = new ImgProc(device_id, context, this, sensor, cam->cc.camera_num, nv12_width, nv12_uv_offset); } CameraBuf::~CameraBuf() { @@ -138,24 +136,6 @@ void CameraBuf::queue(size_t buf_idx) { // common functions -void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data, CameraState *c) { - framed.setFrameId(frame_data.frame_id); - framed.setRequestId(frame_data.request_id); - framed.setTimestampEof(frame_data.timestamp_eof); - framed.setTimestampSof(frame_data.timestamp_sof); - framed.setIntegLines(frame_data.integ_lines); - framed.setGain(frame_data.gain); - framed.setHighConversionGain(frame_data.high_conversion_gain); - framed.setMeasuredGreyFraction(frame_data.measured_grey_fraction); - framed.setTargetGreyFraction(frame_data.target_grey_fraction); - framed.setProcessingTime(frame_data.processing_time); - - const float ev = c->cur_ev[frame_data.frame_id % 3]; - const float perc = util::map_val(ev, c->sensor->min_ev, c->sensor->max_ev, 0.0f, 100.0f); - framed.setExposureValPercent(perc); - framed.setSensor(c->sensor->image_sensor); -} - kj::Array get_raw_frame_image(const CameraBuf *b) { const uint8_t *dat = (const uint8_t *)b->cur_camera_buf->addr; @@ -283,30 +263,6 @@ float set_exposure_target(const CameraBuf *b, Rect ae_xywh, int x_skip, int y_sk return lum_med / 256.0; } -void camerad_thread() { - cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); -#ifdef QCOM2 - const cl_context_properties props[] = {CL_CONTEXT_PRIORITY_HINT_QCOM, CL_PRIORITY_HINT_HIGH_QCOM, 0}; - cl_context context = CL_CHECK_ERR(clCreateContext(props, 1, &device_id, NULL, NULL, &err)); -#else - cl_context context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); -#endif - - { - MultiCameraState cameras; - cameras.pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); - VisionIpcServer vipc_server("camerad", device_id, context); - - cameras_init(&cameras, &vipc_server, device_id, context); - - vipc_server.start_listener(); - - cameras_run(&cameras); - } - - CL_CHECK(clReleaseContext(context)); -} - int open_v4l_by_name_and_index(const char name[], int index, int flags) { for (int v4l_index = 0; /**/; ++v4l_index) { std::string v4l_name = util::read_file(util::string_format("/sys/class/video4linux/v4l-subdev%d/name", v4l_index)); diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 567a03c193..d1f0b0d0e1 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -8,6 +8,7 @@ #include "common/queue.h" #include "common/util.h" + const int YUV_BUFFER_COUNT = 20; enum CameraType { @@ -39,7 +40,7 @@ typedef struct FrameMetadata { float processing_time; } FrameMetadata; -struct MultiCameraState; +class SpectraCamera; class CameraState; class ImgProc; @@ -62,18 +63,13 @@ public: CameraBuf() = default; ~CameraBuf(); - void init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType type); + void init(cl_device_id device_id, cl_context context, SpectraCamera *cam, VisionIpcServer * v, int frame_cnt, VisionStreamType type); bool acquire(); void queue(size_t buf_idx); }; -void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data, CameraState *c); +void camerad_thread(); kj::Array get_raw_frame_image(const CameraBuf *b); float set_exposure_target(const CameraBuf *b, Rect ae_xywh, int x_skip, int y_skip); void publish_thumbnail(PubMaster *pm, const CameraBuf *b); -void cameras_init(MultiCameraState *s, VisionIpcServer *v, cl_device_id device_id, cl_context ctx); -void cameras_run(MultiCameraState *s); -void cameras_close(MultiCameraState *s); -void camerad_thread(); - int open_v4l_by_name_and_index(const char name[], int index = 0, int flags = O_RDWR | O_NONBLOCK); diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 6febbf36a9..3b2b9db330 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -1,4 +1,5 @@ -#include "system/camerad/cameras/camera_qcom2.h" +#include "system/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/spectra.h" #include #include @@ -11,759 +12,62 @@ #include #include +#include "CL/cl_ext_qcom.h" + #include "media/cam_defs.h" -#include "media/cam_isp.h" -#include "media/cam_isp_ife.h" -#include "media/cam_req_mgr.h" #include "media/cam_sensor_cmn_header.h" #include "media/cam_sync.h" +#include "common/clutil.h" #include "common/params.h" #include "common/swaglog.h" -const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py ExitHandler do_exit; -CameraState::CameraState(MultiCameraState *multi_camera_state, const CameraConfig &config) - : multi_cam_state(multi_camera_state), - enabled(config.enabled) , - cc(config) { -} - -CameraState::~CameraState() { - if (open) { - camera_close(); - } -} - - -int CameraState::clear_req_queue() { - struct cam_req_mgr_flush_info req_mgr_flush_request = {0}; - req_mgr_flush_request.session_hdl = session_handle; - req_mgr_flush_request.link_hdl = link_handle; - req_mgr_flush_request.flush_type = CAM_REQ_MGR_FLUSH_TYPE_ALL; - int ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_FLUSH_REQ, &req_mgr_flush_request, sizeof(req_mgr_flush_request)); - // LOGD("flushed all req: %d", ret); - return ret; -} - -// ************** high level camera helpers **************** - -void CameraState::sensors_start() { - if (!enabled) return; - LOGD("starting sensor %d", cc.camera_num); - sensors_i2c(sensor->start_reg_array.data(), sensor->start_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, sensor->data_word); -} - -void CameraState::sensors_poke(int request_id) { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet); - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 0; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - pkt->header.op_code = CAM_SENSOR_PACKET_OPCODE_SENSOR_NOP; - pkt->header.request_id = request_id; - - int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); - if (ret != 0) { - LOGE("** sensor %d FAILED poke, disabling", cc.camera_num); - enabled = false; - return; - } -} - -void CameraState::sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word) { - // LOGD("sensors_i2c: %d", len); - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 1; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - pkt->header.op_code = op_code; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct i2c_rdwr_header) + len*sizeof(struct i2c_random_wr_payload); - buf_desc[0].type = CAM_CMD_BUF_I2C; - - auto i2c_random_wr = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - i2c_random_wr->header.count = len; - i2c_random_wr->header.op_code = 1; - i2c_random_wr->header.cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR; - i2c_random_wr->header.data_type = data_word ? CAMERA_SENSOR_I2C_TYPE_WORD : CAMERA_SENSOR_I2C_TYPE_BYTE; - i2c_random_wr->header.addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; - memcpy(i2c_random_wr->random_wr_payload, dat, len*sizeof(struct i2c_random_wr_payload)); - - int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); - if (ret != 0) { - LOGE("** sensor %d FAILED i2c, disabling", cc.camera_num); - enabled = false; - return; - } -} - -static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) { - cam_cmd_unconditional_wait *unconditional_wait = (cam_cmd_unconditional_wait *)((char *)power + (sizeof(struct cam_cmd_power) + (power->count - 1) * sizeof(struct cam_power_settings))); - unconditional_wait->cmd_type = CAMERA_SENSOR_CMD_TYPE_WAIT; - unconditional_wait->delay = delay_ms; - unconditional_wait->op_code = CAMERA_SENSOR_WAIT_OP_SW_UCND; - return (struct cam_cmd_power *)(unconditional_wait + 1); -} - -int CameraState::sensors_init() { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 2; - pkt->kmd_cmd_buf_index = -1; - pkt->header.op_code = 0x1000000 | CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE; - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_info) + sizeof(struct cam_cmd_probe); - buf_desc[0].type = CAM_CMD_BUF_LEGACY; - auto i2c_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - auto probe = (struct cam_cmd_probe *)(i2c_info.get() + 1); - - probe->camera_id = cc.camera_num; - i2c_info->slave_addr = sensor->getSlaveAddress(cc.camera_num); - // 0(I2C_STANDARD_MODE) = 100khz, 1(I2C_FAST_MODE) = 400khz - //i2c_info->i2c_freq_mode = I2C_STANDARD_MODE; - i2c_info->i2c_freq_mode = I2C_FAST_MODE; - i2c_info->cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_INFO; - - probe->data_type = CAMERA_SENSOR_I2C_TYPE_WORD; - probe->addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; - probe->op_code = 3; // don't care? - probe->cmd_type = CAMERA_SENSOR_CMD_TYPE_PROBE; - probe->reg_addr = sensor->probe_reg_addr; - probe->expected_data = sensor->probe_expected_data; - probe->data_mask = 0; - - //buf_desc[1].size = buf_desc[1].length = 148; - buf_desc[1].size = buf_desc[1].length = 196; - buf_desc[1].type = CAM_CMD_BUF_I2C; - auto power_settings = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); - - // power on - struct cam_cmd_power *power = power_settings.get(); - power->count = 4; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 3; // clock?? - power->power_settings[1].power_seq_type = 1; // analog - power->power_settings[2].power_seq_type = 2; // digital - power->power_settings[3].power_seq_type = 8; // reset low - power = power_set_wait(power, 1); - - // set clock - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 0; - power->power_settings[0].config_val_low = sensor->mclk_frequency; - power = power_set_wait(power, 1); - - // reset high - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 1; - // wait 650000 cycles @ 19.2 mhz = 33.8 ms - power = power_set_wait(power, 34); - - // probe happens here - - // disable clock - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 0; - power->power_settings[0].config_val_low = 0; - power = power_set_wait(power, 1); - - // reset high - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 1; - power = power_set_wait(power, 1); - - // reset low - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 0; - power = power_set_wait(power, 1); - - // power off - power->count = 3; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 2; - power->power_settings[1].power_seq_type = 1; - power->power_settings[2].power_seq_type = 3; - - int ret = do_cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)(uintptr_t)cam_packet_handle, 0); - LOGD("probing the sensor: %d", ret); - return ret; -} - -void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset) { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; - if (io_mem_handle != 0) { - size += sizeof(struct cam_buf_io_cfg); - } - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 2; - pkt->kmd_cmd_buf_index = 0; - // YUV has kmd_cmd_buf_offset = 1780 - // I guess this is the ISP command - // YUV also has patch_offset = 0x1030 and num_patches = 10 - - if (io_mem_handle != 0) { - pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf; - pkt->num_io_configs = 1; - } - - if (io_mem_handle != 0) { - pkt->header.op_code = 0xf000001; - pkt->header.request_id = request_id; - } else { - pkt->header.op_code = 0xf000000; - } - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - struct cam_buf_io_cfg *io_cfg = (struct cam_buf_io_cfg *)((char*)&pkt->payload + pkt->io_configs_offset); - - // TODO: support MMU - buf_desc[0].size = 65624; - buf_desc[0].length = 0; - buf_desc[0].type = CAM_CMD_BUF_DIRECT; - buf_desc[0].meta_data = 3; - buf_desc[0].mem_handle = buf0_mem_handle; - buf_desc[0].offset = buf0_offset; - - // parsed by cam_isp_packet_generic_blob_handler - struct isp_packet { - uint32_t type_0; - cam_isp_resource_hfr_config resource_hfr; - - uint32_t type_1; - cam_isp_clock_config clock; - uint64_t extra_rdi_hz[3]; - - uint32_t type_2; - cam_isp_bw_config bw; - struct cam_isp_bw_vote extra_rdi_vote[6]; - } __attribute__((packed)) tmp; - memset(&tmp, 0, sizeof(tmp)); - - tmp.type_0 = CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG; - tmp.type_0 |= sizeof(cam_isp_resource_hfr_config) << 8; - static_assert(sizeof(cam_isp_resource_hfr_config) == 0x20); - tmp.resource_hfr = { - .num_ports = 1, // 10 for YUV (but I don't think we need them) - .port_hfr_config[0] = { - .resource_type = CAM_ISP_IFE_OUT_RES_RDI_0, // CAM_ISP_IFE_OUT_RES_FULL for YUV - .subsample_pattern = 1, - .subsample_period = 0, - .framedrop_pattern = 1, - .framedrop_period = 0, - }}; - - tmp.type_1 = CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG; - tmp.type_1 |= (sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) << 8; - static_assert((sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) == 0x38); - tmp.clock = { - .usage_type = 1, // dual mode - .num_rdi = 4, - .left_pix_hz = 404000000, - .right_pix_hz = 404000000, - .rdi_hz[0] = 404000000, - }; - - - tmp.type_2 = CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG; - tmp.type_2 |= (sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) << 8; - static_assert((sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) == 0xe0); - tmp.bw = { - .usage_type = 1, // dual mode - .num_rdi = 4, - .left_pix_vote = { - .resource_id = 0, - .cam_bw_bps = 450000000, - .ext_bw_bps = 450000000, - }, - .rdi_vote[0] = { - .resource_id = 0, - .cam_bw_bps = 8706200000, - .ext_bw_bps = 8706200000, - }, - }; - - static_assert(offsetof(struct isp_packet, type_2) == 0x60); - - buf_desc[1].size = sizeof(tmp); - buf_desc[1].offset = io_mem_handle != 0 ? 0x60 : 0; - buf_desc[1].length = buf_desc[1].size - buf_desc[1].offset; - buf_desc[1].type = CAM_CMD_BUF_GENERIC; - buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; - auto buf2 = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); - memcpy(buf2.get(), &tmp, sizeof(tmp)); - - if (io_mem_handle != 0) { - io_cfg[0].mem_handle[0] = io_mem_handle; - io_cfg[0].planes[0] = (struct cam_plane_cfg){ - .width = sensor->frame_width, - .height = sensor->frame_height + sensor->extra_height, - .plane_stride = sensor->frame_stride, - .slice_height = sensor->frame_height + sensor->extra_height, - .meta_stride = 0x0, // YUV has meta(stride=0x400, size=0x5000) - .meta_size = 0x0, - .meta_offset = 0x0, - .packer_config = 0x0, // 0xb for YUV - .mode_config = 0x0, // 0x9ef for YUV - .tile_config = 0x0, - .h_init = 0x0, - .v_init = 0x0, - }; - io_cfg[0].format = sensor->mipi_format; // CAM_FORMAT_UBWC_TP10 for YUV - io_cfg[0].color_space = CAM_COLOR_SPACE_BASE; // CAM_COLOR_SPACE_BT601_FULL for YUV - io_cfg[0].color_pattern = 0x5; // 0x0 for YUV - io_cfg[0].bpp = (sensor->mipi_format == CAM_FORMAT_MIPI_RAW_10 ? 0xa : 0xc); // bits per pixel - io_cfg[0].resource_type = CAM_ISP_IFE_OUT_RES_RDI_0; // CAM_ISP_IFE_OUT_RES_FULL for YUV - io_cfg[0].fence = fence; - io_cfg[0].direction = CAM_BUF_OUTPUT; - io_cfg[0].subsample_pattern = 0x1; - io_cfg[0].framedrop_pattern = 0x1; - } - - int ret = device_config(multi_cam_state->isp_fd, session_handle, isp_dev_handle, cam_packet_handle); - assert(ret == 0); - if (ret != 0) { - LOGE("isp config failed"); - } -} - -void CameraState::enqueue_buffer(int i, bool dp) { - int ret; - uint64_t request_id = request_ids[i]; - - if (buf_handle[i] && sync_objs[i]) { - // wait - struct cam_sync_wait sync_wait = {0}; - sync_wait.sync_obj = sync_objs[i]; - sync_wait.timeout_ms = 50; // max dt tolerance, typical should be 23 - ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_WAIT, &sync_wait, sizeof(sync_wait)); - if (ret != 0) { - LOGE("failed to wait for sync: %d %d", ret, sync_wait.sync_obj); - // TODO: handle frame drop cleanly - } - - buf.camera_bufs_metadata[i].timestamp_eof = (uint64_t)nanos_since_boot(); // set true eof - if (dp) buf.queue(i); - - // destroy old output fence - struct cam_sync_info sync_destroy = {0}; - sync_destroy.sync_obj = sync_objs[i]; - ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_DESTROY, &sync_destroy, sizeof(sync_destroy)); - if (ret != 0) { - LOGE("failed to destroy sync object: %d %d", ret, sync_destroy.sync_obj); - } - } - - // create output fence - struct cam_sync_info sync_create = {0}; - strcpy(sync_create.name, "NodeOutputPortFence"); - ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create)); - if (ret != 0) { - LOGE("failed to create fence: %d %d", ret, sync_create.sync_obj); - } - sync_objs[i] = sync_create.sync_obj; - - // schedule request with camera request manager - struct cam_req_mgr_sched_request req_mgr_sched_request = {0}; - req_mgr_sched_request.session_hdl = session_handle; - req_mgr_sched_request.link_hdl = link_handle; - req_mgr_sched_request.req_id = request_id; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_SCHED_REQ, &req_mgr_sched_request, sizeof(req_mgr_sched_request)); - if (ret != 0) { - LOGE("failed to schedule cam mgr request: %d %lu", ret, request_id); - } - - // poke sensor, must happen after schedule - sensors_poke(request_id); - - // submit request to the ife - config_isp(buf_handle[i], sync_objs[i], request_id, buf0_handle, 65632*(i+1)); -} - -void CameraState::enqueue_req_multi(uint64_t start, int n, bool dp) { - for (uint64_t i = start; i < start + n; ++i) { - request_ids[(i - 1) % FRAME_BUF_COUNT] = i; - enqueue_buffer((i - 1) % FRAME_BUF_COUNT, dp); - } -} - -// ******************* camera ******************* - -void CameraState::set_exposure_rect() { - // set areas for each camera, shouldn't be changed - std::vector> ae_targets = { - // (Rect, F) - std::make_pair((Rect){96, 250, 1734, 524}, 567.0), // wide - std::make_pair((Rect){96, 160, 1734, 986}, 2648.0), // road - std::make_pair((Rect){96, 242, 1736, 906}, 567.0) // driver - }; - int h_ref = 1208; - /* - exposure target intrinics is - [ - [F, 0, 0.5*ae_xywh[2]] - [0, F, 0.5*H-ae_xywh[1]] - [0, 0, 1] - ] - */ - auto ae_target = ae_targets[cc.camera_num]; - Rect xywh_ref = ae_target.first; - float fl_ref = ae_target.second; - - ae_xywh = (Rect){ - std::max(0, buf.out_img_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), - std::max(0, buf.out_img_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), - std::min((int)(fl_pix / fl_ref * xywh_ref.w), buf.out_img_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), - std::min((int)(fl_pix / fl_ref * xywh_ref.h), buf.out_img_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) - }; -} - -void CameraState::sensor_set_parameters() { - dc_gain_weight = sensor->dc_gain_min_weight; - gain_idx = sensor->analog_gain_rec_idx; - cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight) * sensor->sensor_analog_gains[gain_idx] * exposure_time; -} - -void CameraState::camera_map_bufs() { - for (int i = 0; i < FRAME_BUF_COUNT; i++) { - // configure ISP to put the image in place - struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0}; - mem_mgr_map_cmd.mmu_hdls[0] = multi_cam_state->device_iommu; - mem_mgr_map_cmd.num_hdl = 1; - mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE; - mem_mgr_map_cmd.fd = buf.camera_bufs[i].fd; - int ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd)); - LOGD("map buf req: (fd: %d) 0x%x %d", buf.camera_bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret); - buf_handle[i] = mem_mgr_map_cmd.out.buf_handle; - } - enqueue_req_multi(1, FRAME_BUF_COUNT, 0); -} - -void CameraState::camera_init(VisionIpcServer * v, cl_device_id device_id, cl_context ctx) { - if (!enabled) return; - - LOGD("camera init %d", cc.camera_num); - buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, cc.stream_type); - camera_map_bufs(); - - fl_pix = cc.focal_len / sensor->pixel_size_mm; - set_exposure_rect(); -} - -void CameraState::camera_open() { - if (!enabled) return; - if (!openSensor()) { - return; - } +// high level camera state +class CameraState : public SpectraCamera { +public: + std::mutex exp_lock; - open = true; - configISP(); - configCSIPHY(); - linkDevices(); -} + int exposure_time = 5; + bool dc_gain_enabled = false; + int dc_gain_weight = 0; + int gain_idx = 0; + float analog_gain_frac = 0; -bool CameraState::openSensor() { - sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", cc.camera_num); - assert(sensor_fd >= 0); - LOGD("opened sensor for %d", cc.camera_num); + float cur_ev[3] = {}; + float best_ev_score = 0; + int new_exp_g = 0; + int new_exp_t = 0; - // init memorymanager for this camera - mm.init(multi_cam_state->video0_fd); + Rect ae_xywh = {}; + float measured_grey_fraction = 0; + float target_grey_fraction = 0.3; - LOGD("-- Probing sensor %d", cc.camera_num); + float fl_pix = 0; - auto init_sensor_lambda = [this](SensorInfo *s) { - sensor.reset(s); - int ret = sensors_init(); - if (ret == 0) { - sensor_set_parameters(); - } - return ret == 0; - }; + CameraState(SpectraMaster *master, const CameraConfig &config) : SpectraCamera(master, config) {}; + void update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain); + void set_camera_exposure(float grey_frac); - // Try different sensors one by one until it success. - if (!init_sensor_lambda(new AR0231) && - !init_sensor_lambda(new OX03C10) && - !init_sensor_lambda(new OS04C10)) { - LOGE("** sensor %d FAILED bringup, disabling", cc.camera_num); - enabled = false; - return false; - } - LOGD("-- Probing sensor %d success", cc.camera_num); - - // create session - struct cam_req_mgr_session_info session_info = {}; - int ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_CREATE_SESSION, &session_info, sizeof(session_info)); - LOGD("get session: %d 0x%X", ret, session_info.session_hdl); - session_handle = session_info.session_hdl; - - // access the sensor - LOGD("-- Accessing sensor"); - auto sensor_dev_handle_ = device_acquire(sensor_fd, session_handle, nullptr); - assert(sensor_dev_handle_); - sensor_dev_handle = *sensor_dev_handle_; - LOGD("acquire sensor dev"); - - LOG("-- Configuring sensor"); - sensors_i2c(sensor->init_reg_array.data(), sensor->init_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, sensor->data_word); - return true; -} + void set_exposure_rect(); + void run(); -void CameraState::configISP() { - // NOTE: to be able to disable road and wide road, we still have to configure the sensor over i2c - // If you don't do this, the strobe GPIO is an output (even in reset it seems!) - if (!enabled) return; + void init() { + fl_pix = cc.focal_len / sensor->pixel_size_mm; + set_exposure_rect(); - struct cam_isp_in_port_info in_port_info = { - .res_type = cc.phy, - .lane_type = CAM_ISP_LANE_TYPE_DPHY, - .lane_num = 4, - .lane_cfg = 0x3210, - - .vc = 0x0, - .dt = sensor->frame_data_type, - .format = sensor->mipi_format, - - .test_pattern = 0x2, // 0x3? - .usage_type = 0x0, - - .left_start = 0, - .left_stop = sensor->frame_width - 1, - .left_width = sensor->frame_width, - - .right_start = 0, - .right_stop = sensor->frame_width - 1, - .right_width = sensor->frame_width, - - .line_start = 0, - .line_stop = sensor->frame_height + sensor->extra_height - 1, - .height = sensor->frame_height + sensor->extra_height, - - .pixel_clk = 0x0, - .batch_size = 0x0, - .dsp_mode = CAM_ISP_DSP_MODE_NONE, - .hbi_cnt = 0x0, - .custom_csid = 0x0, - - .num_out_res = 0x1, - .data[0] = (struct cam_isp_out_port_info){ - .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, - .format = sensor->mipi_format, - .width = sensor->frame_width, - .height = sensor->frame_height + sensor->extra_height, - .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, - }, - }; - struct cam_isp_resource isp_resource = { - .resource_id = CAM_ISP_RES_ID_PORT, - .handle_type = CAM_HANDLE_USER_POINTER, - .res_hdl = (uint64_t)&in_port_info, - .length = sizeof(in_port_info), + dc_gain_weight = sensor->dc_gain_min_weight; + gain_idx = sensor->analog_gain_rec_idx; + cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight) * sensor->sensor_analog_gains[gain_idx] * exposure_time; }; - auto isp_dev_handle_ = device_acquire(multi_cam_state->isp_fd, session_handle, &isp_resource); - assert(isp_dev_handle_); - isp_dev_handle = *isp_dev_handle_; - LOGD("acquire isp dev"); - - // config ISP - alloc_w_mmu_hdl(multi_cam_state->video0_fd, 984480, (uint32_t*)&buf0_handle, 0x20, CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | - CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, multi_cam_state->device_iommu, multi_cam_state->cdm_iommu); - config_isp(0, 0, 1, buf0_handle, 0); -} - -void CameraState::configCSIPHY() { - csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", cc.camera_num); - assert(csiphy_fd >= 0); - LOGD("opened csiphy for %d", cc.camera_num); - - struct cam_csiphy_acquire_dev_info csiphy_acquire_dev_info = {.combo_mode = 0}; - auto csiphy_dev_handle_ = device_acquire(csiphy_fd, session_handle, &csiphy_acquire_dev_info); - assert(csiphy_dev_handle_); - csiphy_dev_handle = *csiphy_dev_handle_; - LOGD("acquire csiphy dev"); - - // config csiphy - LOG("-- Config CSI PHY"); - { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 1; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_csiphy_info); - buf_desc[0].type = CAM_CMD_BUF_GENERIC; - - auto csiphy_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - csiphy_info->lane_mask = 0x1f; - csiphy_info->lane_assign = 0x3210;// skip clk. How is this 16 bit for 5 channels?? - csiphy_info->csiphy_3phase = 0x0; // no 3 phase, only 2 conductors per lane - csiphy_info->combo_mode = 0x0; - csiphy_info->lane_cnt = 0x4; - csiphy_info->secure_mode = 0x0; - csiphy_info->settle_time = MIPI_SETTLE_CNT * 200000000ULL; - csiphy_info->data_rate = 48000000; // Calculated by camera_freqs.py - - int ret_ = device_config(csiphy_fd, session_handle, csiphy_dev_handle, cam_packet_handle); - assert(ret_ == 0); - } -} - -void CameraState::linkDevices() { - LOG("-- Link devices"); - struct cam_req_mgr_link_info req_mgr_link_info = {0}; - req_mgr_link_info.session_hdl = session_handle; - req_mgr_link_info.num_devices = 2; - req_mgr_link_info.dev_hdls[0] = isp_dev_handle; - req_mgr_link_info.dev_hdls[1] = sensor_dev_handle; - int ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_LINK, &req_mgr_link_info, sizeof(req_mgr_link_info)); - link_handle = req_mgr_link_info.link_hdl; - LOGD("link: %d session: 0x%X isp: 0x%X sensors: 0x%X link: 0x%X", ret, session_handle, isp_dev_handle, sensor_dev_handle, link_handle); - - struct cam_req_mgr_link_control req_mgr_link_control = {0}; - req_mgr_link_control.ops = CAM_REQ_MGR_LINK_ACTIVATE; - req_mgr_link_control.session_hdl = session_handle; - req_mgr_link_control.num_links = 1; - req_mgr_link_control.link_hdls[0] = link_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); - LOGD("link control: %d", ret); - - ret = device_control(csiphy_fd, CAM_START_DEV, session_handle, csiphy_dev_handle); - LOGD("start csiphy: %d", ret); - ret = device_control(multi_cam_state->isp_fd, CAM_START_DEV, session_handle, isp_dev_handle); - LOGD("start isp: %d", ret); - assert(ret == 0); - - // TODO: this is unneeded, should we be doing the start i2c in a different way? - //ret = device_control(sensor_fd, CAM_START_DEV, session_handle, sensor_dev_handle); - //LOGD("start sensor: %d", ret); -} - -void cameras_init(MultiCameraState *s, VisionIpcServer *v, cl_device_id device_id, cl_context ctx) { - LOG("-- Opening devices"); - // video0 is req_mgr, the target of many ioctls - s->video0_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-soc:qcom_cam-req-mgr-video-index0", O_RDWR | O_NONBLOCK)); - assert(s->video0_fd >= 0); - LOGD("opened video0"); - - // video1 is cam_sync, the target of some ioctls - s->cam_sync_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-cam_sync-video-index0", O_RDWR | O_NONBLOCK)); - assert(s->cam_sync_fd >= 0); - LOGD("opened video1 (cam_sync)"); - - // looks like there's only one of these - s->isp_fd = open_v4l_by_name_and_index("cam-isp"); - assert(s->isp_fd >= 0); - LOGD("opened isp"); - - // query icp for MMU handles - LOG("-- Query ICP for MMU handles"); - struct cam_isp_query_cap_cmd isp_query_cap_cmd = {0}; - struct cam_query_cap_cmd query_cap_cmd = {0}; - query_cap_cmd.handle_type = 1; - query_cap_cmd.caps_handle = (uint64_t)&isp_query_cap_cmd; - query_cap_cmd.size = sizeof(isp_query_cap_cmd); - int ret = do_cam_control(s->isp_fd, CAM_QUERY_CAP, &query_cap_cmd, sizeof(query_cap_cmd)); - assert(ret == 0); - LOGD("using MMU handle: %x", isp_query_cap_cmd.device_iommu.non_secure); - LOGD("using MMU handle: %x", isp_query_cap_cmd.cdm_iommu.non_secure); - s->device_iommu = isp_query_cap_cmd.device_iommu.non_secure; - s->cdm_iommu = isp_query_cap_cmd.cdm_iommu.non_secure; - - // subscribe - LOG("-- Subscribing"); - struct v4l2_event_subscription sub = {0}; - sub.type = V4L_EVENT_CAM_REQ_MGR_EVENT; - sub.id = V4L_EVENT_CAM_REQ_MGR_SOF_BOOT_TS; - ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); - LOGD("req mgr subscribe: %d", ret); - - // open - s->driver_cam.camera_open(); - LOGD("driver camera opened"); - s->road_cam.camera_open(); - LOGD("road camera opened"); - s->wide_road_cam.camera_open(); - LOGD("wide road camera opened"); - - // init - s->driver_cam.camera_init(v, device_id, ctx); - s->road_cam.camera_init(v, device_id, ctx); - s->wide_road_cam.camera_init(v, device_id, ctx); -} - -void CameraState::camera_close() { - // stop devices - LOG("-- Stop devices %d", cc.camera_num); - - if (enabled) { - // ret = device_control(sensor_fd, CAM_STOP_DEV, session_handle, sensor_dev_handle); - // LOGD("stop sensor: %d", ret); - int ret = device_control(multi_cam_state->isp_fd, CAM_STOP_DEV, session_handle, isp_dev_handle); - LOGD("stop isp: %d", ret); - ret = device_control(csiphy_fd, CAM_STOP_DEV, session_handle, csiphy_dev_handle); - LOGD("stop csiphy: %d", ret); - // link control stop - LOG("-- Stop link control"); - struct cam_req_mgr_link_control req_mgr_link_control = {0}; - req_mgr_link_control.ops = CAM_REQ_MGR_LINK_DEACTIVATE; - req_mgr_link_control.session_hdl = session_handle; - req_mgr_link_control.num_links = 1; - req_mgr_link_control.link_hdls[0] = link_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); - LOGD("link control stop: %d", ret); - - // unlink - LOG("-- Unlink"); - struct cam_req_mgr_unlink_info req_mgr_unlink_info = {0}; - req_mgr_unlink_info.session_hdl = session_handle; - req_mgr_unlink_info.link_hdl = link_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_UNLINK, &req_mgr_unlink_info, sizeof(req_mgr_unlink_info)); - LOGD("unlink: %d", ret); - - // release devices - LOGD("-- Release devices"); - ret = device_control(multi_cam_state->isp_fd, CAM_RELEASE_DEV, session_handle, isp_dev_handle); - LOGD("release isp: %d", ret); - ret = device_control(csiphy_fd, CAM_RELEASE_DEV, session_handle, csiphy_dev_handle); - LOGD("release csiphy: %d", ret); - - for (int i = 0; i < FRAME_BUF_COUNT; i++) { - release(multi_cam_state->video0_fd, buf_handle[i]); - } - LOGD("released buffers"); - } + // TODO: this should move to SpectraCamera + void handle_camera_event(void *evdat); +}; - int ret = device_control(sensor_fd, CAM_RELEASE_DEV, session_handle, sensor_dev_handle); - LOGD("release sensor: %d", ret); - - // destroyed session - struct cam_req_mgr_session_info session_info = {.session_hdl = session_handle}; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_DESTROY_SESSION, &session_info, sizeof(session_info)); - LOGD("destroyed session %d: %d", cc.camera_num, ret); -} void CameraState::handle_camera_event(void *evdat) { if (!enabled) return; @@ -824,6 +128,35 @@ void CameraState::handle_camera_event(void *evdat) { } } +void CameraState::set_exposure_rect() { + // set areas for each camera, shouldn't be changed + std::vector> ae_targets = { + // (Rect, F) + std::make_pair((Rect){96, 250, 1734, 524}, 567.0), // wide + std::make_pair((Rect){96, 160, 1734, 986}, 2648.0), // road + std::make_pair((Rect){96, 242, 1736, 906}, 567.0) // driver + }; + int h_ref = 1208; + /* + exposure target intrinics is + [ + [F, 0, 0.5*ae_xywh[2]] + [0, F, 0.5*H-ae_xywh[1]] + [0, 0, 1] + ] + */ + auto ae_target = ae_targets[cc.camera_num]; + Rect xywh_ref = ae_target.first; + float fl_ref = ae_target.second; + + ae_xywh = (Rect){ + std::max(0, buf.out_img_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), + std::max(0, buf.out_img_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), + std::min((int)(fl_pix / fl_ref * xywh_ref.w), buf.out_img_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), + std::min((int)(fl_pix / fl_ref * xywh_ref.h), buf.out_img_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) + }; +} + void CameraState::update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain) { float score = sensor->getExposureScore(desired_ev, exp_t, exp_g_idx, exp_gain, gain_idx); if (score < best_ev_score) { @@ -939,13 +272,31 @@ void CameraState::set_camera_exposure(float grey_frac) { void CameraState::run() { util::set_thread_name(cc.publish_name); + std::vector pubs = {cc.publish_name}; + if (cc.stream_type == VISION_STREAM_ROAD) pubs.push_back("thumbnail"); + PubMaster pm(pubs); + for (uint32_t cnt = 0; !do_exit; ++cnt) { // Acquire the buffer; continue if acquisition fails if (!buf.acquire()) continue; MessageBuilder msg; auto framed = (msg.initEvent().*cc.init_camera_state)(); - fill_frame_data(framed, buf.cur_frame_data, this); + framed.setFrameId(buf.cur_frame_data.frame_id); + framed.setRequestId(buf.cur_frame_data.request_id); + framed.setTimestampEof(buf.cur_frame_data.timestamp_eof); + framed.setTimestampSof(buf.cur_frame_data.timestamp_sof); + framed.setIntegLines(buf.cur_frame_data.integ_lines); + framed.setGain(buf.cur_frame_data.gain); + framed.setHighConversionGain(buf.cur_frame_data.high_conversion_gain); + framed.setMeasuredGreyFraction(buf.cur_frame_data.measured_grey_fraction); + framed.setTargetGreyFraction(buf.cur_frame_data.target_grey_fraction); + framed.setProcessingTime(buf.cur_frame_data.processing_time); + + const float ev = cur_ev[buf.cur_frame_data.frame_id % 3]; + const float perc = util::map_val(ev, sensor->min_ev, sensor->max_ev, 0.0f, 100.0f); + framed.setExposureValPercent(perc); + framed.setSensor(sensor->image_sensor); // Log raw frames for road camera if (env_log_raw_frames && cc.stream_type == VISION_STREAM_ROAD && cnt % 100 == 5) { // no overlap with qlog decimation @@ -957,38 +308,58 @@ void CameraState::run() { set_camera_exposure(set_exposure_target(&buf, ae_xywh, 2, cc.stream_type != VISION_STREAM_DRIVER ? 2 : 4)); // Send the message - multi_cam_state->pm->send(cc.publish_name, msg); + pm.send(cc.publish_name, msg); if (cc.stream_type == VISION_STREAM_ROAD && cnt % 100 == 3) { - publish_thumbnail(multi_cam_state->pm, &buf); // this takes 10ms??? + publish_thumbnail(&pm, &buf); // this takes 10ms??? } } } -MultiCameraState::MultiCameraState() - : driver_cam(this, DRIVER_CAMERA_CONFIG), - road_cam(this, ROAD_CAMERA_CONFIG), - wide_road_cam(this, WIDE_ROAD_CAMERA_CONFIG) { -} +void camerad_thread() { + /* + TODO: future cleanups + - centralize enabled handling + - open/init/etc mess + - no ISP stuff in this file + */ + + cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); + const cl_context_properties props[] = {CL_CONTEXT_PRIORITY_HINT_QCOM, CL_PRIORITY_HINT_HIGH_QCOM, 0}; + cl_context ctx = CL_CHECK_ERR(clCreateContext(props, 1, &device_id, NULL, NULL, &err)); + + VisionIpcServer v("camerad", device_id, ctx); + + // *** initial ISP init *** + SpectraMaster m; + m.init(); + + // *** per-cam init *** + std::vector cams = { + new CameraState(&m, ROAD_CAMERA_CONFIG), + new CameraState(&m, WIDE_ROAD_CAMERA_CONFIG), + new CameraState(&m, DRIVER_CAMERA_CONFIG), + }; + for (auto cam : cams) cam->camera_open(); + for (auto cam : cams) cam->camera_init(&v, device_id, ctx); + for (auto cam : cams) cam->init(); + v.start_listener(); -void cameras_run(MultiCameraState *s) { LOG("-- Starting threads"); std::vector threads; - if (s->driver_cam.enabled) threads.emplace_back(&CameraState::run, &s->driver_cam); - if (s->road_cam.enabled) threads.emplace_back(&CameraState::run, &s->road_cam); - if (s->wide_road_cam.enabled) threads.emplace_back(&CameraState::run, &s->wide_road_cam); + for (auto cam : cams) { + if (cam->enabled) threads.emplace_back(&CameraState::run, cam); + } // start devices LOG("-- Starting devices"); - s->driver_cam.sensors_start(); - s->road_cam.sensors_start(); - s->wide_road_cam.sensors_start(); + for (auto cam : cams) cam->sensors_start(); // poll events LOG("-- Dequeueing Video events"); while (!do_exit) { struct pollfd fds[1] = {{0}}; - fds[0].fd = s->video0_fd; + fds[0].fd = m.video0_fd; fds[0].events = POLLPRI; int ret = poll(fds, std::size(fds), 1000); @@ -1011,15 +382,11 @@ void cameras_run(MultiCameraState *s) { do_exit = do_exit || event_data->u.frame_msg.frame_id > (1*20); } - if (event_data->session_hdl == s->road_cam.session_handle) { - s->road_cam.handle_camera_event(event_data); - } else if (event_data->session_hdl == s->wide_road_cam.session_handle) { - s->wide_road_cam.handle_camera_event(event_data); - } else if (event_data->session_hdl == s->driver_cam.session_handle) { - s->driver_cam.handle_camera_event(event_data); - } else { - LOGE("Unknown vidioc event source"); - assert(false); + for (auto cam : cams) { + if (event_data->session_hdl == cam->session_handle) { + cam->handle_camera_event(event_data); + break; + } } } else { LOGE("unhandled event %d\n", ev.type); @@ -1030,6 +397,6 @@ void cameras_run(MultiCameraState *s) { } LOG(" ************** STOPPING **************"); - for (auto &t : threads) t.join(); + for (auto cam : cams) delete cam; } diff --git a/system/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h deleted file mode 100644 index bd53a326f3..0000000000 --- a/system/camerad/cameras/camera_qcom2.h +++ /dev/null @@ -1,156 +0,0 @@ -#pragma once - -#include -#include - -#include "media/cam_isp_ife.h" - -#include "system/camerad/cameras/camera_common.h" -#include "system/camerad/cameras/camera_util.h" -#include "system/camerad/sensors/sensor.h" -#include "common/util.h" - -#define FRAME_BUF_COUNT 4 - -struct CameraConfig { - int camera_num; - VisionStreamType stream_type; - float focal_len; // millimeters - const char *publish_name; - cereal::FrameData::Builder (cereal::Event::Builder::*init_camera_state)(); - bool enabled; - uint32_t phy; -}; - -const CameraConfig WIDE_ROAD_CAMERA_CONFIG = { - .camera_num = 0, - .stream_type = VISION_STREAM_WIDE_ROAD, - .focal_len = 1.71, - .publish_name = "wideRoadCameraState", - .init_camera_state = &cereal::Event::Builder::initWideRoadCameraState, - .enabled = !getenv("DISABLE_WIDE_ROAD"), - .phy = CAM_ISP_IFE_IN_RES_PHY_0, -}; - -const CameraConfig ROAD_CAMERA_CONFIG = { - .camera_num = 1, - .stream_type = VISION_STREAM_ROAD, - .focal_len = 8.0, - .publish_name = "roadCameraState", - .init_camera_state = &cereal::Event::Builder::initRoadCameraState, - .enabled = !getenv("DISABLE_ROAD"), - .phy = CAM_ISP_IFE_IN_RES_PHY_1, -}; - -const CameraConfig DRIVER_CAMERA_CONFIG = { - .camera_num = 2, - .stream_type = VISION_STREAM_DRIVER, - .focal_len = 1.71, - .publish_name = "driverCameraState", - .init_camera_state = &cereal::Event::Builder::initDriverCameraState, - .enabled = !getenv("DISABLE_DRIVER"), - .phy = CAM_ISP_IFE_IN_RES_PHY_2, -}; - -class CameraState { -public: - CameraConfig cc; - MultiCameraState *multi_cam_state = nullptr; - std::unique_ptr sensor; - bool enabled = true; - bool open = false; - - std::mutex exp_lock; - - int exposure_time = 5; - bool dc_gain_enabled = false; - int dc_gain_weight = 0; - int gain_idx = 0; - float analog_gain_frac = 0; - - float cur_ev[3] = {}; - float best_ev_score = 0; - int new_exp_g = 0; - int new_exp_t = 0; - - Rect ae_xywh = {}; - float measured_grey_fraction = 0; - float target_grey_fraction = 0.3; - - unique_fd sensor_fd; - unique_fd csiphy_fd; - - float fl_pix = 0; - - CameraState(MultiCameraState *multi_camera_state, const CameraConfig &config); - ~CameraState(); - void handle_camera_event(void *evdat); - void update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain); - void set_camera_exposure(float grey_frac); - - void sensors_start(); - - void camera_open(); - void set_exposure_rect(); - void sensor_set_parameters(); - void camera_map_bufs(); - void camera_init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx); - void camera_close(); - void run(); - - int32_t session_handle = -1; - int32_t sensor_dev_handle = -1; - int32_t isp_dev_handle = -1; - int32_t csiphy_dev_handle = -1; - - int32_t link_handle = -1; - - int buf0_handle = 0; - int buf_handle[FRAME_BUF_COUNT] = {}; - int sync_objs[FRAME_BUF_COUNT] = {}; - uint64_t request_ids[FRAME_BUF_COUNT] = {}; - uint64_t request_id_last = 0; - uint64_t frame_id_last = 0; - uint64_t idx_offset = 0; - bool skipped = true; - - CameraBuf buf; - MemoryManager mm; - - void config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset); - void enqueue_req_multi(uint64_t start, int n, bool dp); - void enqueue_buffer(int i, bool dp); - int clear_req_queue(); - - int sensors_init(); - void sensors_poke(int request_id); - void sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word); - -private: - bool openSensor(); - void configISP(); - void configCSIPHY(); - void linkDevices(); -}; - -class MultiCameraState { -public: - MultiCameraState(); - ~MultiCameraState() { - if (pm != nullptr) { - delete pm; - } - }; - - unique_fd video0_fd; - unique_fd cam_sync_fd; - unique_fd isp_fd; - int device_iommu = -1; - int cdm_iommu = -1; - - CameraState road_cam; - CameraState wide_road_cam; - CameraState driver_cam; - - PubMaster *pm = nullptr; -}; diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc new file mode 100644 index 0000000000..609d77bf0f --- /dev/null +++ b/system/camerad/cameras/spectra.cc @@ -0,0 +1,695 @@ +#include + +#include +#include +#include +#include + +#include "media/cam_defs.h" +#include "media/cam_isp.h" +#include "media/cam_isp_ife.h" +#include "media/cam_req_mgr.h" +#include "media/cam_sensor_cmn_header.h" +#include "media/cam_sync.h" + +#include "common/util.h" +#include "common/swaglog.h" + +#include "system/camerad/cameras/spectra.h" + + +// *** helpers *** + +static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) { + cam_cmd_unconditional_wait *unconditional_wait = (cam_cmd_unconditional_wait *)((char *)power + (sizeof(struct cam_cmd_power) + (power->count - 1) * sizeof(struct cam_power_settings))); + unconditional_wait->cmd_type = CAMERA_SENSOR_CMD_TYPE_WAIT; + unconditional_wait->delay = delay_ms; + unconditional_wait->op_code = CAMERA_SENSOR_WAIT_OP_SW_UCND; + return (struct cam_cmd_power *)(unconditional_wait + 1); +} + +// *** SpectraMaster *** + +void SpectraMaster::init() { + LOG("-- Opening devices"); + // video0 is req_mgr, the target of many ioctls + video0_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-soc:qcom_cam-req-mgr-video-index0", O_RDWR | O_NONBLOCK)); + assert(video0_fd >= 0); + LOGD("opened video0"); + + // video1 is cam_sync, the target of some ioctls + cam_sync_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-cam_sync-video-index0", O_RDWR | O_NONBLOCK)); + assert(cam_sync_fd >= 0); + LOGD("opened video1 (cam_sync)"); + + // looks like there's only one of these + isp_fd = open_v4l_by_name_and_index("cam-isp"); + assert(isp_fd >= 0); + LOGD("opened isp"); + + // query icp for MMU handles + LOG("-- Query ICP for MMU handles"); + struct cam_isp_query_cap_cmd isp_query_cap_cmd = {0}; + struct cam_query_cap_cmd query_cap_cmd = {0}; + query_cap_cmd.handle_type = 1; + query_cap_cmd.caps_handle = (uint64_t)&isp_query_cap_cmd; + query_cap_cmd.size = sizeof(isp_query_cap_cmd); + int ret = do_cam_control(isp_fd, CAM_QUERY_CAP, &query_cap_cmd, sizeof(query_cap_cmd)); + assert(ret == 0); + LOGD("using MMU handle: %x", isp_query_cap_cmd.device_iommu.non_secure); + LOGD("using MMU handle: %x", isp_query_cap_cmd.cdm_iommu.non_secure); + device_iommu = isp_query_cap_cmd.device_iommu.non_secure; + cdm_iommu = isp_query_cap_cmd.cdm_iommu.non_secure; + + // subscribe + LOG("-- Subscribing"); + struct v4l2_event_subscription sub = {0}; + sub.type = V4L_EVENT_CAM_REQ_MGR_EVENT; + sub.id = V4L_EVENT_CAM_REQ_MGR_SOF_BOOT_TS; + ret = HANDLE_EINTR(ioctl(video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); + LOGD("req mgr subscribe: %d", ret); +} + +// *** SpectraCamera *** + +SpectraCamera::SpectraCamera(SpectraMaster *master, const CameraConfig &config) + : m(master), + enabled(config.enabled) , + cc(config) { + mm.init(m->video0_fd); +} + +SpectraCamera::~SpectraCamera() { + if (open) { + camera_close(); + } +} + +int SpectraCamera::clear_req_queue() { + struct cam_req_mgr_flush_info req_mgr_flush_request = {0}; + req_mgr_flush_request.session_hdl = session_handle; + req_mgr_flush_request.link_hdl = link_handle; + req_mgr_flush_request.flush_type = CAM_REQ_MGR_FLUSH_TYPE_ALL; + int ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_FLUSH_REQ, &req_mgr_flush_request, sizeof(req_mgr_flush_request)); + // LOGD("flushed all req: %d", ret); + return ret; +} + +void SpectraCamera::camera_open() { + if (!enabled) return; + + if (!openSensor()) { + return; + } + + open = true; + configISP(); + configCSIPHY(); + linkDevices(); +} + +void SpectraCamera::camera_init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx) { + if (!enabled) return; + + LOGD("camera init %d", cc.camera_num); + buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, cc.stream_type); + camera_map_bufs(); +} + +void SpectraCamera::enqueue_req_multi(uint64_t start, int n, bool dp) { + for (uint64_t i = start; i < start + n; ++i) { + request_ids[(i - 1) % FRAME_BUF_COUNT] = i; + enqueue_buffer((i - 1) % FRAME_BUF_COUNT, dp); + } +} + +void SpectraCamera::sensors_start() { + if (!enabled) return; + LOGD("starting sensor %d", cc.camera_num); + sensors_i2c(sensor->start_reg_array.data(), sensor->start_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, sensor->data_word); +} + +void SpectraCamera::sensors_poke(int request_id) { + uint32_t cam_packet_handle = 0; + int size = sizeof(struct cam_packet); + auto pkt = mm.alloc(size, &cam_packet_handle); + pkt->num_cmd_buf = 0; + pkt->kmd_cmd_buf_index = -1; + pkt->header.size = size; + pkt->header.op_code = CAM_SENSOR_PACKET_OPCODE_SENSOR_NOP; + pkt->header.request_id = request_id; + + int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); + if (ret != 0) { + LOGE("** sensor %d FAILED poke, disabling", cc.camera_num); + enabled = false; + return; + } +} + +void SpectraCamera::sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word) { + // LOGD("sensors_i2c: %d", len); + uint32_t cam_packet_handle = 0; + int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; + auto pkt = mm.alloc(size, &cam_packet_handle); + pkt->num_cmd_buf = 1; + pkt->kmd_cmd_buf_index = -1; + pkt->header.size = size; + pkt->header.op_code = op_code; + struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; + + buf_desc[0].size = buf_desc[0].length = sizeof(struct i2c_rdwr_header) + len*sizeof(struct i2c_random_wr_payload); + buf_desc[0].type = CAM_CMD_BUF_I2C; + + auto i2c_random_wr = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); + i2c_random_wr->header.count = len; + i2c_random_wr->header.op_code = 1; + i2c_random_wr->header.cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR; + i2c_random_wr->header.data_type = data_word ? CAMERA_SENSOR_I2C_TYPE_WORD : CAMERA_SENSOR_I2C_TYPE_BYTE; + i2c_random_wr->header.addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; + memcpy(i2c_random_wr->random_wr_payload, dat, len*sizeof(struct i2c_random_wr_payload)); + + int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); + if (ret != 0) { + LOGE("** sensor %d FAILED i2c, disabling", cc.camera_num); + enabled = false; + return; + } +} + +int SpectraCamera::sensors_init() { + uint32_t cam_packet_handle = 0; + int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; + auto pkt = mm.alloc(size, &cam_packet_handle); + pkt->num_cmd_buf = 2; + pkt->kmd_cmd_buf_index = -1; + pkt->header.op_code = 0x1000000 | CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE; + pkt->header.size = size; + struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; + + buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_info) + sizeof(struct cam_cmd_probe); + buf_desc[0].type = CAM_CMD_BUF_LEGACY; + auto i2c_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); + auto probe = (struct cam_cmd_probe *)(i2c_info.get() + 1); + + probe->camera_id = cc.camera_num; + i2c_info->slave_addr = sensor->getSlaveAddress(cc.camera_num); + // 0(I2C_STANDARD_MODE) = 100khz, 1(I2C_FAST_MODE) = 400khz + //i2c_info->i2c_freq_mode = I2C_STANDARD_MODE; + i2c_info->i2c_freq_mode = I2C_FAST_MODE; + i2c_info->cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_INFO; + + probe->data_type = CAMERA_SENSOR_I2C_TYPE_WORD; + probe->addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; + probe->op_code = 3; // don't care? + probe->cmd_type = CAMERA_SENSOR_CMD_TYPE_PROBE; + probe->reg_addr = sensor->probe_reg_addr; + probe->expected_data = sensor->probe_expected_data; + probe->data_mask = 0; + + //buf_desc[1].size = buf_desc[1].length = 148; + buf_desc[1].size = buf_desc[1].length = 196; + buf_desc[1].type = CAM_CMD_BUF_I2C; + auto power_settings = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); + + // power on + struct cam_cmd_power *power = power_settings.get(); + power->count = 4; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; + power->power_settings[0].power_seq_type = 3; // clock?? + power->power_settings[1].power_seq_type = 1; // analog + power->power_settings[2].power_seq_type = 2; // digital + power->power_settings[3].power_seq_type = 8; // reset low + power = power_set_wait(power, 1); + + // set clock + power->count = 1; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; + power->power_settings[0].power_seq_type = 0; + power->power_settings[0].config_val_low = sensor->mclk_frequency; + power = power_set_wait(power, 1); + + // reset high + power->count = 1; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; + power->power_settings[0].power_seq_type = 8; + power->power_settings[0].config_val_low = 1; + // wait 650000 cycles @ 19.2 mhz = 33.8 ms + power = power_set_wait(power, 34); + + // probe happens here + + // disable clock + power->count = 1; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; + power->power_settings[0].power_seq_type = 0; + power->power_settings[0].config_val_low = 0; + power = power_set_wait(power, 1); + + // reset high + power->count = 1; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; + power->power_settings[0].power_seq_type = 8; + power->power_settings[0].config_val_low = 1; + power = power_set_wait(power, 1); + + // reset low + power->count = 1; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; + power->power_settings[0].power_seq_type = 8; + power->power_settings[0].config_val_low = 0; + power = power_set_wait(power, 1); + + // power off + power->count = 3; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; + power->power_settings[0].power_seq_type = 2; + power->power_settings[1].power_seq_type = 1; + power->power_settings[2].power_seq_type = 3; + + int ret = do_cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)(uintptr_t)cam_packet_handle, 0); + LOGD("probing the sensor: %d", ret); + return ret; +} + +void SpectraCamera::config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset) { + uint32_t cam_packet_handle = 0; + int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; + if (io_mem_handle != 0) { + size += sizeof(struct cam_buf_io_cfg); + } + auto pkt = mm.alloc(size, &cam_packet_handle); + pkt->num_cmd_buf = 2; + pkt->kmd_cmd_buf_index = 0; + + if (io_mem_handle != 0) { + pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf; + pkt->num_io_configs = 1; + } + + if (io_mem_handle != 0) { + pkt->header.op_code = 0xf000001; + pkt->header.request_id = request_id; + } else { + pkt->header.op_code = 0xf000000; + pkt->header.request_id = 1; + } + pkt->header.size = size; + struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; + struct cam_buf_io_cfg *io_cfg = (struct cam_buf_io_cfg *)((char*)&pkt->payload + pkt->io_configs_offset); + + // TODO: support MMU + buf_desc[0].size = 65624; + buf_desc[0].length = 0; + buf_desc[0].type = CAM_CMD_BUF_DIRECT; + buf_desc[0].meta_data = 3; + buf_desc[0].mem_handle = buf0_mem_handle; + buf_desc[0].offset = buf0_offset; + + // parsed by cam_isp_packet_generic_blob_handler + struct isp_packet { + uint32_t type_0; + cam_isp_resource_hfr_config resource_hfr; + + uint32_t type_1; + cam_isp_clock_config clock; + uint64_t extra_rdi_hz[3]; + + uint32_t type_2; + cam_isp_bw_config bw; + struct cam_isp_bw_vote extra_rdi_vote[6]; + } __attribute__((packed)) tmp; + memset(&tmp, 0, sizeof(tmp)); + + tmp.type_0 = CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG; + tmp.type_0 |= sizeof(cam_isp_resource_hfr_config) << 8; + static_assert(sizeof(cam_isp_resource_hfr_config) == 0x20); + tmp.resource_hfr = { + .num_ports = 1, // 10 for YUV (but I don't think we need them) + .port_hfr_config[0] = { + .resource_type = CAM_ISP_IFE_OUT_RES_RDI_0, // CAM_ISP_IFE_OUT_RES_FULL for YUV + .subsample_pattern = 1, + .subsample_period = 0, + .framedrop_pattern = 1, + .framedrop_period = 0, + }}; + + tmp.type_1 = CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG; + tmp.type_1 |= (sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) << 8; + static_assert((sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) == 0x38); + tmp.clock = { + .usage_type = 1, // dual mode + .num_rdi = 4, + .left_pix_hz = 404000000, + .right_pix_hz = 404000000, + .rdi_hz[0] = 404000000, + }; + + tmp.type_2 = CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG; + tmp.type_2 |= (sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) << 8; + static_assert((sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) == 0xe0); + tmp.bw = { + .usage_type = 1, // dual mode + .num_rdi = 4, + .left_pix_vote = { + .resource_id = 0, + .cam_bw_bps = 450000000, + .ext_bw_bps = 450000000, + }, + .rdi_vote[0] = { + .resource_id = 0, + .cam_bw_bps = 8706200000, + .ext_bw_bps = 8706200000, + }, + }; + + static_assert(offsetof(struct isp_packet, type_2) == 0x60); + + buf_desc[1].size = sizeof(tmp); + buf_desc[1].offset = io_mem_handle != 0 ? 0x60 : 0; + buf_desc[1].length = buf_desc[1].size - buf_desc[1].offset; + buf_desc[1].type = CAM_CMD_BUF_GENERIC; + buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; + auto buf2 = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); + memcpy(buf2.get(), &tmp, sizeof(tmp)); + + if (io_mem_handle != 0) { + io_cfg[0].mem_handle[0] = io_mem_handle; + io_cfg[0].planes[0] = (struct cam_plane_cfg){ + .width = sensor->frame_width, + .height = sensor->frame_height + sensor->extra_height, + .plane_stride = sensor->frame_stride, + .slice_height = sensor->frame_height + sensor->extra_height, + .meta_stride = 0x0, // YUV has meta(stride=0x400, size=0x5000) + .meta_size = 0x0, + .meta_offset = 0x0, + .packer_config = 0x0, // 0xb for YUV + .mode_config = 0x0, // 0x9ef for YUV + .tile_config = 0x0, + .h_init = 0x0, + .v_init = 0x0, + }; + io_cfg[0].format = sensor->mipi_format; // CAM_FORMAT_UBWC_TP10 for YUV + io_cfg[0].color_space = CAM_COLOR_SPACE_BASE; // CAM_COLOR_SPACE_BT601_FULL for YUV + io_cfg[0].color_pattern = 0x5; // 0x0 for YUV + io_cfg[0].bpp = (sensor->mipi_format == CAM_FORMAT_MIPI_RAW_10 ? 0xa : 0xc); // bits per pixel + io_cfg[0].resource_type = CAM_ISP_IFE_OUT_RES_RDI_0; // CAM_ISP_IFE_OUT_RES_FULL for YUV + io_cfg[0].fence = fence; + io_cfg[0].direction = CAM_BUF_OUTPUT; + io_cfg[0].subsample_pattern = 0x1; + io_cfg[0].framedrop_pattern = 0x1; + } + + int ret = device_config(m->isp_fd, session_handle, isp_dev_handle, cam_packet_handle); + assert(ret == 0); + if (ret != 0) { + LOGE("isp config failed"); + } +} + +void SpectraCamera::enqueue_buffer(int i, bool dp) { + int ret; + uint64_t request_id = request_ids[i]; + + if (buf_handle[i] && sync_objs[i]) { + // wait + struct cam_sync_wait sync_wait = {0}; + sync_wait.sync_obj = sync_objs[i]; + sync_wait.timeout_ms = 50; // max dt tolerance, typical should be 23 + ret = do_cam_control(m->cam_sync_fd, CAM_SYNC_WAIT, &sync_wait, sizeof(sync_wait)); + if (ret != 0) { + LOGE("failed to wait for sync: %d %d", ret, sync_wait.sync_obj); + // TODO: handle frame drop cleanly + } + + buf.camera_bufs_metadata[i].timestamp_eof = (uint64_t)nanos_since_boot(); // set true eof + if (dp) buf.queue(i); + + // destroy old output fence + struct cam_sync_info sync_destroy = {0}; + sync_destroy.sync_obj = sync_objs[i]; + ret = do_cam_control(m->cam_sync_fd, CAM_SYNC_DESTROY, &sync_destroy, sizeof(sync_destroy)); + if (ret != 0) { + LOGE("failed to destroy sync object: %d %d", ret, sync_destroy.sync_obj); + } + } + + // create output fence + struct cam_sync_info sync_create = {0}; + strcpy(sync_create.name, "NodeOutputPortFence"); + ret = do_cam_control(m->cam_sync_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create)); + if (ret != 0) { + LOGE("failed to create fence: %d %d", ret, sync_create.sync_obj); + } + sync_objs[i] = sync_create.sync_obj; + + // schedule request with camera request manager + struct cam_req_mgr_sched_request req_mgr_sched_request = {0}; + req_mgr_sched_request.session_hdl = session_handle; + req_mgr_sched_request.link_hdl = link_handle; + req_mgr_sched_request.req_id = request_id; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_SCHED_REQ, &req_mgr_sched_request, sizeof(req_mgr_sched_request)); + if (ret != 0) { + LOGE("failed to schedule cam mgr request: %d %lu", ret, request_id); + } + + // poke sensor, must happen after schedule + sensors_poke(request_id); + + // submit request to the ife + config_isp(buf_handle[i], sync_objs[i], request_id, buf0_handle, 65632*(i+1)); +} + +void SpectraCamera::camera_map_bufs() { + for (int i = 0; i < FRAME_BUF_COUNT; i++) { + // configure ISP to put the image in place + struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0}; + mem_mgr_map_cmd.mmu_hdls[0] = m->device_iommu; + mem_mgr_map_cmd.num_hdl = 1; + mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE; + mem_mgr_map_cmd.fd = buf.camera_bufs[i].fd; + int ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd)); + LOGD("map buf req: (fd: %d) 0x%x %d", buf.camera_bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret); + buf_handle[i] = mem_mgr_map_cmd.out.buf_handle; + } + enqueue_req_multi(1, FRAME_BUF_COUNT, 0); +} + +bool SpectraCamera::openSensor() { + sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", cc.camera_num); + assert(sensor_fd >= 0); + LOGD("opened sensor for %d", cc.camera_num); + + LOGD("-- Probing sensor %d", cc.camera_num); + + auto init_sensor_lambda = [this](SensorInfo *s) { + sensor.reset(s); + return (sensors_init() == 0); + }; + + // Figure out which sensor we have + if (!init_sensor_lambda(new AR0231) && + !init_sensor_lambda(new OX03C10) && + !init_sensor_lambda(new OS04C10)) { + LOGE("** sensor %d FAILED bringup, disabling", cc.camera_num); + enabled = false; + return false; + } + LOGD("-- Probing sensor %d success", cc.camera_num); + + // create session + struct cam_req_mgr_session_info session_info = {}; + int ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_CREATE_SESSION, &session_info, sizeof(session_info)); + LOGD("get session: %d 0x%X", ret, session_info.session_hdl); + session_handle = session_info.session_hdl; + + // access the sensor + LOGD("-- Accessing sensor"); + auto sensor_dev_handle_ = device_acquire(sensor_fd, session_handle, nullptr); + assert(sensor_dev_handle_); + sensor_dev_handle = *sensor_dev_handle_; + LOGD("acquire sensor dev"); + + LOG("-- Configuring sensor"); + sensors_i2c(sensor->init_reg_array.data(), sensor->init_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, sensor->data_word); + return true; +} + +void SpectraCamera::configISP() { + // NOTE: to be able to disable road and wide road, we still have to configure the sensor over i2c + // If you don't do this, the strobe GPIO is an output (even in reset it seems!) + if (!enabled) return; + + struct cam_isp_in_port_info in_port_info = { + .res_type = cc.phy, + .lane_type = CAM_ISP_LANE_TYPE_DPHY, + .lane_num = 4, + .lane_cfg = 0x3210, + + .vc = 0x0, + .dt = sensor->frame_data_type, + .format = sensor->mipi_format, + + .test_pattern = 0x2, // 0x3? + .usage_type = 0x0, + + .left_start = 0, + .left_stop = sensor->frame_width - 1, + .left_width = sensor->frame_width, + + .right_start = 0, + .right_stop = sensor->frame_width - 1, + .right_width = sensor->frame_width, + + .line_start = 0, + .line_stop = sensor->frame_height + sensor->extra_height - 1, + .height = sensor->frame_height + sensor->extra_height, + + .pixel_clk = 0x0, + .batch_size = 0x0, + .dsp_mode = CAM_ISP_DSP_MODE_NONE, + .hbi_cnt = 0x0, + .custom_csid = 0x0, + + .num_out_res = 0x1, + .data[0] = (struct cam_isp_out_port_info){ + .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, + .format = sensor->mipi_format, + .width = sensor->frame_width, + .height = sensor->frame_height + sensor->extra_height, + .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, + }, + }; + struct cam_isp_resource isp_resource = { + .resource_id = CAM_ISP_RES_ID_PORT, + .handle_type = CAM_HANDLE_USER_POINTER, + .res_hdl = (uint64_t)&in_port_info, + .length = sizeof(in_port_info), + }; + + auto isp_dev_handle_ = device_acquire(m->isp_fd, session_handle, &isp_resource); + assert(isp_dev_handle_); + isp_dev_handle = *isp_dev_handle_; + LOGD("acquire isp dev"); + + // config ISP + alloc_w_mmu_hdl(m->video0_fd, 984480, (uint32_t*)&buf0_handle, 0x20, CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | + CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, m->device_iommu, m->cdm_iommu); + config_isp(0, 0, 1, buf0_handle, 0); +} + +void SpectraCamera::configCSIPHY() { + csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", cc.camera_num); + assert(csiphy_fd >= 0); + LOGD("opened csiphy for %d", cc.camera_num); + + struct cam_csiphy_acquire_dev_info csiphy_acquire_dev_info = {.combo_mode = 0}; + auto csiphy_dev_handle_ = device_acquire(csiphy_fd, session_handle, &csiphy_acquire_dev_info); + assert(csiphy_dev_handle_); + csiphy_dev_handle = *csiphy_dev_handle_; + LOGD("acquire csiphy dev"); + + // config csiphy + LOG("-- Config CSI PHY"); + { + uint32_t cam_packet_handle = 0; + int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; + auto pkt = mm.alloc(size, &cam_packet_handle); + pkt->num_cmd_buf = 1; + pkt->kmd_cmd_buf_index = -1; + pkt->header.size = size; + struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; + + buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_csiphy_info); + buf_desc[0].type = CAM_CMD_BUF_GENERIC; + + auto csiphy_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); + csiphy_info->lane_mask = 0x1f; + csiphy_info->lane_assign = 0x3210;// skip clk. How is this 16 bit for 5 channels?? + csiphy_info->csiphy_3phase = 0x0; // no 3 phase, only 2 conductors per lane + csiphy_info->combo_mode = 0x0; + csiphy_info->lane_cnt = 0x4; + csiphy_info->secure_mode = 0x0; + csiphy_info->settle_time = MIPI_SETTLE_CNT * 200000000ULL; + csiphy_info->data_rate = 48000000; // Calculated by camera_freqs.py + + int ret_ = device_config(csiphy_fd, session_handle, csiphy_dev_handle, cam_packet_handle); + assert(ret_ == 0); + } +} + +void SpectraCamera::linkDevices() { + LOG("-- Link devices"); + struct cam_req_mgr_link_info req_mgr_link_info = {0}; + req_mgr_link_info.session_hdl = session_handle; + req_mgr_link_info.num_devices = 2; + req_mgr_link_info.dev_hdls[0] = isp_dev_handle; + req_mgr_link_info.dev_hdls[1] = sensor_dev_handle; + int ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_LINK, &req_mgr_link_info, sizeof(req_mgr_link_info)); + link_handle = req_mgr_link_info.link_hdl; + LOGD("link: %d session: 0x%X isp: 0x%X sensors: 0x%X link: 0x%X", ret, session_handle, isp_dev_handle, sensor_dev_handle, link_handle); + + struct cam_req_mgr_link_control req_mgr_link_control = {0}; + req_mgr_link_control.ops = CAM_REQ_MGR_LINK_ACTIVATE; + req_mgr_link_control.session_hdl = session_handle; + req_mgr_link_control.num_links = 1; + req_mgr_link_control.link_hdls[0] = link_handle; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); + LOGD("link control: %d", ret); + + ret = device_control(csiphy_fd, CAM_START_DEV, session_handle, csiphy_dev_handle); + LOGD("start csiphy: %d", ret); + ret = device_control(m->isp_fd, CAM_START_DEV, session_handle, isp_dev_handle); + LOGD("start isp: %d", ret); + assert(ret == 0); +} + +void SpectraCamera::camera_close() { + LOG("-- Stop devices %d", cc.camera_num); + + if (enabled) { + // ret = device_control(sensor_fd, CAM_STOP_DEV, session_handle, sensor_dev_handle); + // LOGD("stop sensor: %d", ret); + int ret = device_control(m->isp_fd, CAM_STOP_DEV, session_handle, isp_dev_handle); + LOGD("stop isp: %d", ret); + ret = device_control(csiphy_fd, CAM_STOP_DEV, session_handle, csiphy_dev_handle); + LOGD("stop csiphy: %d", ret); + // link control stop + LOG("-- Stop link control"); + struct cam_req_mgr_link_control req_mgr_link_control = {0}; + req_mgr_link_control.ops = CAM_REQ_MGR_LINK_DEACTIVATE; + req_mgr_link_control.session_hdl = session_handle; + req_mgr_link_control.num_links = 1; + req_mgr_link_control.link_hdls[0] = link_handle; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); + LOGD("link control stop: %d", ret); + + // unlink + LOG("-- Unlink"); + struct cam_req_mgr_unlink_info req_mgr_unlink_info = {0}; + req_mgr_unlink_info.session_hdl = session_handle; + req_mgr_unlink_info.link_hdl = link_handle; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_UNLINK, &req_mgr_unlink_info, sizeof(req_mgr_unlink_info)); + LOGD("unlink: %d", ret); + + // release devices + LOGD("-- Release devices"); + ret = device_control(m->isp_fd, CAM_RELEASE_DEV, session_handle, isp_dev_handle); + LOGD("release isp: %d", ret); + ret = device_control(csiphy_fd, CAM_RELEASE_DEV, session_handle, csiphy_dev_handle); + LOGD("release csiphy: %d", ret); + + for (int i = 0; i < FRAME_BUF_COUNT; i++) { + release(m->video0_fd, buf_handle[i]); + } + LOGD("released buffers"); + } + + int ret = device_control(sensor_fd, CAM_RELEASE_DEV, session_handle, sensor_dev_handle); + LOGD("release sensor: %d", ret); + + // destroyed session + struct cam_req_mgr_session_info session_info = {.session_hdl = session_handle}; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_DESTROY_SESSION, &session_info, sizeof(session_info)); + LOGD("destroyed session %d: %d", cc.camera_num, ret); +} diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h new file mode 100644 index 0000000000..baa5cbc32f --- /dev/null +++ b/system/camerad/cameras/spectra.h @@ -0,0 +1,87 @@ +#pragma once + +#include +#include + +#include "media/cam_isp_ife.h" + +#include "common/util.h" +#include "system/camerad/cameras/tici.h" +#include "system/camerad/cameras/camera_util.h" +#include "system/camerad/cameras/camera_common.h" +#include "system/camerad/sensors/sensor.h" + +#define FRAME_BUF_COUNT 4 + +const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py + +// For use with the Spectra 280 ISP in the SDM845 +// https://github.com/commaai/agnos-kernel-sdm845 + + +class SpectraMaster { +public: + void init(); + + unique_fd video0_fd; + unique_fd cam_sync_fd; + unique_fd isp_fd; + int device_iommu = -1; + int cdm_iommu = -1; +}; + +class SpectraCamera { +public: + SpectraCamera(SpectraMaster *master, const CameraConfig &config); + ~SpectraCamera(); + + void camera_open(); + void camera_close(); + void camera_map_bufs(); + void camera_init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx); + void config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset); + + int clear_req_queue(); + void enqueue_buffer(int i, bool dp); + void enqueue_req_multi(uint64_t start, int n, bool dp); + + int sensors_init(); + void sensors_start(); + void sensors_poke(int request_id); + void sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word); + + bool openSensor(); + void configISP(); + void configCSIPHY(); + void linkDevices(); + + // *** state *** + + bool open = false; + bool enabled = true; + CameraConfig cc; + std::unique_ptr sensor; + + unique_fd sensor_fd; + unique_fd csiphy_fd; + + int32_t session_handle = -1; + int32_t sensor_dev_handle = -1; + int32_t isp_dev_handle = -1; + int32_t csiphy_dev_handle = -1; + + int32_t link_handle = -1; + + int buf0_handle = 0; + int buf_handle[FRAME_BUF_COUNT] = {}; + int sync_objs[FRAME_BUF_COUNT] = {}; + uint64_t request_ids[FRAME_BUF_COUNT] = {}; + uint64_t request_id_last = 0; + uint64_t frame_id_last = 0; + uint64_t idx_offset = 0; + bool skipped = true; + + CameraBuf buf; + MemoryManager mm; + SpectraMaster *m; +}; diff --git a/system/camerad/cameras/tici.h b/system/camerad/cameras/tici.h new file mode 100644 index 0000000000..228ff8e284 --- /dev/null +++ b/system/camerad/cameras/tici.h @@ -0,0 +1,49 @@ +#pragma once + +#include "common/util.h" +#include "cereal/gen/cpp/log.capnp.h" +#include "msgq/visionipc/visionipc_server.h" + +#include "media/cam_isp_ife.h" + +// For the comma 3/3X three camera platform + +struct CameraConfig { + int camera_num; + VisionStreamType stream_type; + float focal_len; // millimeters + const char *publish_name; + cereal::FrameData::Builder (cereal::Event::Builder::*init_camera_state)(); + bool enabled; + uint32_t phy; +}; + +const CameraConfig WIDE_ROAD_CAMERA_CONFIG = { + .camera_num = 0, + .stream_type = VISION_STREAM_WIDE_ROAD, + .focal_len = 1.71, + .publish_name = "wideRoadCameraState", + .init_camera_state = &cereal::Event::Builder::initWideRoadCameraState, + .enabled = !getenv("DISABLE_WIDE_ROAD"), + .phy = CAM_ISP_IFE_IN_RES_PHY_0, +}; + +const CameraConfig ROAD_CAMERA_CONFIG = { + .camera_num = 1, + .stream_type = VISION_STREAM_ROAD, + .focal_len = 8.0, + .publish_name = "roadCameraState", + .init_camera_state = &cereal::Event::Builder::initRoadCameraState, + .enabled = !getenv("DISABLE_ROAD"), + .phy = CAM_ISP_IFE_IN_RES_PHY_1, +}; + +const CameraConfig DRIVER_CAMERA_CONFIG = { + .camera_num = 2, + .stream_type = VISION_STREAM_DRIVER, + .focal_len = 1.71, + .publish_name = "driverCameraState", + .init_camera_state = &cereal::Event::Builder::initDriverCameraState, + .enabled = !getenv("DISABLE_DRIVER"), + .phy = CAM_ISP_IFE_IN_RES_PHY_2, +}; diff --git a/system/camerad/sensors/ar0231.cc b/system/camerad/sensors/ar0231.cc index 74f09dfa61..ce8b0c0a4b 100644 --- a/system/camerad/sensors/ar0231.cc +++ b/system/camerad/sensors/ar0231.cc @@ -1,7 +1,6 @@ #include #include "common/swaglog.h" -#include "system/camerad/cameras/camera_common.h" #include "system/camerad/sensors/sensor.h" namespace { diff --git a/system/camerad/sensors/sensor.h b/system/camerad/sensors/sensor.h index 22083eb62b..4ab09a9fd2 100644 --- a/system/camerad/sensors/sensor.h +++ b/system/camerad/sensors/sensor.h @@ -6,7 +6,8 @@ #include #include #include "media/cam_sensor.h" -#include "system/camerad/cameras/camera_common.h" + +#include "cereal/gen/cpp/log.capnp.h" #include "system/camerad/sensors/ar0231_registers.h" #include "system/camerad/sensors/ox03c10_registers.h" #include "system/camerad/sensors/os04c10_registers.h" From e018a20bc2b7e40b957b7bc9d90cacea2473bcc1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 18 Sep 2024 22:47:42 -0700 Subject: [PATCH 087/214] longitudinal maneuver readme: small improvements --- tools/longitudinal_maneuvers/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tools/longitudinal_maneuvers/README.md b/tools/longitudinal_maneuvers/README.md index f1981d9b1e..66ec697912 100644 --- a/tools/longitudinal_maneuvers/README.md +++ b/tools/longitudinal_maneuvers/README.md @@ -1,6 +1,6 @@ # Longitudinal Maneuvers Testing Tool -Test your vehicle's longitudinal control with this tool. The tool will test the vehicle's ability to follow a few longitudinal maneuvers and includes a tool to generate a report from the route. +Test your vehicle's longitudinal control tuning with this tool. The tool will test the vehicle's ability to follow a few longitudinal maneuvers and includes a tool to generate a report from the route.
Sample snapshot of a report.
@@ -18,11 +18,11 @@ Test your vehicle's longitudinal control with this tool. The tool will test the ![videoframe_6652](https://github.com/user-attachments/assets/e9d4c95a-cd76-4ab7-933e-19937792fa0f) -5. Ensure the road ahead is clear, as openpilot will not brake for any obstructions in this mode. If so, press "Set" on your steering wheel to start the tests. The tests will run for about 4 minutes. If you need to pause the tests, press "Cancel" on your steering wheel. You can resume the tests by pressing "Resume" on your steering wheel. +5. Ensure the road ahead is clear, as openpilot will not brake for any obstructions in this mode. Once you are ready, press "Set" on your steering wheel to start the tests. The tests will run for about 4 minutes. If you need to pause the tests, press "Cancel" on your steering wheel. You can resume the tests by pressing "Resume" on your steering wheel. ![cog-clip-00 01 11 250-00 01 22 250](https://github.com/user-attachments/assets/c312c1cc-76e8-46e1-a05e-bb9dfb58994f) -6. When the testing is complete, you'll see an alert that says "Maneuvers Finished," complete the route by pulling over and turning off the vehicle. +6. When the testing is complete, you'll see an alert that says "Maneuvers Finished." Complete the route by pulling over and turning off the vehicle. ![fin2](https://github.com/user-attachments/assets/c06960ae-7cfb-44af-beaa-4dc28848e49d) From 08b731cbd7587ef750ce4b60d3978e8a473b515e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 18 Sep 2024 22:48:15 -0700 Subject: [PATCH 088/214] Lexus ES TSS2: improve start from stop for ICE variants (#33586) bump --- opendbc_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc_repo b/opendbc_repo index c8beb979ec..b937eefca1 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit c8beb979ecd675adeae0c35df7ba4b71f90685d6 +Subproject commit b937eefca19a70f38ddd2a9ffbc9d331f581ec9d From fc8762ab51d8dd9e45997497af2a7c5bbb5b812d Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 19 Sep 2024 13:53:47 +0800 Subject: [PATCH 089/214] ci: fix ui report issues (#33585) * fix ui report issues * fix indentation * Update selfdrive/ui/tests/test_ui/run.py --------- Co-authored-by: Shane Smiskol --- selfdrive/ui/tests/test_ui/run.py | 21 +++++++++++++++++++-- 1 file changed, 19 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 6f8acb1a53..eee0ada266 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -12,7 +12,7 @@ import time from cereal import log from msgq.visionipc import VisionIpcServer, VisionStreamType -from cereal.messaging import PubMaster, log_from_bytes +from cereal.messaging import PubMaster, log_from_bytes, sub_sock from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params from openpilot.common.prefix import OpenpilotPrefix @@ -51,7 +51,15 @@ def setup_onroad(click, pm: PubMaster): vipc_server.create_buffers(stream_type, 5, False, cam.width, cam.height) vipc_server.start_listener() - for packet_id in range(30): + uidebug_received_cnt = 0 + packet_id = 0 + uidebug_sock = sub_sock('uiDebug') + + # Condition check for uiDebug processing + check_uidebug = DATA['deviceState'].deviceState.started and not DATA['carParams'].carParams.notCar + + # Loop until 20 'uiDebug' messages are received + while uidebug_received_cnt <= 20: for service, data in DATA.items(): if data: data.clear_write_flag() @@ -60,6 +68,13 @@ def setup_onroad(click, pm: PubMaster): for stream_type, _, image in STREAMS: vipc_server.send(stream_type, image, packet_id, packet_id, packet_id) + if check_uidebug: + while uidebug_sock.receive(non_blocking=True): + uidebug_received_cnt += 1 + else: + uidebug_received_cnt += 1 + + packet_id += 1 time.sleep(0.05) def setup_onroad_wide(click, pm: PubMaster): @@ -70,10 +85,12 @@ def setup_onroad_wide(click, pm: PubMaster): def setup_onroad_sidebar(click, pm: PubMaster): setup_onroad(click, pm) click(500, 500) + setup_onroad(click, pm) def setup_onroad_wide_sidebar(click, pm: PubMaster): setup_onroad_wide(click, pm) click(500, 500) + setup_onroad_wide(click, pm) def setup_body(click, pm: PubMaster): DATA['carParams'].carParams.carName = "BODY" From 467bd749447b3613d24391bee4b1ce3fece57dbe Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 20 Sep 2024 01:33:24 +0800 Subject: [PATCH 090/214] camerad: remove `CameraType` enum from `camera_common.h` (#33588) remove CameraType from camera_common.h --- system/camerad/cameras/camera_common.h | 6 ------ system/loggerd/encoder/encoder.h | 1 - system/loggerd/encoderd.cc | 8 ++++---- system/loggerd/loggerd.h | 8 -------- tools/replay/framereader.h | 2 +- tools/replay/logreader.h | 1 - tools/replay/util.h | 7 +++++++ 7 files changed, 12 insertions(+), 21 deletions(-) diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index d1f0b0d0e1..0536ecc7f3 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -11,12 +11,6 @@ const int YUV_BUFFER_COUNT = 20; -enum CameraType { - RoadCam = 0, - DriverCam, - WideRoadCam -}; - // for debugging const bool env_debug_frames = getenv("DEBUG_FRAMES") != NULL; const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != NULL; diff --git a/system/loggerd/encoder/encoder.h b/system/loggerd/encoder/encoder.h index 96ad4ffeb0..1296f78f61 100644 --- a/system/loggerd/encoder/encoder.h +++ b/system/loggerd/encoder/encoder.h @@ -17,7 +17,6 @@ #include "cereal/messaging/messaging.h" #include "msgq/visionipc/visionipc.h" #include "common/queue.h" -#include "system/camerad/cameras/camera_common.h" #include "system/loggerd/loggerd.h" class VideoEncoder { diff --git a/system/loggerd/encoderd.cc b/system/loggerd/encoderd.cc index 1b45df6827..4186e13ef1 100644 --- a/system/loggerd/encoderd.cc +++ b/system/loggerd/encoderd.cc @@ -18,12 +18,12 @@ struct EncoderdState { // Sync logic for startup std::atomic encoders_ready = 0; std::atomic start_frame_id = 0; - bool camera_ready[WideRoadCam + 1] = {}; - bool camera_synced[WideRoadCam + 1] = {}; + bool camera_ready[VISION_STREAM_WIDE_ROAD + 1] = {}; + bool camera_synced[VISION_STREAM_WIDE_ROAD + 1] = {}; }; // Handle initial encoder syncing by waiting for all encoders to reach the same frame id -bool sync_encoders(EncoderdState *s, CameraType cam_type, uint32_t frame_id) { +bool sync_encoders(EncoderdState *s, VisionStreamType cam_type, uint32_t frame_id) { if (s->camera_synced[cam_type]) return true; if (s->max_waiting > 1 && s->encoders_ready != s->max_waiting) { @@ -85,7 +85,7 @@ void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { } lagging = false; - if (!sync_encoders(s, cam_info.type, extra.frame_id)) { + if (!sync_encoders(s, cam_info.stream_type, extra.frame_id)) { continue; } if (do_exit) break; diff --git a/system/loggerd/loggerd.h b/system/loggerd/loggerd.h index 7c80ba51a2..e8cdadda06 100644 --- a/system/loggerd/loggerd.h +++ b/system/loggerd/loggerd.h @@ -5,7 +5,6 @@ #include "cereal/messaging/messaging.h" #include "cereal/services.h" #include "msgq/visionipc/visionipc_client.h" -#include "system/camerad/cameras/camera_common.h" #include "system/hardware/hw.h" #include "common/params.h" #include "common/swaglog.h" @@ -51,7 +50,6 @@ class LogCameraInfo { public: const char *thread_name; int fps = MAIN_FPS; - CameraType type; VisionStreamType stream_type; std::vector encoder_infos; }; @@ -112,42 +110,36 @@ const EncoderInfo qcam_encoder_info = { const LogCameraInfo road_camera_info{ .thread_name = "road_cam_encoder", - .type = RoadCam, .stream_type = VISION_STREAM_ROAD, .encoder_infos = {main_road_encoder_info, qcam_encoder_info} }; const LogCameraInfo wide_road_camera_info{ .thread_name = "wide_road_cam_encoder", - .type = WideRoadCam, .stream_type = VISION_STREAM_WIDE_ROAD, .encoder_infos = {main_wide_road_encoder_info} }; const LogCameraInfo driver_camera_info{ .thread_name = "driver_cam_encoder", - .type = DriverCam, .stream_type = VISION_STREAM_DRIVER, .encoder_infos = {main_driver_encoder_info} }; const LogCameraInfo stream_road_camera_info{ .thread_name = "road_cam_encoder", - .type = RoadCam, .stream_type = VISION_STREAM_ROAD, .encoder_infos = {stream_road_encoder_info} }; const LogCameraInfo stream_wide_road_camera_info{ .thread_name = "wide_road_cam_encoder", - .type = WideRoadCam, .stream_type = VISION_STREAM_WIDE_ROAD, .encoder_infos = {stream_wide_road_encoder_info} }; const LogCameraInfo stream_driver_camera_info{ .thread_name = "driver_cam_encoder", - .type = DriverCam, .stream_type = VISION_STREAM_DRIVER, .encoder_infos = {stream_driver_encoder_info} }; diff --git a/tools/replay/framereader.h b/tools/replay/framereader.h index 7a4d024aa2..03ea5be8b2 100644 --- a/tools/replay/framereader.h +++ b/tools/replay/framereader.h @@ -4,8 +4,8 @@ #include #include "msgq/visionipc/visionbuf.h" -#include "system/camerad/cameras/camera_common.h" #include "tools/replay/filereader.h" +#include "tools/replay/util.h" extern "C" { #include diff --git a/tools/replay/logreader.h b/tools/replay/logreader.h index ab35954db6..f8d60ffadd 100644 --- a/tools/replay/logreader.h +++ b/tools/replay/logreader.h @@ -4,7 +4,6 @@ #include #include "cereal/gen/cpp/log.capnp.h" -#include "system/camerad/cameras/camera_common.h" #include "tools/replay/util.h" const CameraType ALL_CAMERAS[] = {RoadCam, DriverCam, WideRoadCam}; diff --git a/tools/replay/util.h b/tools/replay/util.h index c3b016c391..d6c26a3471 100644 --- a/tools/replay/util.h +++ b/tools/replay/util.h @@ -4,6 +4,13 @@ #include #include #include +#include "cereal/messaging/messaging.h" + +enum CameraType { + RoadCam = 0, + DriverCam, + WideRoadCam +}; enum class ReplyMsgType { Info, From 78db1369146d98e71933633eff154b27a2b21864 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 20 Sep 2024 01:41:51 +0800 Subject: [PATCH 091/214] camerad: remove libyuv dependency (#33593) remove libyuv --- system/camerad/SConscript | 2 +- system/camerad/cameras/camera_common.cc | 3 +-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/system/camerad/SConscript b/system/camerad/SConscript index 4e2eddeb42..f5cbc15748 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -1,6 +1,6 @@ Import('env', 'arch', 'messaging', 'common', 'gpucommon', 'visionipc') -libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', messaging, visionipc, gpucommon, 'atomic'] +libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', messaging, visionipc, gpucommon, 'atomic'] camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc', 'cameras/spectra.cc', 'sensors/ar0231.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc']) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index a4ac385440..dcb5a70987 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -3,7 +3,6 @@ #include #include -#include "third_party/libyuv/include/libyuv.h" #include #include "common/clutil.h" @@ -153,7 +152,7 @@ static kj::Array yuv420_to_jpeg(const CameraBuf *b, int thumbnail_w int in_stride = b->cur_yuv_buf->stride; // make the buffer big enough. jpeg_write_raw_data requires 16-pixels aligned height to be used. - std::unique_ptr buf(new uint8_t[(thumbnail_width * ((thumbnail_height + 15) & ~15) * 3) / 2]); + std::unique_ptr buf(new uint8_t[(thumbnail_width * ((thumbnail_height + 15) & ~15) * 3) / 2]); uint8_t *y_plane = buf.get(); uint8_t *u_plane = y_plane + thumbnail_width * thumbnail_height; uint8_t *v_plane = u_plane + (thumbnail_width * thumbnail_height) / 4; From c95f0f039f0c7163ebf85904b2ba16477038b0f9 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 20 Sep 2024 01:45:57 +0800 Subject: [PATCH 092/214] camerad: move debugging parameters from camera_common.h to camera_qcom2.cc (#33589) move debugging parameters Co-authored-by: Adeeb Shihadeh --- system/camerad/cameras/camera_common.h | 5 ----- system/camerad/cameras/camera_qcom2.cc | 5 +++++ 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 0536ecc7f3..f745300e1c 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -11,11 +11,6 @@ const int YUV_BUFFER_COUNT = 20; -// for debugging -const bool env_debug_frames = getenv("DEBUG_FRAMES") != NULL; -const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != NULL; -const bool env_ctrl_exp_from_params = getenv("CTRL_EXP_FROM_PARAMS") != NULL; - typedef struct FrameMetadata { uint32_t frame_id; uint32_t request_id; diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 3b2b9db330..9785ceef9b 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -25,6 +25,11 @@ ExitHandler do_exit; +// for debugging +const bool env_debug_frames = getenv("DEBUG_FRAMES") != nullptr; +const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != nullptr; +const bool env_ctrl_exp_from_params = getenv("CTRL_EXP_FROM_PARAMS") != nullptr; + // high level camera state class CameraState : public SpectraCamera { From b852aba670d67271c455fcc33d8a8b5b90256429 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 20 Sep 2024 01:58:06 +0800 Subject: [PATCH 093/214] camerad: fix POLLPRI event check in poll loop (#33591) fix event check in poll loop to validate POLLPRI --- system/camerad/cameras/camera_qcom2.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 9785ceef9b..1b717754d7 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -374,7 +374,7 @@ void camerad_thread() { break; } - if (!fds[0].revents) continue; + if (!(fds[0].revents & POLLPRI)) continue; struct v4l2_event ev = {0}; ret = HANDLE_EINTR(ioctl(fds[0].fd, VIDIOC_DQEVENT, &ev)); From 943aa616b376f3c8f1f9361ecf0e591a0533850b Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 20 Sep 2024 01:58:49 +0800 Subject: [PATCH 094/214] camerad: add helper function get_gain_factor (#33594) --- system/camerad/cameras/camera_qcom2.cc | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 1b717754d7..58ec47b040 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -60,20 +60,23 @@ public: void set_exposure_rect(); void run(); + float get_gain_factor() const { + return (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight); + } + void init() { fl_pix = cc.focal_len / sensor->pixel_size_mm; set_exposure_rect(); dc_gain_weight = sensor->dc_gain_min_weight; gain_idx = sensor->analog_gain_rec_idx; - cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight) * sensor->sensor_analog_gains[gain_idx] * exposure_time; + cur_ev[0] = cur_ev[1] = cur_ev[2] = get_gain_factor() * sensor->sensor_analog_gains[gain_idx] * exposure_time; }; // TODO: this should move to SpectraCamera void handle_camera_event(void *evdat); }; - void CameraState::handle_camera_event(void *evdat) { if (!enabled) return; struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)evdat; @@ -113,7 +116,7 @@ void CameraState::handle_camera_event(void *evdat) { meta_data.request_id = real_id; meta_data.timestamp_sof = timestamp; exp_lock.lock(); - meta_data.gain = analog_gain_frac * (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight); + meta_data.gain = analog_gain_frac * get_gain_factor(); meta_data.high_conversion_gain = dc_gain_enabled; meta_data.integ_lines = exposure_time; meta_data.measured_grey_fraction = measured_grey_fraction; @@ -233,7 +236,7 @@ void CameraState::set_camera_exposure(float grey_frac) { // Simple brute force optimizer to choose sensor parameters // to reach desired EV for (int g = std::max((int)sensor->analog_gain_min_idx, gain_idx - 1); g <= std::min((int)sensor->analog_gain_max_idx, gain_idx + 1); g++) { - float gain = sensor->sensor_analog_gains[g] * (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight); + float gain = sensor->sensor_analog_gains[g] * get_gain_factor(); // Compute optimal time for given gain int t = std::clamp(int(std::round(desired_ev / gain)), sensor->exposure_time_min, sensor->exposure_time_max); @@ -257,7 +260,7 @@ void CameraState::set_camera_exposure(float grey_frac) { exposure_time = new_exp_t; dc_gain_enabled = enable_dc_gain; - float gain = analog_gain_frac * (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight); + float gain = analog_gain_frac * get_gain_factor(); cur_ev[buf.cur_frame_data.frame_id % 3] = exposure_time * gain; exp_lock.unlock(); From eea06b4c3eda8c7d1dfadcc244954d9919402ee1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 19 Sep 2024 11:22:46 -0700 Subject: [PATCH 095/214] camerad: camera_util is spectra (#33597) * camerad: camera_util is spectra * lil more * mv that * fix build * runs on device --------- Co-authored-by: Comma Device --- system/camerad/SConscript | 4 +- system/camerad/cameras/camera_util.cc | 140 -------------------------- system/camerad/cameras/camera_util.h | 39 ------- system/camerad/cameras/spectra.cc | 138 +++++++++++++++++++++++-- system/camerad/cameras/spectra.h | 31 +++++- tools/replay/camera.cc | 4 +- 6 files changed, 166 insertions(+), 190 deletions(-) delete mode 100644 system/camerad/cameras/camera_util.cc delete mode 100644 system/camerad/cameras/camera_util.h diff --git a/system/camerad/SConscript b/system/camerad/SConscript index f5cbc15748..8bafd83f08 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -2,8 +2,8 @@ Import('env', 'arch', 'messaging', 'common', 'gpucommon', 'visionipc') libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', messaging, visionipc, gpucommon, 'atomic'] -camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc', - 'cameras/spectra.cc', 'sensors/ar0231.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc']) +camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/spectra.cc', + 'sensors/ar0231.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc']) env.Program('camerad', ['main.cc', camera_obj], LIBS=libs) if GetOption("extras") and arch == "x86_64": diff --git a/system/camerad/cameras/camera_util.cc b/system/camerad/cameras/camera_util.cc deleted file mode 100644 index 4d78556800..0000000000 --- a/system/camerad/cameras/camera_util.cc +++ /dev/null @@ -1,140 +0,0 @@ -#include "system/camerad/cameras/camera_util.h" - -#include - -#include - -#include -#include - -#include "common/swaglog.h" -#include "common/util.h" - -// For debugging: -// echo "4294967295" > /sys/module/cam_debug_util/parameters/debug_mdl - -// ************** low level camera helpers **************** -int do_cam_control(int fd, int op_code, void *handle, int size) { - struct cam_control camcontrol = {0}; - camcontrol.op_code = op_code; - camcontrol.handle = (uint64_t)handle; - if (size == 0) { - camcontrol.size = 8; - camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE; - } else { - camcontrol.size = size; - camcontrol.handle_type = CAM_HANDLE_USER_POINTER; - } - - int ret = HANDLE_EINTR(ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol)); - if (ret == -1) { - LOGE("VIDIOC_CAM_CONTROL error: op_code %d - errno %d", op_code, errno); - } - return ret; -} - -std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources) { - struct cam_acquire_dev_cmd cmd = { - .session_handle = session_handle, - .handle_type = CAM_HANDLE_USER_POINTER, - .num_resources = (uint32_t)(data ? num_resources : 0), - .resource_hdl = (uint64_t)data, - }; - int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd)); - return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt; -} - -int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle) { - struct cam_config_dev_cmd cmd = { - .session_handle = session_handle, - .dev_handle = dev_handle, - .packet_handle = packet_handle, - }; - return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd)); -} - -int device_control(int fd, int op_code, int session_handle, int dev_handle) { - // start stop and release are all the same - struct cam_start_stop_dev_cmd cmd { .session_handle = session_handle, .dev_handle = dev_handle }; - return do_cam_control(fd, op_code, &cmd, sizeof(cmd)); -} - -void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align, int flags, int mmu_hdl, int mmu_hdl2) { - struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0}; - mem_mgr_alloc_cmd.len = len; - mem_mgr_alloc_cmd.align = align; - mem_mgr_alloc_cmd.flags = flags; - mem_mgr_alloc_cmd.num_hdl = 0; - if (mmu_hdl != 0) { - mem_mgr_alloc_cmd.mmu_hdls[0] = mmu_hdl; - mem_mgr_alloc_cmd.num_hdl++; - } - if (mmu_hdl2 != 0) { - mem_mgr_alloc_cmd.mmu_hdls[1] = mmu_hdl2; - mem_mgr_alloc_cmd.num_hdl++; - } - - do_cam_control(video0_fd, CAM_REQ_MGR_ALLOC_BUF, &mem_mgr_alloc_cmd, sizeof(mem_mgr_alloc_cmd)); - *handle = mem_mgr_alloc_cmd.out.buf_handle; - - void *ptr = NULL; - if (mem_mgr_alloc_cmd.out.fd > 0) { - ptr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, mem_mgr_alloc_cmd.out.fd, 0); - assert(ptr != MAP_FAILED); - } - - // LOGD("allocated: %x %d %llx mapped %p", mem_mgr_alloc_cmd.out.buf_handle, mem_mgr_alloc_cmd.out.fd, mem_mgr_alloc_cmd.out.vaddr, ptr); - - return ptr; -} - -void release(int video0_fd, uint32_t handle) { - struct cam_mem_mgr_release_cmd mem_mgr_release_cmd = {0}; - mem_mgr_release_cmd.buf_handle = handle; - - int ret = do_cam_control(video0_fd, CAM_REQ_MGR_RELEASE_BUF, &mem_mgr_release_cmd, sizeof(mem_mgr_release_cmd)); - assert(ret == 0); -} - -// *** MemoryManager *** - -void *MemoryManager::alloc_buf(int size, uint32_t *handle) { - lock.lock(); - void *ptr; - if (!cached_allocations[size].empty()) { - ptr = cached_allocations[size].front(); - cached_allocations[size].pop(); - *handle = handle_lookup[ptr]; - } else { - ptr = alloc_w_mmu_hdl(video0_fd, size, handle); - handle_lookup[ptr] = *handle; - size_lookup[ptr] = size; - } - lock.unlock(); - memset(ptr, 0, size); - return ptr; -} - -void MemoryManager::free(void *ptr) { - lock.lock(); - cached_allocations[size_lookup[ptr]].push(ptr); - lock.unlock(); -} - -MemoryManager::~MemoryManager() { - for (auto& x : cached_allocations) { - while (!x.second.empty()) { - void *ptr = x.second.front(); - x.second.pop(); - LOGD("freeing cached allocation %p with size %d", ptr, size_lookup[ptr]); - munmap(ptr, size_lookup[ptr]); - - // release fd - close(handle_lookup[ptr] >> 16); - release(video0_fd, handle_lookup[ptr]); - - handle_lookup.erase(ptr); - size_lookup.erase(ptr); - } - } -} diff --git a/system/camerad/cameras/camera_util.h b/system/camerad/cameras/camera_util.h deleted file mode 100644 index a2e7bfb434..0000000000 --- a/system/camerad/cameras/camera_util.h +++ /dev/null @@ -1,39 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include - -std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1); -int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle); -int device_control(int fd, int op_code, int session_handle, int dev_handle); -int do_cam_control(int fd, int op_code, void *handle, int size); -void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, - int mmu_hdl = 0, int mmu_hdl2 = 0); -void release(int video0_fd, uint32_t handle); - -class MemoryManager { -public: - void init(int _video0_fd) { video0_fd = _video0_fd; } - ~MemoryManager(); - - template - auto alloc(int len, uint32_t *handle) { - return std::unique_ptr>((T*)alloc_buf(len, handle), [this](void *ptr) { this->free(ptr); }); - } - -private: - void *alloc_buf(int len, uint32_t *handle); - void free(void *ptr); - - std::mutex lock; - std::map handle_lookup; - std::map size_lookup; - std::map > cached_allocations; - int video0_fd; -}; diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index 609d77bf0f..42aa32c8b0 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -1,9 +1,7 @@ -#include - +#include #include -#include -#include -#include +#include +#include #include "media/cam_defs.h" #include "media/cam_isp.h" @@ -14,11 +12,94 @@ #include "common/util.h" #include "common/swaglog.h" - #include "system/camerad/cameras/spectra.h" +// For debugging: +// echo "4294967295" > /sys/module/cam_debug_util/parameters/debug_mdl + +// ************** low level camera helpers **************** + +int do_cam_control(int fd, int op_code, void *handle, int size) { + struct cam_control camcontrol = {0}; + camcontrol.op_code = op_code; + camcontrol.handle = (uint64_t)handle; + if (size == 0) { + camcontrol.size = 8; + camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE; + } else { + camcontrol.size = size; + camcontrol.handle_type = CAM_HANDLE_USER_POINTER; + } + + int ret = HANDLE_EINTR(ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol)); + if (ret == -1) { + LOGE("VIDIOC_CAM_CONTROL error: op_code %d - errno %d", op_code, errno); + } + return ret; +} + +std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources) { + struct cam_acquire_dev_cmd cmd = { + .session_handle = session_handle, + .handle_type = CAM_HANDLE_USER_POINTER, + .num_resources = (uint32_t)(data ? num_resources : 0), + .resource_hdl = (uint64_t)data, + }; + int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd)); + return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt; +} + +int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle) { + struct cam_config_dev_cmd cmd = { + .session_handle = session_handle, + .dev_handle = dev_handle, + .packet_handle = packet_handle, + }; + return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd)); +} + +int device_control(int fd, int op_code, int session_handle, int dev_handle) { + // start stop and release are all the same + struct cam_start_stop_dev_cmd cmd { .session_handle = session_handle, .dev_handle = dev_handle }; + return do_cam_control(fd, op_code, &cmd, sizeof(cmd)); +} + +void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align, int flags, int mmu_hdl, int mmu_hdl2) { + struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0}; + mem_mgr_alloc_cmd.len = len; + mem_mgr_alloc_cmd.align = align; + mem_mgr_alloc_cmd.flags = flags; + mem_mgr_alloc_cmd.num_hdl = 0; + if (mmu_hdl != 0) { + mem_mgr_alloc_cmd.mmu_hdls[0] = mmu_hdl; + mem_mgr_alloc_cmd.num_hdl++; + } + if (mmu_hdl2 != 0) { + mem_mgr_alloc_cmd.mmu_hdls[1] = mmu_hdl2; + mem_mgr_alloc_cmd.num_hdl++; + } + + do_cam_control(video0_fd, CAM_REQ_MGR_ALLOC_BUF, &mem_mgr_alloc_cmd, sizeof(mem_mgr_alloc_cmd)); + *handle = mem_mgr_alloc_cmd.out.buf_handle; + + void *ptr = NULL; + if (mem_mgr_alloc_cmd.out.fd > 0) { + ptr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, mem_mgr_alloc_cmd.out.fd, 0); + assert(ptr != MAP_FAILED); + } + + // LOGD("allocated: %x %d %llx mapped %p", mem_mgr_alloc_cmd.out.buf_handle, mem_mgr_alloc_cmd.out.fd, mem_mgr_alloc_cmd.out.vaddr, ptr); + + return ptr; +} + +void release(int video0_fd, uint32_t handle) { + struct cam_mem_mgr_release_cmd mem_mgr_release_cmd = {0}; + mem_mgr_release_cmd.buf_handle = handle; -// *** helpers *** + int ret = do_cam_control(video0_fd, CAM_REQ_MGR_RELEASE_BUF, &mem_mgr_release_cmd, sizeof(mem_mgr_release_cmd)); + assert(ret == 0); +} static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) { cam_cmd_unconditional_wait *unconditional_wait = (cam_cmd_unconditional_wait *)((char *)power + (sizeof(struct cam_cmd_power) + (power->count - 1) * sizeof(struct cam_power_settings))); @@ -28,6 +109,49 @@ static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) { return (struct cam_cmd_power *)(unconditional_wait + 1); } +// *** MemoryManager *** + +void *MemoryManager::alloc_buf(int size, uint32_t *handle) { + lock.lock(); + void *ptr; + if (!cached_allocations[size].empty()) { + ptr = cached_allocations[size].front(); + cached_allocations[size].pop(); + *handle = handle_lookup[ptr]; + } else { + ptr = alloc_w_mmu_hdl(video0_fd, size, handle); + handle_lookup[ptr] = *handle; + size_lookup[ptr] = size; + } + lock.unlock(); + memset(ptr, 0, size); + return ptr; +} + +void MemoryManager::free(void *ptr) { + lock.lock(); + cached_allocations[size_lookup[ptr]].push(ptr); + lock.unlock(); +} + +MemoryManager::~MemoryManager() { + for (auto& x : cached_allocations) { + while (!x.second.empty()) { + void *ptr = x.second.front(); + x.second.pop(); + LOGD("freeing cached allocation %p with size %d", ptr, size_lookup[ptr]); + munmap(ptr, size_lookup[ptr]); + + // release fd + close(handle_lookup[ptr] >> 16); + release(video0_fd, handle_lookup[ptr]); + + handle_lookup.erase(ptr); + size_lookup.erase(ptr); + } + } +} + // *** SpectraMaster *** void SpectraMaster::init() { diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h index baa5cbc32f..5c84d527dd 100644 --- a/system/camerad/cameras/spectra.h +++ b/system/camerad/cameras/spectra.h @@ -4,10 +4,10 @@ #include #include "media/cam_isp_ife.h" +#include "media/cam_req_mgr.h" #include "common/util.h" #include "system/camerad/cameras/tici.h" -#include "system/camerad/cameras/camera_util.h" #include "system/camerad/cameras/camera_common.h" #include "system/camerad/sensors/sensor.h" @@ -19,6 +19,35 @@ const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py // https://github.com/commaai/agnos-kernel-sdm845 +std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1); +int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle); +int device_control(int fd, int op_code, int session_handle, int dev_handle); +int do_cam_control(int fd, int op_code, void *handle, int size); +void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, + int mmu_hdl = 0, int mmu_hdl2 = 0); +void release(int video0_fd, uint32_t handle); + +class MemoryManager { +public: + void init(int _video0_fd) { video0_fd = _video0_fd; } + ~MemoryManager(); + + template + auto alloc(int len, uint32_t *handle) { + return std::unique_ptr>((T*)alloc_buf(len, handle), [this](void *ptr) { this->free(ptr); }); + } + +private: + void *alloc_buf(int len, uint32_t *handle); + void free(void *ptr); + + std::mutex lock; + std::map handle_lookup; + std::map size_lookup; + std::map > cached_allocations; + int video0_fd; +}; + class SpectraMaster { public: void init(); diff --git a/tools/replay/camera.cc b/tools/replay/camera.cc index ded966da6d..914c18e15f 100644 --- a/tools/replay/camera.cc +++ b/tools/replay/camera.cc @@ -1,7 +1,9 @@ #include "tools/replay/camera.h" -#include #include +#include + +#include #include "third_party/linux/include/msm_media_info.h" #include "tools/replay/util.h" From 34f5ba46b314cb31a15af38662393973a18b9e34 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 20 Sep 2024 02:34:37 +0800 Subject: [PATCH 096/214] camerad: move `handle_camera_event` to SpectraCamera class (#33595) move handle event Co-authored-by: Comma Device --- system/camerad/cameras/camera_common.cc | 4 +- system/camerad/cameras/camera_common.h | 9 +-- system/camerad/cameras/camera_qcom2.cc | 80 ++----------------------- system/camerad/cameras/spectra.cc | 49 +++++++++++++++ system/camerad/cameras/spectra.h | 1 + 5 files changed, 59 insertions(+), 84 deletions(-) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index dcb5a70987..769557d70b 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -102,7 +102,7 @@ CameraBuf::~CameraBuf() { if (imgproc) delete imgproc; } -bool CameraBuf::acquire() { +bool CameraBuf::acquire(int expo_time) { if (!safe_queue.try_pop(cur_buf_idx, 50)) return false; if (camera_bufs_metadata[cur_buf_idx].frame_id == -1) { @@ -115,7 +115,7 @@ bool CameraBuf::acquire() { cur_camera_buf = &camera_bufs[cur_buf_idx]; double start_time = millis_since_boot(); - imgproc->runKernel(camera_bufs[cur_buf_idx].buf_cl, cur_yuv_buf->buf_cl, out_img_width, out_img_height, cur_frame_data.integ_lines); + imgproc->runKernel(camera_bufs[cur_buf_idx].buf_cl, cur_yuv_buf->buf_cl, out_img_width, out_img_height, expo_time); cur_frame_data.processing_time = (millis_since_boot() - start_time) / 1000.0; VisionIpcBufExtra extra = { diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index f745300e1c..6140d24b1c 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -19,13 +19,6 @@ typedef struct FrameMetadata { uint64_t timestamp_sof; uint64_t timestamp_eof; - // Exposure - unsigned int integ_lines; - bool high_conversion_gain; - float gain; - float measured_grey_fraction; - float target_grey_fraction; - float processing_time; } FrameMetadata; @@ -53,7 +46,7 @@ public: CameraBuf() = default; ~CameraBuf(); void init(cl_device_id device_id, cl_context context, SpectraCamera *cam, VisionIpcServer * v, int frame_cnt, VisionStreamType type); - bool acquire(); + bool acquire(int expo_time); void queue(size_t buf_idx); }; diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 58ec47b040..3c27ccbadd 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -34,8 +34,6 @@ const bool env_ctrl_exp_from_params = getenv("CTRL_EXP_FROM_PARAMS") != nullptr; // high level camera state class CameraState : public SpectraCamera { public: - std::mutex exp_lock; - int exposure_time = 5; bool dc_gain_enabled = false; int dc_gain_weight = 0; @@ -72,69 +70,8 @@ public: gain_idx = sensor->analog_gain_rec_idx; cur_ev[0] = cur_ev[1] = cur_ev[2] = get_gain_factor() * sensor->sensor_analog_gains[gain_idx] * exposure_time; }; - - // TODO: this should move to SpectraCamera - void handle_camera_event(void *evdat); }; -void CameraState::handle_camera_event(void *evdat) { - if (!enabled) return; - struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)evdat; - assert(event_data->session_hdl == session_handle); - assert(event_data->u.frame_msg.link_hdl == link_handle); - - uint64_t timestamp = event_data->u.frame_msg.timestamp; - uint64_t main_id = event_data->u.frame_msg.frame_id; - uint64_t real_id = event_data->u.frame_msg.request_id; - - if (real_id != 0) { // next ready - if (real_id == 1) {idx_offset = main_id;} - int buf_idx = (real_id - 1) % FRAME_BUF_COUNT; - - // check for skipped frames - if (main_id > frame_id_last + 1 && !skipped) { - LOGE("camera %d realign", cc.camera_num); - clear_req_queue(); - enqueue_req_multi(real_id + 1, FRAME_BUF_COUNT - 1, 0); - skipped = true; - } else if (main_id == frame_id_last + 1) { - skipped = false; - } - - // check for dropped requests - if (real_id > request_id_last + 1) { - LOGE("camera %d dropped requests %ld %ld", cc.camera_num, real_id, request_id_last); - enqueue_req_multi(request_id_last + 1 + FRAME_BUF_COUNT, real_id - (request_id_last + 1), 0); - } - - // metas - frame_id_last = main_id; - request_id_last = real_id; - - auto &meta_data = buf.camera_bufs_metadata[buf_idx]; - meta_data.frame_id = main_id - idx_offset; - meta_data.request_id = real_id; - meta_data.timestamp_sof = timestamp; - exp_lock.lock(); - meta_data.gain = analog_gain_frac * get_gain_factor(); - meta_data.high_conversion_gain = dc_gain_enabled; - meta_data.integ_lines = exposure_time; - meta_data.measured_grey_fraction = measured_grey_fraction; - meta_data.target_grey_fraction = target_grey_fraction; - exp_lock.unlock(); - - // dispatch - enqueue_req_multi(real_id + FRAME_BUF_COUNT, 1, 1); - } else { // not ready - if (main_id > frame_id_last + 10) { - LOGE("camera %d reset after half second of no response", cc.camera_num); - clear_req_queue(); - enqueue_req_multi(request_id_last + 1, FRAME_BUF_COUNT, 0); - frame_id_last = main_id; - skipped = true; - } - } -} void CameraState::set_exposure_rect() { // set areas for each camera, shouldn't be changed @@ -250,8 +187,6 @@ void CameraState::set_camera_exposure(float grey_frac) { } } - exp_lock.lock(); - measured_grey_fraction = grey_frac; target_grey_fraction = target_grey; @@ -263,8 +198,6 @@ void CameraState::set_camera_exposure(float grey_frac) { float gain = analog_gain_frac * get_gain_factor(); cur_ev[buf.cur_frame_data.frame_id % 3] = exposure_time * gain; - exp_lock.unlock(); - // Processing a frame takes right about 50ms, so we need to wait a few ms // so we don't send i2c commands around the frame start. int ms = (nanos_since_boot() - buf.cur_frame_data.timestamp_sof) / 1000000; @@ -286,7 +219,7 @@ void CameraState::run() { for (uint32_t cnt = 0; !do_exit; ++cnt) { // Acquire the buffer; continue if acquisition fails - if (!buf.acquire()) continue; + if (!buf.acquire(exposure_time)) continue; MessageBuilder msg; auto framed = (msg.initEvent().*cc.init_camera_state)(); @@ -294,11 +227,11 @@ void CameraState::run() { framed.setRequestId(buf.cur_frame_data.request_id); framed.setTimestampEof(buf.cur_frame_data.timestamp_eof); framed.setTimestampSof(buf.cur_frame_data.timestamp_sof); - framed.setIntegLines(buf.cur_frame_data.integ_lines); - framed.setGain(buf.cur_frame_data.gain); - framed.setHighConversionGain(buf.cur_frame_data.high_conversion_gain); - framed.setMeasuredGreyFraction(buf.cur_frame_data.measured_grey_fraction); - framed.setTargetGreyFraction(buf.cur_frame_data.target_grey_fraction); + framed.setIntegLines(exposure_time); + framed.setGain(analog_gain_frac * get_gain_factor()); + framed.setHighConversionGain(dc_gain_enabled); + framed.setMeasuredGreyFraction(measured_grey_fraction); + framed.setTargetGreyFraction(target_grey_fraction); framed.setProcessingTime(buf.cur_frame_data.processing_time); const float ev = cur_ev[buf.cur_frame_data.frame_id % 3]; @@ -328,7 +261,6 @@ void camerad_thread() { TODO: future cleanups - centralize enabled handling - open/init/etc mess - - no ISP stuff in this file */ cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index 42aa32c8b0..603dfe032b 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -817,3 +817,52 @@ void SpectraCamera::camera_close() { ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_DESTROY_SESSION, &session_info, sizeof(session_info)); LOGD("destroyed session %d: %d", cc.camera_num, ret); } + +void SpectraCamera::handle_camera_event(const cam_req_mgr_message *event_data) { + if (!enabled) return; + + uint64_t timestamp = event_data->u.frame_msg.timestamp; + uint64_t main_id = event_data->u.frame_msg.frame_id; + uint64_t real_id = event_data->u.frame_msg.request_id; + + if (real_id != 0) { // next ready + if (real_id == 1) {idx_offset = main_id;} + int buf_idx = (real_id - 1) % FRAME_BUF_COUNT; + + // check for skipped frames + if (main_id > frame_id_last + 1 && !skipped) { + LOGE("camera %d realign", cc.camera_num); + clear_req_queue(); + enqueue_req_multi(real_id + 1, FRAME_BUF_COUNT - 1, 0); + skipped = true; + } else if (main_id == frame_id_last + 1) { + skipped = false; + } + + // check for dropped requests + if (real_id > request_id_last + 1) { + LOGE("camera %d dropped requests %ld %ld", cc.camera_num, real_id, request_id_last); + enqueue_req_multi(request_id_last + 1 + FRAME_BUF_COUNT, real_id - (request_id_last + 1), 0); + } + + // metas + frame_id_last = main_id; + request_id_last = real_id; + + auto &meta_data = buf.camera_bufs_metadata[buf_idx]; + meta_data.frame_id = main_id - idx_offset; + meta_data.request_id = real_id; + meta_data.timestamp_sof = timestamp; + + // dispatch + enqueue_req_multi(real_id + FRAME_BUF_COUNT, 1, 1); + } else { // not ready + if (main_id > frame_id_last + 10) { + LOGE("camera %d reset after half second of no response", cc.camera_num); + clear_req_queue(); + enqueue_req_multi(request_id_last + 1, FRAME_BUF_COUNT, 0); + frame_id_last = main_id; + skipped = true; + } + } +} diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h index 5c84d527dd..9d412481f1 100644 --- a/system/camerad/cameras/spectra.h +++ b/system/camerad/cameras/spectra.h @@ -65,6 +65,7 @@ public: ~SpectraCamera(); void camera_open(); + void handle_camera_event(const cam_req_mgr_message *event_data); void camera_close(); void camera_map_bufs(); void camera_init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx); From 7a11d0180b68fb95e9bd7416e4caf1c036bafed7 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 20 Sep 2024 04:09:41 +0800 Subject: [PATCH 097/214] locationd: improve circular buffer handling with np.roll (#33470) improve circular buffer handling --- selfdrive/locationd/locationd.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py index 4cde1e5ad4..7f5541b8c2 100755 --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -49,7 +49,7 @@ class LocationEstimator: self.debug = debug - self.posenet_stds = [POSENET_STD_INITIAL_VALUE] * (POSENET_STD_HIST_HALF * 2) + self.posenet_stds = np.array([POSENET_STD_INITIAL_VALUE] * (POSENET_STD_HIST_HALF * 2)) self.car_speed = 0.0 self.camodo_yawrate_distribution = np.array([0.0, 10.0]) # mean, std self.device_from_calib = np.eye(3) @@ -168,8 +168,8 @@ class LocationEstimator: if np.linalg.norm(rot_calib_std) > 10 * ROTATION_SANITY_CHECK or np.linalg.norm(trans_calib_std) > 10 * TRANS_SANITY_CHECK: return HandleLogResult.INPUT_INVALID - self.posenet_stds.pop(0) - self.posenet_stds.append(trans_calib_std[0]) + self.posenet_stds = np.roll(self.posenet_stds, -1) + self.posenet_stds[-1] = trans_calib_std[0] # Multiply by N to avoid to high certainty in kalman filter because of temporally correlated noise rot_calib_std *= 10 From 81a0e3716e8caa75eadd2f859b53bdcc7a0ab48a Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 19 Sep 2024 13:30:11 -0700 Subject: [PATCH 098/214] longitudinal report: description is optional --- tools/longitudinal_maneuvers/generate_report.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py index f487225054..712d76d95b 100755 --- a/tools/longitudinal_maneuvers/generate_report.py +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -124,7 +124,7 @@ def report(platform, route, _description, CP, maneuvers): if __name__ == '__main__': parser = argparse.ArgumentParser(description='Generate longitudinal maneuver report from route') parser.add_argument('route', type=str, help='Route name (e.g. 00000000--5f742174be)') - parser.add_argument('description', type=str, default=None) + parser.add_argument('description', type=str, nargs='?') args = parser.parse_args() From 91e342fc58ddef69d14c3f9dffabcdbdc14fb623 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 19 Sep 2024 14:14:22 -0700 Subject: [PATCH 099/214] longitudinal maneuver report: require two frames above target (#33602) require two frames --- tools/longitudinal_maneuvers/generate_report.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py index 712d76d95b..36e2d3eecc 100755 --- a/tools/longitudinal_maneuvers/generate_report.py +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -59,13 +59,18 @@ def report(platform, route, _description, CP, maneuvers): aTarget = longitudinalPlan[0].aTarget target_cross_time = None f.write(f'

Initial aTarget: {aTarget} m/s^2') + + # Localizer is noisy, require two consecutive 20Hz frames above threshold + prev_crossed = False for t, lp in zip(t_livePose, livePose, strict=True): - if (0 < aTarget < lp.accelerationDevice.x) or (0 > aTarget > lp.accelerationDevice.x): + crossed = (0 < aTarget < lp.accelerationDevice.x) or (0 > aTarget > lp.accelerationDevice.x) + if crossed and prev_crossed: f.write(f', crossed in {t:.3f}s') target_cross_time = t if maneuver_valid: target_cross_times[description].append(t) break + prev_crossed = crossed else: f.write(', not crossed') f.write('

') From eaebea0968ed87a276551f1ce8f747f476bf06b5 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 20 Sep 2024 05:16:48 +0800 Subject: [PATCH 100/214] camerad: cleanup includes (#33600) cleanup includes Co-authored-by: Comma Device --- system/camerad/cameras/camera_common.h | 1 - system/camerad/cameras/camera_qcom2.cc | 2 -- system/camerad/cameras/spectra.cc | 1 - system/camerad/cameras/spectra.h | 1 - 4 files changed, 5 deletions(-) diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 6140d24b1c..e0e16e18fc 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -1,6 +1,5 @@ #pragma once -#include #include #include "cereal/messaging/messaging.h" diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 3c27ccbadd..97e4d9b756 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -14,9 +14,7 @@ #include "CL/cl_ext_qcom.h" -#include "media/cam_defs.h" #include "media/cam_sensor_cmn_header.h" -#include "media/cam_sync.h" #include "common/clutil.h" #include "common/params.h" diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index 603dfe032b..c479f10241 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -6,7 +6,6 @@ #include "media/cam_defs.h" #include "media/cam_isp.h" #include "media/cam_isp_ife.h" -#include "media/cam_req_mgr.h" #include "media/cam_sensor_cmn_header.h" #include "media/cam_sync.h" diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h index 9d412481f1..936d8d168e 100644 --- a/system/camerad/cameras/spectra.h +++ b/system/camerad/cameras/spectra.h @@ -3,7 +3,6 @@ #include #include -#include "media/cam_isp_ife.h" #include "media/cam_req_mgr.h" #include "common/util.h" From df9b8f0222ad9e75fa56033552611cb3d3192463 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 19 Sep 2024 16:14:29 -0700 Subject: [PATCH 101/214] camerad: final debayer prep (#33598) * prep part 4? * cleanup * little less magic * reorg * final touches --------- Co-authored-by: Comma Device --- common/util.h | 2 + system/camerad/cameras/spectra.cc | 214 ++++++++++++++++-------------- system/camerad/cameras/spectra.h | 5 +- system/camerad/cameras/tici.h | 2 + 4 files changed, 126 insertions(+), 97 deletions(-) diff --git a/common/util.h b/common/util.h index 186873ac21..7cfa008509 100644 --- a/common/util.h +++ b/common/util.h @@ -37,6 +37,8 @@ const double MS_TO_MPH = MS_TO_KPH * KM_TO_MILE; const double METER_TO_MILE = KM_TO_MILE / 1000.0; const double METER_TO_FOOT = 3.28084; +#define ALIGNED_SIZE(x, align) (((x) + (align)-1) & ~((align)-1)) + namespace util { void set_thread_name(const char* name); diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index c479f10241..58758f9feb 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -395,20 +395,15 @@ int SpectraCamera::sensors_init() { return ret; } -void SpectraCamera::config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset) { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; +void SpectraCamera::config_isp(int io_mem_handle, int fence, int request_id, int buf0_idx) { + printf("cam cmd buf %lu %lu\n", sizeof(struct cam_cmd_buf_desc), sizeof(struct cam_buf_io_cfg)); + int size = sizeof(struct cam_packet) + sizeof(struct cam_cmd_buf_desc)*2; if (io_mem_handle != 0) { size += sizeof(struct cam_buf_io_cfg); } - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 2; - pkt->kmd_cmd_buf_index = 0; - if (io_mem_handle != 0) { - pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf; - pkt->num_io_configs = 1; - } + uint32_t cam_packet_handle = 0; + auto pkt = mm.alloc(size, &cam_packet_handle); if (io_mem_handle != 0) { pkt->header.op_code = 0xf000001; @@ -418,96 +413,124 @@ void SpectraCamera::config_isp(int io_mem_handle, int fence, int request_id, int pkt->header.request_id = 1; } pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - struct cam_buf_io_cfg *io_cfg = (struct cam_buf_io_cfg *)((char*)&pkt->payload + pkt->io_configs_offset); - - // TODO: support MMU - buf_desc[0].size = 65624; - buf_desc[0].length = 0; - buf_desc[0].type = CAM_CMD_BUF_DIRECT; - buf_desc[0].meta_data = 3; - buf_desc[0].mem_handle = buf0_mem_handle; - buf_desc[0].offset = buf0_offset; - - // parsed by cam_isp_packet_generic_blob_handler - struct isp_packet { - uint32_t type_0; - cam_isp_resource_hfr_config resource_hfr; - - uint32_t type_1; - cam_isp_clock_config clock; - uint64_t extra_rdi_hz[3]; - - uint32_t type_2; - cam_isp_bw_config bw; - struct cam_isp_bw_vote extra_rdi_vote[6]; - } __attribute__((packed)) tmp; - memset(&tmp, 0, sizeof(tmp)); - - tmp.type_0 = CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG; - tmp.type_0 |= sizeof(cam_isp_resource_hfr_config) << 8; - static_assert(sizeof(cam_isp_resource_hfr_config) == 0x20); - tmp.resource_hfr = { - .num_ports = 1, // 10 for YUV (but I don't think we need them) - .port_hfr_config[0] = { - .resource_type = CAM_ISP_IFE_OUT_RES_RDI_0, // CAM_ISP_IFE_OUT_RES_FULL for YUV - .subsample_pattern = 1, - .subsample_period = 0, - .framedrop_pattern = 1, - .framedrop_period = 0, - }}; - - tmp.type_1 = CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG; - tmp.type_1 |= (sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) << 8; - static_assert((sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) == 0x38); - tmp.clock = { - .usage_type = 1, // dual mode - .num_rdi = 4, - .left_pix_hz = 404000000, - .right_pix_hz = 404000000, - .rdi_hz[0] = 404000000, - }; - tmp.type_2 = CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG; - tmp.type_2 |= (sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) << 8; - static_assert((sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) == 0xe0); - tmp.bw = { - .usage_type = 1, // dual mode - .num_rdi = 4, - .left_pix_vote = { - .resource_id = 0, - .cam_bw_bps = 450000000, - .ext_bw_bps = 450000000, - }, - .rdi_vote[0] = { - .resource_id = 0, - .cam_bw_bps = 8706200000, - .ext_bw_bps = 8706200000, - }, - }; + // *** kmd cmd buf *** + { + pkt->kmd_cmd_buf_index = 0; + pkt->kmd_cmd_buf_offset = 0; + } - static_assert(offsetof(struct isp_packet, type_2) == 0x60); + // *** patches *** + { + pkt->num_patches = 0; + pkt->patch_offset = 0x0; + } - buf_desc[1].size = sizeof(tmp); - buf_desc[1].offset = io_mem_handle != 0 ? 0x60 : 0; - buf_desc[1].length = buf_desc[1].size - buf_desc[1].offset; - buf_desc[1].type = CAM_CMD_BUF_GENERIC; - buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; - auto buf2 = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); - memcpy(buf2.get(), &tmp, sizeof(tmp)); + // *** cmd buf *** + { + struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; + pkt->num_cmd_buf = 2; + + // *** first command *** + // TODO: support MMU + buf_desc[0].size = buf0_size; + buf_desc[0].length = 0; + buf_desc[0].type = CAM_CMD_BUF_DIRECT; + buf_desc[0].meta_data = 3; + buf_desc[0].mem_handle = buf0_handle; + buf_desc[0].offset = ALIGNED_SIZE(buf0_size, buf0_alignment)*buf0_idx; + + // *** second command *** + // parsed by cam_isp_packet_generic_blob_handler + struct isp_packet { + uint32_t type_0; + cam_isp_resource_hfr_config resource_hfr; + + uint32_t type_1; + cam_isp_clock_config clock; + uint64_t extra_rdi_hz[3]; + + uint32_t type_2; + cam_isp_bw_config bw; + struct cam_isp_bw_vote extra_rdi_vote[6]; + } __attribute__((packed)) tmp; + memset(&tmp, 0, sizeof(tmp)); + + tmp.type_0 = CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG; + tmp.type_0 |= sizeof(cam_isp_resource_hfr_config) << 8; + static_assert(sizeof(cam_isp_resource_hfr_config) == 0x20); + tmp.resource_hfr = { + .num_ports = 1, // 10 for YUV (but I don't think we need them) + .port_hfr_config[0] = { + .resource_type = CAM_ISP_IFE_OUT_RES_RDI_0, // CAM_ISP_IFE_OUT_RES_FULL for YUV + .subsample_pattern = 1, + .subsample_period = 0, + .framedrop_pattern = 1, + .framedrop_period = 0, + }}; + + tmp.type_1 = CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG; + tmp.type_1 |= (sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) << 8; + static_assert((sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) == 0x38); + tmp.clock = { + .usage_type = 1, // dual mode + .num_rdi = 4, + .left_pix_hz = 404000000, + .right_pix_hz = 404000000, + .rdi_hz[0] = 404000000, + }; + tmp.type_2 = CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG; + tmp.type_2 |= (sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) << 8; + static_assert((sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) == 0xe0); + tmp.bw = { + .usage_type = 1, // dual mode + .num_rdi = 4, + .left_pix_vote = { + .resource_id = 0, + .cam_bw_bps = 450000000, + .ext_bw_bps = 450000000, + }, + .rdi_vote[0] = { + .resource_id = 0, + .cam_bw_bps = 8706200000, + .ext_bw_bps = 8706200000, + }, + }; + + static_assert(offsetof(struct isp_packet, type_2) == 0x60); + + buf_desc[1].size = sizeof(tmp); + buf_desc[1].offset = io_mem_handle != 0 ? 0x60 : 0; + buf_desc[1].length = buf_desc[1].size - buf_desc[1].offset; + buf_desc[1].type = CAM_CMD_BUF_GENERIC; + buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; + auto buf2 = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); + memcpy(buf2.get(), &tmp, sizeof(tmp)); + } + + // *** io config *** if (io_mem_handle != 0) { + // configure output frame + pkt->num_io_configs = 1; + pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf; + + struct cam_buf_io_cfg *io_cfg = (struct cam_buf_io_cfg *)((char*)&pkt->payload + pkt->io_configs_offset); + io_cfg[0].offsets[0] = 0; io_cfg[0].mem_handle[0] = io_mem_handle; + io_cfg[0].planes[0] = (struct cam_plane_cfg){ .width = sensor->frame_width, .height = sensor->frame_height + sensor->extra_height, .plane_stride = sensor->frame_stride, .slice_height = sensor->frame_height + sensor->extra_height, - .meta_stride = 0x0, // YUV has meta(stride=0x400, size=0x5000) + + // these are for UBWC, we'll want that eventually + .meta_stride = 0x0, .meta_size = 0x0, .meta_offset = 0x0, - .packer_config = 0x0, // 0xb for YUV - .mode_config = 0x0, // 0x9ef for YUV + .packer_config = 0x0, + .mode_config = 0x0, .tile_config = 0x0, .h_init = 0x0, .v_init = 0x0, @@ -525,9 +548,6 @@ void SpectraCamera::config_isp(int io_mem_handle, int fence, int request_id, int int ret = device_config(m->isp_fd, session_handle, isp_dev_handle, cam_packet_handle); assert(ret == 0); - if (ret != 0) { - LOGE("isp config failed"); - } } void SpectraCamera::enqueue_buffer(int i, bool dp) { @@ -580,7 +600,7 @@ void SpectraCamera::enqueue_buffer(int i, bool dp) { sensors_poke(request_id); // submit request to the ife - config_isp(buf_handle[i], sync_objs[i], request_id, buf0_handle, 65632*(i+1)); + config_isp(buf_handle[i], sync_objs[i], request_id, i); } void SpectraCamera::camera_map_bufs() { @@ -639,11 +659,10 @@ bool SpectraCamera::openSensor() { } void SpectraCamera::configISP() { - // NOTE: to be able to disable road and wide road, we still have to configure the sensor over i2c - // If you don't do this, the strobe GPIO is an output (even in reset it seems!) if (!enabled) return; struct cam_isp_in_port_info in_port_info = { + // ISP input to the CSID .res_type = cc.phy, .lane_type = CAM_ISP_LANE_TYPE_DPHY, .lane_num = 4, @@ -674,6 +693,7 @@ void SpectraCamera::configISP() { .hbi_cnt = 0x0, .custom_csid = 0x0, + // ISP outputs .num_out_res = 0x1, .data[0] = (struct cam_isp_out_port_info){ .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, @@ -696,9 +716,11 @@ void SpectraCamera::configISP() { LOGD("acquire isp dev"); // config ISP - alloc_w_mmu_hdl(m->video0_fd, 984480, (uint32_t*)&buf0_handle, 0x20, CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | - CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, m->device_iommu, m->cdm_iommu); - config_isp(0, 0, 1, buf0_handle, 0); + // TODO: unclear where this 15 comes from + alloc_w_mmu_hdl(m->video0_fd, 15*ALIGNED_SIZE(buf0_size, buf0_alignment), (uint32_t*)&buf0_handle, buf0_alignment, + CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, + m->device_iommu, m->cdm_iommu); + config_isp(0, 0, 1, 0); } void SpectraCamera::configCSIPHY() { diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h index 936d8d168e..a42540cc8f 100644 --- a/system/camerad/cameras/spectra.h +++ b/system/camerad/cameras/spectra.h @@ -68,7 +68,7 @@ public: void camera_close(); void camera_map_bufs(); void camera_init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx); - void config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset); + void config_isp(int io_mem_handle, int fence, int request_id, int buf0_idx); int clear_req_queue(); void enqueue_buffer(int i, bool dp); @@ -101,6 +101,9 @@ public: int32_t link_handle = -1; + const int buf0_size = 65624; // unclear what this is and how it's determined, for internal ISP use? it's just copied from an ioctl dump + const int buf0_alignment = 0x20; + int buf0_handle = 0; int buf_handle[FRAME_BUF_COUNT] = {}; int sync_objs[FRAME_BUF_COUNT] = {}; diff --git a/system/camerad/cameras/tici.h b/system/camerad/cameras/tici.h index 228ff8e284..d0b2aece6d 100644 --- a/system/camerad/cameras/tici.h +++ b/system/camerad/cameras/tici.h @@ -18,6 +18,8 @@ struct CameraConfig { uint32_t phy; }; +// NOTE: to be able to disable road and wide road, we still have to configure the sensor over i2c +// If you don't do this, the strobe GPIO is an output (even in reset it seems!) const CameraConfig WIDE_ROAD_CAMERA_CONFIG = { .camera_num = 0, .stream_type = VISION_STREAM_WIDE_ROAD, From bdb4b87fa59fd82a74a17459cb87fae14f34039b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 19 Sep 2024 16:39:27 -0700 Subject: [PATCH 102/214] rm debug print --- system/camerad/cameras/spectra.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index 58758f9feb..b8b8959f67 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -396,7 +396,6 @@ int SpectraCamera::sensors_init() { } void SpectraCamera::config_isp(int io_mem_handle, int fence, int request_id, int buf0_idx) { - printf("cam cmd buf %lu %lu\n", sizeof(struct cam_cmd_buf_desc), sizeof(struct cam_buf_io_cfg)); int size = sizeof(struct cam_packet) + sizeof(struct cam_cmd_buf_desc)*2; if (io_mem_handle != 0) { size += sizeof(struct cam_buf_io_cfg); From f79aca8e1ef9160a93b2609146b4074b2343f75c Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Thu, 19 Sep 2024 17:42:44 -0700 Subject: [PATCH 103/214] exec DM model with gpu (#33397) * half old-commit-hash: 9f72eca003d4637ca7fe847ebaf925c694fc2e84 * optimed old-commit-hash: 6e36e2a12e09275ec21d1590012a92b05ca52ff5 * thneed old-commit-hash: 419a06c09c0c767d828bcd1e118bc575898c343a * exec old-commit-hash: 0059c27ec11b076a37f65d604ed135ea6541b1a6 * runner old-commit-hash: 34232ada94450ce541eaef546197fa219810a891 * runs but old-commit-hash: 3db37c00b6a64908293b4de8d8b56e80308cd8f2 * it is 01 old-commit-hash: a160d81eb1a7e77abbef959b44f602610f68f665 * np old-commit-hash: c1caff6ba648cc2c0094c71b2ea074f01c3c2dc8 * module url old-commit-hash: 6f4902c4d384263a53e2c1d14d93b5ff864b6a5f * new old-commit-hash: 779ae79b1bc3df6374fb6663ac8592e107a6e504 * ds fast * is this work * corcention * real timing * no reg * interim gather * 0e4a9c7b * fa69be01, and halve * list * cleanup * slighly faster * setprotlt * expected * replay ref * more powar * reluctantly * bump tg * 8 * less * less * bump tg * better than exp * closer * cc * see diff * commits * was right * to 32 cast * remove dlc file * support both --------- Co-authored-by: Comma Device --- .gitattributes | 1 - selfdrive/modeld/SConscript | 4 +++ selfdrive/modeld/dmonitoringmodeld | 10 +++++++ selfdrive/modeld/dmonitoringmodeld.py | 30 +++++++++++-------- .../modeld/models/dmonitoring_model.current | 4 +-- .../modeld/models/dmonitoring_model.onnx | 4 +-- .../modeld/models/dmonitoring_model_q.dlc | 3 -- selfdrive/modeld/runners/onnxmodel.py | 13 +++++--- selfdrive/monitoring/helpers.py | 4 +-- .../process_replay/model_replay_ref_commit | 2 +- selfdrive/test/test_onroad.py | 3 +- system/hardware/tici/tests/test_power_draw.py | 2 +- system/manager/process_config.py | 2 +- tinygrad_repo | 2 +- 14 files changed, 53 insertions(+), 31 deletions(-) create mode 100755 selfdrive/modeld/dmonitoringmodeld delete mode 100644 selfdrive/modeld/models/dmonitoring_model_q.dlc diff --git a/.gitattributes b/.gitattributes index 8781a7371f..eda2505d0e 100644 --- a/.gitattributes +++ b/.gitattributes @@ -2,7 +2,6 @@ # to move existing files into LFS: # git add --renormalize . -*.dlc filter=lfs diff=lfs merge=lfs -text *.onnx filter=lfs diff=lfs merge=lfs -text *.svg filter=lfs diff=lfs merge=lfs -text *.png filter=lfs diff=lfs merge=lfs -text diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index d572915c72..d472998416 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -69,6 +69,10 @@ if arch == "larch64" or GetOption('pc_thneed'): lenv.Command(fn + ".thneed", [fn + ".onnx"] + tinygrad_files, cmd) + fn_dm = File("models/dmonitoring_model").abspath + cmd = f"cd {Dir('#').abspath}/tinygrad_repo && " + ' '.join(tinygrad_opts) + f" python3 openpilot/compile2.py {fn_dm}.onnx {fn_dm}.thneed" + lenv.Command(fn_dm + ".thneed", [fn_dm + ".onnx"] + tinygrad_files, cmd) + thneed_lib = env.SharedLibrary('thneed', thneed_src, LIBS=[gpucommon, common, 'OpenCL', 'dl']) thneedmodel_lib = env.Library('thneedmodel', ['runners/thneedmodel.cc']) lenvCython.Program('runners/thneedmodel_pyx.so', 'runners/thneedmodel_pyx.pyx', LIBS=envCython["LIBS"]+[thneedmodel_lib, thneed_lib, gpucommon, common, 'dl', 'OpenCL']) diff --git a/selfdrive/modeld/dmonitoringmodeld b/selfdrive/modeld/dmonitoringmodeld new file mode 100755 index 0000000000..80157e1751 --- /dev/null +++ b/selfdrive/modeld/dmonitoringmodeld @@ -0,0 +1,10 @@ +#!/usr/bin/env bash + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd "$DIR/../../" + +if [ -f "$DIR/libthneed.so" ]; then + export LD_PRELOAD="$DIR/libthneed.so" +fi + +exec "$DIR/dmonitoringmodeld.py" "$@" diff --git a/selfdrive/modeld/dmonitoringmodeld.py b/selfdrive/modeld/dmonitoringmodeld.py index a388bf089c..d648a4511a 100755 --- a/selfdrive/modeld/dmonitoringmodeld.py +++ b/selfdrive/modeld/dmonitoringmodeld.py @@ -6,6 +6,7 @@ import time import ctypes import numpy as np from pathlib import Path +from setproctitle import setproctitle from cereal import messaging from cereal.messaging import PubMaster, SubMaster @@ -14,16 +15,18 @@ from openpilot.common.swaglog import cloudlog from openpilot.common.params import Params from openpilot.common.realtime import set_realtime_priority from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime -from openpilot.selfdrive.modeld.models.commonmodel_pyx import sigmoid +from openpilot.selfdrive.modeld.models.commonmodel_pyx import sigmoid, CLContext CALIB_LEN = 3 -REG_SCALE = 0.25 MODEL_WIDTH = 1440 MODEL_HEIGHT = 960 -OUTPUT_SIZE = 84 +FEATURE_LEN = 512 +OUTPUT_SIZE = 84 + FEATURE_LEN + +PROCESS_NAME = "selfdrive.modeld.dmonitoringmodeld" SEND_RAW_PRED = os.getenv('SEND_RAW_PRED') MODEL_PATHS = { - ModelRunner.SNPE: Path(__file__).parent / 'models/dmonitoring_model_q.dlc', + ModelRunner.THNEED: Path(__file__).parent / 'models/dmonitoring_model.thneed', ModelRunner.ONNX: Path(__file__).parent / 'models/dmonitoring_model.onnx'} class DriverStateResult(ctypes.Structure): @@ -49,21 +52,22 @@ class DMonitoringModelResult(ctypes.Structure): ("driver_state_lhd", DriverStateResult), ("driver_state_rhd", DriverStateResult), ("poor_vision_prob", ctypes.c_float), - ("wheel_on_right_prob", ctypes.c_float)] + ("wheel_on_right_prob", ctypes.c_float), + ("features", ctypes.c_float*FEATURE_LEN)] class ModelState: inputs: dict[str, np.ndarray] output: np.ndarray model: ModelRunner - def __init__(self): + def __init__(self, cl_ctx): assert ctypes.sizeof(DMonitoringModelResult) == OUTPUT_SIZE * ctypes.sizeof(ctypes.c_float) self.output = np.zeros(OUTPUT_SIZE, dtype=np.float32) self.inputs = { 'input_img': np.zeros(MODEL_HEIGHT * MODEL_WIDTH, dtype=np.uint8), 'calib': np.zeros(CALIB_LEN, dtype=np.float32)} - self.model = ModelRunner(MODEL_PATHS, self.output, Runtime.DSP, True, None) + self.model = ModelRunner(MODEL_PATHS, self.output, Runtime.GPU, False, cl_ctx) self.model.addInput("input_img", None) self.model.addInput("calib", self.inputs['calib']) @@ -76,17 +80,17 @@ class ModelState: input_data = self.inputs['input_img'].reshape(MODEL_HEIGHT, MODEL_WIDTH) input_data[:] = buf_data[v_offset:v_offset+MODEL_HEIGHT, h_offset:h_offset+MODEL_WIDTH] - t1 = time.perf_counter() self.model.setInputBuffer("input_img", self.inputs['input_img'].view(np.float32)) + t1 = time.perf_counter() self.model.execute() t2 = time.perf_counter() return self.output, t2 - t1 def fill_driver_state(msg, ds_result: DriverStateResult): - msg.faceOrientation = [x * REG_SCALE for x in ds_result.face_orientation] + msg.faceOrientation = list(ds_result.face_orientation) msg.faceOrientationStd = [math.exp(x) for x in ds_result.face_orientation_std] - msg.facePosition = [x * REG_SCALE for x in ds_result.face_position[:2]] + msg.facePosition = list(ds_result.face_position[:2]) msg.facePositionStd = [math.exp(x) for x in ds_result.face_position_std[:2]] msg.faceProb = sigmoid(ds_result.face_prob) msg.leftEyeProb = sigmoid(ds_result.left_eye_prob) @@ -115,14 +119,16 @@ def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: def main(): gc.disable() + setproctitle(PROCESS_NAME) set_realtime_priority(1) - model = ModelState() + cl_context = CLContext() + model = ModelState(cl_context) cloudlog.warning("models loaded, dmonitoringmodeld starting") Params().put_bool("DmModelInitialized", True) cloudlog.warning("connecting to driver stream") - vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_DRIVER, True) + vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_DRIVER, True, cl_context) while not vipc_client.connect(False): time.sleep(0.1) assert vipc_client.is_connected() diff --git a/selfdrive/modeld/models/dmonitoring_model.current b/selfdrive/modeld/models/dmonitoring_model.current index f935ab06b3..121871ef2b 100644 --- a/selfdrive/modeld/models/dmonitoring_model.current +++ b/selfdrive/modeld/models/dmonitoring_model.current @@ -1,2 +1,2 @@ -5ec97a39-0095-4cea-adfa-6d72b1966cc1 -26cac7a9757a27c783a365403040a1bd27ccdaea \ No newline at end of file +fa69be01-b430-4504-9d72-7dcb058eb6dd +d9fb22d1c4fa3ca3d201dbc8edf1d0f0918e53e6 diff --git a/selfdrive/modeld/models/dmonitoring_model.onnx b/selfdrive/modeld/models/dmonitoring_model.onnx index dd3a6aba2e..dcc727510e 100644 --- a/selfdrive/modeld/models/dmonitoring_model.onnx +++ b/selfdrive/modeld/models/dmonitoring_model.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3dd3982940d823c4fbb0429b733a0b78b0688d7d67aa76ff7b754a3e2f3d8683 -size 16132780 +oid sha256:50efe6451a3fb3fa04b6bb0e846544533329bd46ecefe9e657e91214dee2aaeb +size 7196502 diff --git a/selfdrive/modeld/models/dmonitoring_model_q.dlc b/selfdrive/modeld/models/dmonitoring_model_q.dlc deleted file mode 100644 index fc285954d4..0000000000 --- a/selfdrive/modeld/models/dmonitoring_model_q.dlc +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:7c26f13816b143f5bb29ac2980f8557bd5687a75729e4d895313fb9a5a1f0f46 -size 4488449 diff --git a/selfdrive/modeld/runners/onnxmodel.py b/selfdrive/modeld/runners/onnxmodel.py index 69b44a5a97..2145035a9f 100644 --- a/selfdrive/modeld/runners/onnxmodel.py +++ b/selfdrive/modeld/runners/onnxmodel.py @@ -14,8 +14,12 @@ def attributeproto_fp16_to_fp32(attr): attr.data_type = 1 attr.raw_data = float32_list.astype(np.float32).tobytes() -def convert_fp16_to_fp32(path): - model = onnx.load(path) +def convert_fp16_to_fp32(onnx_path_or_bytes): + if isinstance(onnx_path_or_bytes, bytes): + model = onnx.load_from_string(onnx_path_or_bytes) + elif isinstance(onnx_path_or_bytes, str): + model = onnx.load(onnx_path_or_bytes) + for i in model.graph.initializer: if i.data_type == 10: attributeproto_fp16_to_fp32(i) @@ -23,6 +27,8 @@ def convert_fp16_to_fp32(path): if i.type.tensor_type.elem_type == 10: i.type.tensor_type.elem_type = 1 for i in model.graph.node: + if i.op_type == 'Cast' and i.attribute[0].i == 10: + i.attribute[0].i = 1 for a in i.attribute: if hasattr(a, 't'): if a.t.data_type == 10: @@ -61,7 +67,6 @@ class ONNXModel(RunModel): def __init__(self, path, output, runtime, use_tf8, cl_context): self.inputs = {} self.output = output - self.use_tf8 = use_tf8 self.session = create_ort_session(path, fp16_to_fp32=True) self.input_names = [x.name for x in self.session.get_inputs()] @@ -85,7 +90,7 @@ class ONNXModel(RunModel): return None def execute(self): - inputs = {k: (v.view(np.uint8) / 255. if self.use_tf8 and k == 'input_img' else v) for k,v in self.inputs.items()} + inputs = {k: v.view(self.input_dtypes[k]) for k,v in self.inputs.items()} inputs = {k: v.reshape(self.input_shapes[k]).astype(self.input_dtypes[k]) for k,v in inputs.items()} outputs = self.session.run(None, inputs) assert len(outputs) == 1, "Only single model outputs are supported" diff --git a/selfdrive/monitoring/helpers.py b/selfdrive/monitoring/helpers.py index 2a7979221a..08cc049ab0 100644 --- a/selfdrive/monitoring/helpers.py +++ b/selfdrive/monitoring/helpers.py @@ -33,8 +33,8 @@ class DRIVER_MONITOR_SETTINGS: self._SG_THRESHOLD = 0.9 self._BLINK_THRESHOLD = 0.865 - self._EE_THRESH11 = 0.25 - self._EE_THRESH12 = 7.5 + self._EE_THRESH11 = 0.4 + self._EE_THRESH12 = 15.0 self._EE_MAX_OFFSET1 = 0.06 self._EE_MIN_OFFSET1 = 0.025 self._EE_THRESH21 = 0.01 diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 66971ebde1..2c757dde11 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -32fe8cf4a0daa8d10a689c9ae2e51a879151c87c +91d1089681f427a3916b42984d5df04eb94a0b90 diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 5bc6bff1c2..964848e3d3 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -32,6 +32,7 @@ CPU usage budget * total CPU usage of openpilot (sum(PROCS.values()) should not exceed MAX_TOTAL_CPU """ + MAX_TOTAL_CPU = 265. # total for all 8 cores PROCS = { # Baseline CPU usage by process @@ -312,7 +313,7 @@ class TestOnroad: assert max(mems) - min(mems) <= 3.0 def test_gpu_usage(self): - assert self.gpu_procs == {"weston", "ui", "camerad", "selfdrive.modeld.modeld"} + assert self.gpu_procs == {"weston", "ui", "camerad", "selfdrive.modeld.modeld", "selfdrive.modeld.dmonitoringmodeld"} def test_camera_processing_time(self): result = "\n" diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index eb3a515b76..3b9d65b85a 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -34,7 +34,7 @@ class Proc: PROCS = [ Proc(['camerad'], 2.1, msgs=['roadCameraState', 'wideRoadCameraState', 'driverCameraState']), Proc(['modeld'], 1.12, atol=0.2, msgs=['modelV2']), - Proc(['dmonitoringmodeld'], 0.4, msgs=['driverStateV2']), + Proc(['dmonitoringmodeld'], 0.5, msgs=['driverStateV2']), Proc(['encoderd'], 0.23, msgs=[]), ] diff --git a/system/manager/process_config.py b/system/manager/process_config.py index 538c55813b..98a875bf97 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -63,7 +63,7 @@ procs = [ PythonProcess("micd", "system.micd", iscar), PythonProcess("timed", "system.timed", always_run, enabled=not PC), - PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(not PC or WEBCAM)), + NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], driverview, enabled=(not PC or WEBCAM)), NativeProcess("encoderd", "system/loggerd", ["./encoderd"], only_onroad), NativeProcess("stream_encoderd", "system/loggerd", ["./encoderd", "--stream"], notcar), NativeProcess("loggerd", "system/loggerd", ["./loggerd"], logging), diff --git a/tinygrad_repo b/tinygrad_repo index f51aa0fc7c..3e15fa0dae 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit f51aa0fc7cdbac710e640172db280cfb747d2718 +Subproject commit 3e15fa0daefae75e2ddef98f82be5b5d37820631 From 5e024b775b373208c712ea944b414dd531f6c390 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 19 Sep 2024 18:08:40 -0700 Subject: [PATCH 104/214] fix big cars test (#33603) export and fix platforms --- selfdrive/car/tests/big_cars_test.sh | 8 ++++---- selfdrive/car/tests/test_models.py | 1 + 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/tests/big_cars_test.sh b/selfdrive/car/tests/big_cars_test.sh index 8b0e96d980..863b8bead0 100755 --- a/selfdrive/car/tests/big_cars_test.sh +++ b/selfdrive/car/tests/big_cars_test.sh @@ -4,9 +4,9 @@ SCRIPT_DIR=$(dirname "$0") BASEDIR=$(realpath "$SCRIPT_DIR/../../../") cd $BASEDIR -MAX_EXAMPLES=300 -INTERNAL_SEG_CNT=300 -FILEREADER_CACHE=1 -INTERNAL_SEG_LIST=selfdrive/car/tests/test_models_segs.txt +export MAX_EXAMPLES=300 +export INTERNAL_SEG_CNT=300 +export FILEREADER_CACHE=1 +export INTERNAL_SEG_LIST=selfdrive/car/tests/test_models_segs.txt cd selfdrive/car/tests && pytest test_models.py test_car_interfaces.py diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 0548f52764..460b9f196d 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -57,6 +57,7 @@ def get_test_cases() -> list[tuple[str, CarTestRoute | None]]: segment_list = read_segment_list(os.path.join(BASEDIR, INTERNAL_SEG_LIST)) segment_list = random.sample(segment_list, INTERNAL_SEG_CNT or len(segment_list)) for platform, segment in segment_list: + platform = MIGRATION.get(platform, platform) segment_name = SegmentName(segment) test_cases.append((platform, CarTestRoute(segment_name.route_name.canonical_name, platform, segment=segment_name.segment_num))) From ffb6e11f968525f41567aedb8bd5a24b88998afd Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Thu, 19 Sep 2024 20:55:11 -0700 Subject: [PATCH 105/214] Revert "exec DM model with gpu" (#33604) Revert "exec DM model with gpu (#33397)" This reverts commit f79aca8e1ef9160a93b2609146b4074b2343f75c. --- .gitattributes | 1 + selfdrive/modeld/SConscript | 4 --- selfdrive/modeld/dmonitoringmodeld | 10 ------- selfdrive/modeld/dmonitoringmodeld.py | 30 ++++++++----------- .../modeld/models/dmonitoring_model.current | 4 +-- .../modeld/models/dmonitoring_model.onnx | 4 +-- .../modeld/models/dmonitoring_model_q.dlc | 3 ++ selfdrive/modeld/runners/onnxmodel.py | 13 +++----- selfdrive/monitoring/helpers.py | 4 +-- .../process_replay/model_replay_ref_commit | 2 +- selfdrive/test/test_onroad.py | 3 +- system/hardware/tici/tests/test_power_draw.py | 2 +- system/manager/process_config.py | 2 +- tinygrad_repo | 2 +- 14 files changed, 31 insertions(+), 53 deletions(-) delete mode 100755 selfdrive/modeld/dmonitoringmodeld create mode 100644 selfdrive/modeld/models/dmonitoring_model_q.dlc diff --git a/.gitattributes b/.gitattributes index eda2505d0e..8781a7371f 100644 --- a/.gitattributes +++ b/.gitattributes @@ -2,6 +2,7 @@ # to move existing files into LFS: # git add --renormalize . +*.dlc filter=lfs diff=lfs merge=lfs -text *.onnx filter=lfs diff=lfs merge=lfs -text *.svg filter=lfs diff=lfs merge=lfs -text *.png filter=lfs diff=lfs merge=lfs -text diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index d472998416..d572915c72 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -69,10 +69,6 @@ if arch == "larch64" or GetOption('pc_thneed'): lenv.Command(fn + ".thneed", [fn + ".onnx"] + tinygrad_files, cmd) - fn_dm = File("models/dmonitoring_model").abspath - cmd = f"cd {Dir('#').abspath}/tinygrad_repo && " + ' '.join(tinygrad_opts) + f" python3 openpilot/compile2.py {fn_dm}.onnx {fn_dm}.thneed" - lenv.Command(fn_dm + ".thneed", [fn_dm + ".onnx"] + tinygrad_files, cmd) - thneed_lib = env.SharedLibrary('thneed', thneed_src, LIBS=[gpucommon, common, 'OpenCL', 'dl']) thneedmodel_lib = env.Library('thneedmodel', ['runners/thneedmodel.cc']) lenvCython.Program('runners/thneedmodel_pyx.so', 'runners/thneedmodel_pyx.pyx', LIBS=envCython["LIBS"]+[thneedmodel_lib, thneed_lib, gpucommon, common, 'dl', 'OpenCL']) diff --git a/selfdrive/modeld/dmonitoringmodeld b/selfdrive/modeld/dmonitoringmodeld deleted file mode 100755 index 80157e1751..0000000000 --- a/selfdrive/modeld/dmonitoringmodeld +++ /dev/null @@ -1,10 +0,0 @@ -#!/usr/bin/env bash - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" -cd "$DIR/../../" - -if [ -f "$DIR/libthneed.so" ]; then - export LD_PRELOAD="$DIR/libthneed.so" -fi - -exec "$DIR/dmonitoringmodeld.py" "$@" diff --git a/selfdrive/modeld/dmonitoringmodeld.py b/selfdrive/modeld/dmonitoringmodeld.py index d648a4511a..a388bf089c 100755 --- a/selfdrive/modeld/dmonitoringmodeld.py +++ b/selfdrive/modeld/dmonitoringmodeld.py @@ -6,7 +6,6 @@ import time import ctypes import numpy as np from pathlib import Path -from setproctitle import setproctitle from cereal import messaging from cereal.messaging import PubMaster, SubMaster @@ -15,18 +14,16 @@ from openpilot.common.swaglog import cloudlog from openpilot.common.params import Params from openpilot.common.realtime import set_realtime_priority from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime -from openpilot.selfdrive.modeld.models.commonmodel_pyx import sigmoid, CLContext +from openpilot.selfdrive.modeld.models.commonmodel_pyx import sigmoid CALIB_LEN = 3 +REG_SCALE = 0.25 MODEL_WIDTH = 1440 MODEL_HEIGHT = 960 -FEATURE_LEN = 512 -OUTPUT_SIZE = 84 + FEATURE_LEN - -PROCESS_NAME = "selfdrive.modeld.dmonitoringmodeld" +OUTPUT_SIZE = 84 SEND_RAW_PRED = os.getenv('SEND_RAW_PRED') MODEL_PATHS = { - ModelRunner.THNEED: Path(__file__).parent / 'models/dmonitoring_model.thneed', + ModelRunner.SNPE: Path(__file__).parent / 'models/dmonitoring_model_q.dlc', ModelRunner.ONNX: Path(__file__).parent / 'models/dmonitoring_model.onnx'} class DriverStateResult(ctypes.Structure): @@ -52,22 +49,21 @@ class DMonitoringModelResult(ctypes.Structure): ("driver_state_lhd", DriverStateResult), ("driver_state_rhd", DriverStateResult), ("poor_vision_prob", ctypes.c_float), - ("wheel_on_right_prob", ctypes.c_float), - ("features", ctypes.c_float*FEATURE_LEN)] + ("wheel_on_right_prob", ctypes.c_float)] class ModelState: inputs: dict[str, np.ndarray] output: np.ndarray model: ModelRunner - def __init__(self, cl_ctx): + def __init__(self): assert ctypes.sizeof(DMonitoringModelResult) == OUTPUT_SIZE * ctypes.sizeof(ctypes.c_float) self.output = np.zeros(OUTPUT_SIZE, dtype=np.float32) self.inputs = { 'input_img': np.zeros(MODEL_HEIGHT * MODEL_WIDTH, dtype=np.uint8), 'calib': np.zeros(CALIB_LEN, dtype=np.float32)} - self.model = ModelRunner(MODEL_PATHS, self.output, Runtime.GPU, False, cl_ctx) + self.model = ModelRunner(MODEL_PATHS, self.output, Runtime.DSP, True, None) self.model.addInput("input_img", None) self.model.addInput("calib", self.inputs['calib']) @@ -80,17 +76,17 @@ class ModelState: input_data = self.inputs['input_img'].reshape(MODEL_HEIGHT, MODEL_WIDTH) input_data[:] = buf_data[v_offset:v_offset+MODEL_HEIGHT, h_offset:h_offset+MODEL_WIDTH] - self.model.setInputBuffer("input_img", self.inputs['input_img'].view(np.float32)) t1 = time.perf_counter() + self.model.setInputBuffer("input_img", self.inputs['input_img'].view(np.float32)) self.model.execute() t2 = time.perf_counter() return self.output, t2 - t1 def fill_driver_state(msg, ds_result: DriverStateResult): - msg.faceOrientation = list(ds_result.face_orientation) + msg.faceOrientation = [x * REG_SCALE for x in ds_result.face_orientation] msg.faceOrientationStd = [math.exp(x) for x in ds_result.face_orientation_std] - msg.facePosition = list(ds_result.face_position[:2]) + msg.facePosition = [x * REG_SCALE for x in ds_result.face_position[:2]] msg.facePositionStd = [math.exp(x) for x in ds_result.face_position_std[:2]] msg.faceProb = sigmoid(ds_result.face_prob) msg.leftEyeProb = sigmoid(ds_result.left_eye_prob) @@ -119,16 +115,14 @@ def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: def main(): gc.disable() - setproctitle(PROCESS_NAME) set_realtime_priority(1) - cl_context = CLContext() - model = ModelState(cl_context) + model = ModelState() cloudlog.warning("models loaded, dmonitoringmodeld starting") Params().put_bool("DmModelInitialized", True) cloudlog.warning("connecting to driver stream") - vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_DRIVER, True, cl_context) + vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_DRIVER, True) while not vipc_client.connect(False): time.sleep(0.1) assert vipc_client.is_connected() diff --git a/selfdrive/modeld/models/dmonitoring_model.current b/selfdrive/modeld/models/dmonitoring_model.current index 121871ef2b..f935ab06b3 100644 --- a/selfdrive/modeld/models/dmonitoring_model.current +++ b/selfdrive/modeld/models/dmonitoring_model.current @@ -1,2 +1,2 @@ -fa69be01-b430-4504-9d72-7dcb058eb6dd -d9fb22d1c4fa3ca3d201dbc8edf1d0f0918e53e6 +5ec97a39-0095-4cea-adfa-6d72b1966cc1 +26cac7a9757a27c783a365403040a1bd27ccdaea \ No newline at end of file diff --git a/selfdrive/modeld/models/dmonitoring_model.onnx b/selfdrive/modeld/models/dmonitoring_model.onnx index dcc727510e..dd3a6aba2e 100644 --- a/selfdrive/modeld/models/dmonitoring_model.onnx +++ b/selfdrive/modeld/models/dmonitoring_model.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:50efe6451a3fb3fa04b6bb0e846544533329bd46ecefe9e657e91214dee2aaeb -size 7196502 +oid sha256:3dd3982940d823c4fbb0429b733a0b78b0688d7d67aa76ff7b754a3e2f3d8683 +size 16132780 diff --git a/selfdrive/modeld/models/dmonitoring_model_q.dlc b/selfdrive/modeld/models/dmonitoring_model_q.dlc new file mode 100644 index 0000000000..fc285954d4 --- /dev/null +++ b/selfdrive/modeld/models/dmonitoring_model_q.dlc @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7c26f13816b143f5bb29ac2980f8557bd5687a75729e4d895313fb9a5a1f0f46 +size 4488449 diff --git a/selfdrive/modeld/runners/onnxmodel.py b/selfdrive/modeld/runners/onnxmodel.py index 2145035a9f..69b44a5a97 100644 --- a/selfdrive/modeld/runners/onnxmodel.py +++ b/selfdrive/modeld/runners/onnxmodel.py @@ -14,12 +14,8 @@ def attributeproto_fp16_to_fp32(attr): attr.data_type = 1 attr.raw_data = float32_list.astype(np.float32).tobytes() -def convert_fp16_to_fp32(onnx_path_or_bytes): - if isinstance(onnx_path_or_bytes, bytes): - model = onnx.load_from_string(onnx_path_or_bytes) - elif isinstance(onnx_path_or_bytes, str): - model = onnx.load(onnx_path_or_bytes) - +def convert_fp16_to_fp32(path): + model = onnx.load(path) for i in model.graph.initializer: if i.data_type == 10: attributeproto_fp16_to_fp32(i) @@ -27,8 +23,6 @@ def convert_fp16_to_fp32(onnx_path_or_bytes): if i.type.tensor_type.elem_type == 10: i.type.tensor_type.elem_type = 1 for i in model.graph.node: - if i.op_type == 'Cast' and i.attribute[0].i == 10: - i.attribute[0].i = 1 for a in i.attribute: if hasattr(a, 't'): if a.t.data_type == 10: @@ -67,6 +61,7 @@ class ONNXModel(RunModel): def __init__(self, path, output, runtime, use_tf8, cl_context): self.inputs = {} self.output = output + self.use_tf8 = use_tf8 self.session = create_ort_session(path, fp16_to_fp32=True) self.input_names = [x.name for x in self.session.get_inputs()] @@ -90,7 +85,7 @@ class ONNXModel(RunModel): return None def execute(self): - inputs = {k: v.view(self.input_dtypes[k]) for k,v in self.inputs.items()} + inputs = {k: (v.view(np.uint8) / 255. if self.use_tf8 and k == 'input_img' else v) for k,v in self.inputs.items()} inputs = {k: v.reshape(self.input_shapes[k]).astype(self.input_dtypes[k]) for k,v in inputs.items()} outputs = self.session.run(None, inputs) assert len(outputs) == 1, "Only single model outputs are supported" diff --git a/selfdrive/monitoring/helpers.py b/selfdrive/monitoring/helpers.py index 08cc049ab0..2a7979221a 100644 --- a/selfdrive/monitoring/helpers.py +++ b/selfdrive/monitoring/helpers.py @@ -33,8 +33,8 @@ class DRIVER_MONITOR_SETTINGS: self._SG_THRESHOLD = 0.9 self._BLINK_THRESHOLD = 0.865 - self._EE_THRESH11 = 0.4 - self._EE_THRESH12 = 15.0 + self._EE_THRESH11 = 0.25 + self._EE_THRESH12 = 7.5 self._EE_MAX_OFFSET1 = 0.06 self._EE_MIN_OFFSET1 = 0.025 self._EE_THRESH21 = 0.01 diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 2c757dde11..66971ebde1 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -91d1089681f427a3916b42984d5df04eb94a0b90 +32fe8cf4a0daa8d10a689c9ae2e51a879151c87c diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 964848e3d3..5bc6bff1c2 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -32,7 +32,6 @@ CPU usage budget * total CPU usage of openpilot (sum(PROCS.values()) should not exceed MAX_TOTAL_CPU """ - MAX_TOTAL_CPU = 265. # total for all 8 cores PROCS = { # Baseline CPU usage by process @@ -313,7 +312,7 @@ class TestOnroad: assert max(mems) - min(mems) <= 3.0 def test_gpu_usage(self): - assert self.gpu_procs == {"weston", "ui", "camerad", "selfdrive.modeld.modeld", "selfdrive.modeld.dmonitoringmodeld"} + assert self.gpu_procs == {"weston", "ui", "camerad", "selfdrive.modeld.modeld"} def test_camera_processing_time(self): result = "\n" diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index 3b9d65b85a..eb3a515b76 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -34,7 +34,7 @@ class Proc: PROCS = [ Proc(['camerad'], 2.1, msgs=['roadCameraState', 'wideRoadCameraState', 'driverCameraState']), Proc(['modeld'], 1.12, atol=0.2, msgs=['modelV2']), - Proc(['dmonitoringmodeld'], 0.5, msgs=['driverStateV2']), + Proc(['dmonitoringmodeld'], 0.4, msgs=['driverStateV2']), Proc(['encoderd'], 0.23, msgs=[]), ] diff --git a/system/manager/process_config.py b/system/manager/process_config.py index 98a875bf97..538c55813b 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -63,7 +63,7 @@ procs = [ PythonProcess("micd", "system.micd", iscar), PythonProcess("timed", "system.timed", always_run, enabled=not PC), - NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], driverview, enabled=(not PC or WEBCAM)), + PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(not PC or WEBCAM)), NativeProcess("encoderd", "system/loggerd", ["./encoderd"], only_onroad), NativeProcess("stream_encoderd", "system/loggerd", ["./encoderd", "--stream"], notcar), NativeProcess("loggerd", "system/loggerd", ["./loggerd"], logging), diff --git a/tinygrad_repo b/tinygrad_repo index 3e15fa0dae..f51aa0fc7c 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit 3e15fa0daefae75e2ddef98f82be5b5d37820631 +Subproject commit f51aa0fc7cdbac710e640172db280cfb747d2718 From 20c983897baff67fed8667223cc5d08f87e71940 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 19 Sep 2024 20:57:42 -0700 Subject: [PATCH 106/214] camerad: set patch_offset --- system/camerad/cameras/spectra.cc | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index b8b8959f67..a02ec01d28 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -419,12 +419,6 @@ void SpectraCamera::config_isp(int io_mem_handle, int fence, int request_id, int pkt->kmd_cmd_buf_offset = 0; } - // *** patches *** - { - pkt->num_patches = 0; - pkt->patch_offset = 0x0; - } - // *** cmd buf *** { struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; @@ -545,6 +539,12 @@ void SpectraCamera::config_isp(int io_mem_handle, int fence, int request_id, int io_cfg[0].framedrop_pattern = 0x1; } + // *** patches *** + { + pkt->num_patches = 0; + pkt->patch_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf + sizeof(struct cam_buf_io_cfg)*pkt->num_io_configs; + } + int ret = device_config(m->isp_fd, session_handle, isp_dev_handle, cam_packet_handle); assert(ret == 0); } From 3c5ed2f7160f8609695bcb13036f2e1714e53f23 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 19 Sep 2024 21:57:11 -0700 Subject: [PATCH 107/214] Longitudinal maneuver report: display pitch (#33610) * export and fix platforms * test * display pitch * Revert "test" This reverts commit 80c57fda9afcb6e6cae002f54d8ffbe46c2feb01. * Revert "export and fix platforms" This reverts commit 614e62d775799a9af1e76ab9025dc96bbe1b83c6. * add to top * Revert "display pitch" This reverts commit 5bad8c0be71aba914490848473782ed7c4a1ca83. --- tools/longitudinal_maneuvers/generate_report.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py index 36e2d3eecc..dff7a857bc 100755 --- a/tools/longitudinal_maneuvers/generate_report.py +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -75,6 +75,9 @@ def report(platform, route, _description, CP, maneuvers): f.write(', not crossed') f.write('

') + pitches = [math.degrees(m.orientationNED[1]) for m in carControl] + f.write(f'

Average pitch: {sum(pitches) / len(pitches):0.2f} degrees

') + plt.rcParams['font.size'] = 40 fig = plt.figure(figsize=(30, 26)) ax = fig.subplots(4, 1, sharex=True, gridspec_kw={'height_ratios': [5, 3, 1, 1]}) From fe61b436b230637b9c54f15a7ab5535fd806f030 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 19 Sep 2024 21:58:00 -0700 Subject: [PATCH 108/214] fix import --- tools/longitudinal_maneuvers/generate_report.py | 1 + 1 file changed, 1 insertion(+) diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py index dff7a857bc..a396e51127 100755 --- a/tools/longitudinal_maneuvers/generate_report.py +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -3,6 +3,7 @@ import argparse import base64 import io import os +import math import pprint from collections import defaultdict from pathlib import Path From 48938098e0d15f3a1e91b68cbb91ced7209ba103 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Kacper=20R=C4=85czy?= Date: Thu, 19 Sep 2024 22:09:53 -0700 Subject: [PATCH 109/214] Add modelExecutionTime to DrivingModelData (#33606) * Add model execution time to DrivingModelData * Update model replay ref commit * Update ref commit again * Ignore this field in model replay * Back to original ref commit * Bring back --------- Co-authored-by: Comma Device --- cereal/log.capnp | 1 + selfdrive/modeld/fill_model_msg.py | 1 + selfdrive/test/process_replay/model_replay.py | 1 + selfdrive/test/process_replay/process_replay.py | 2 +- 4 files changed, 4 insertions(+), 1 deletion(-) diff --git a/cereal/log.capnp b/cereal/log.capnp index ddde5e4d16..75df44edec 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -887,6 +887,7 @@ struct DrivingModelData { frameId @0 :UInt32; frameIdExtra @1 :UInt32; frameDropPerc @6 :Float32; + modelExecutionTime @7 :Float32; action @2 :ModelDataV2.Action; diff --git a/selfdrive/modeld/fill_model_msg.py b/selfdrive/modeld/fill_model_msg.py index 1c7ae49580..9cdd7e4c52 100644 --- a/selfdrive/modeld/fill_model_msg.py +++ b/selfdrive/modeld/fill_model_msg.py @@ -62,6 +62,7 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D driving_model_data.frameId = vipc_frame_id driving_model_data.frameIdExtra = vipc_frame_id_extra driving_model_data.frameDropPerc = frame_drop_perc + driving_model_data.modelExecutionTime = model_execution_time action = driving_model_data.action action.desiredCurvature = float(net_output_data['desired_curvature'][0,0]) diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index 4402ca31d6..bb7c0b0a8e 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -105,6 +105,7 @@ if __name__ == "__main__": ignore = [ 'logMonoTime', 'drivingModelData.frameDropPerc', + 'drivingModelData.modelExecutionTime', 'modelV2.frameDropPerc', 'modelV2.modelExecutionTime', 'driverStateV2.modelExecutionTime', diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index d94c1d1f52..59f6c6cc53 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -571,7 +571,7 @@ CONFIGS = [ proc_name="modeld", pubs=["deviceState", "roadCameraState", "wideRoadCameraState", "liveCalibration", "driverMonitoringState"], subs=["modelV2", "drivingModelData", "cameraOdometry"], - ignore=["logMonoTime", "modelV2.frameDropPerc", "modelV2.modelExecutionTime"], + ignore=["logMonoTime", "modelV2.frameDropPerc", "modelV2.modelExecutionTime", "drivingModelData.frameDropPerc", "drivingModelData.modelExecutionTime"], should_recv_callback=ModeldCameraSyncRcvCallback(), tolerance=NUMPY_TOLERANCE, processing_time=0.020, From 580388e209630fc806fa9ed89aa7fe0c7bf0fcdd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Kacper=20R=C4=85czy?= Date: Thu, 19 Sep 2024 22:10:07 -0700 Subject: [PATCH 110/214] Deprecate ModelDataV2.gpuExecutionTime (#33607) Deprecate gpuExecutionTime --- cereal/log.capnp | 8 ++++---- tools/latencylogger/README.md | 2 +- tools/latencylogger/latency_logger.py | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/cereal/log.capnp b/cereal/log.capnp index 75df44edec..87be2ceb99 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -933,7 +933,6 @@ struct ModelDataV2 { frameDropPerc @2 :Float32; timestampEof @3 :UInt64; modelExecutionTime @15 :Float32; - gpuExecutionTime @17 :Float32; rawPredictions @16 :Data; # predicted future position, orientation, etc.. @@ -960,12 +959,13 @@ struct ModelDataV2 { # Model perceived motion temporalPose @21 :Pose; + # e2e lateral planner + action @26: Action; + + gpuExecutionTimeDEPRECATED @17 :Float32; navEnabledDEPRECATED @22 :Bool; locationMonoTimeDEPRECATED @24 :UInt64; - - # e2e lateral planner lateralPlannerSolutionDEPRECATED @25: LateralPlannerSolution; - action @26: Action; struct LeadDataV2 { prob @0 :Float32; # probability that car is your lead at time t diff --git a/tools/latencylogger/README.md b/tools/latencylogger/README.md index 24169dfaef..110970308a 100644 --- a/tools/latencylogger/README.md +++ b/tools/latencylogger/README.md @@ -51,7 +51,7 @@ Frame ID: 1202 Execution finished 63.002552 modelV2 published 63.148747 modelV2.modelExecutionTime 23.62649142742157 - modelV2.gpuExecutionTime 0.0 + modelV2.gpuExecutionTimeDEPRECATED 0.0 plannerd longitudinalPlan published 69.715999 longitudinalPlan.solverExecutionTime 0.5619999719783664 diff --git a/tools/latencylogger/latency_logger.py b/tools/latencylogger/latency_logger.py index f145cc35e4..32df0da4b5 100755 --- a/tools/latencylogger/latency_logger.py +++ b/tools/latencylogger/latency_logger.py @@ -23,7 +23,7 @@ MSGQ_TO_SERVICE = { } SERVICE_TO_DURATIONS = { 'camerad': ['processingTime'], - 'modeld': ['modelExecutionTime', 'gpuExecutionTime'], + 'modeld': ['modelExecutionTime', 'gpuExecutionTimeDEPRECATED'], 'plannerd': ['solverExecutionTime'], } From 07f3f93bd9cc7617aa43d228403fd49376078545 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 21 Sep 2024 02:15:49 +0800 Subject: [PATCH 111/214] camerad: remove SpectraCamera inheritance from CameraState and simplify initialization (#33611) remove inherit Co-authored-by: Comma Device --- system/camerad/cameras/camera_qcom2.cc | 146 ++++++++++++------------- system/camerad/cameras/spectra.cc | 6 +- system/camerad/cameras/spectra.h | 3 +- 3 files changed, 71 insertions(+), 84 deletions(-) diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 97e4d9b756..1bbd8202b2 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -29,9 +29,10 @@ const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != nullptr; const bool env_ctrl_exp_from_params = getenv("CTRL_EXP_FROM_PARAMS") != nullptr; -// high level camera state -class CameraState : public SpectraCamera { +class CameraState { public: + SpectraCamera camera; + std::thread thread; int exposure_time = 5; bool dc_gain_enabled = false; int dc_gain_weight = 0; @@ -49,27 +50,35 @@ public: float fl_pix = 0; - CameraState(SpectraMaster *master, const CameraConfig &config) : SpectraCamera(master, config) {}; + CameraState(SpectraMaster *master, const CameraConfig &config) : camera(master, config) {}; + ~CameraState(); + void init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx); void update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain); void set_camera_exposure(float grey_frac); - void set_exposure_rect(); void run(); float get_gain_factor() const { - return (1 + dc_gain_weight * (sensor->dc_gain_factor-1) / sensor->dc_gain_max_weight); + return (1 + dc_gain_weight * (camera.sensor->dc_gain_factor-1) / camera.sensor->dc_gain_max_weight); } +}; - void init() { - fl_pix = cc.focal_len / sensor->pixel_size_mm; - set_exposure_rect(); +void CameraState::init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx) { + camera.camera_open(v, device_id, ctx); - dc_gain_weight = sensor->dc_gain_min_weight; - gain_idx = sensor->analog_gain_rec_idx; - cur_ev[0] = cur_ev[1] = cur_ev[2] = get_gain_factor() * sensor->sensor_analog_gains[gain_idx] * exposure_time; - }; -}; + fl_pix = camera.cc.focal_len / camera.sensor->pixel_size_mm; + set_exposure_rect(); + dc_gain_weight = camera.sensor->dc_gain_min_weight; + gain_idx = camera.sensor->analog_gain_rec_idx; + cur_ev[0] = cur_ev[1] = cur_ev[2] = get_gain_factor() * camera.sensor->sensor_analog_gains[gain_idx] * exposure_time; + + if (camera.enabled) thread = std::thread(&CameraState::run, this); +} + +CameraState::~CameraState() { + if (thread.joinable()) thread.join(); +} void CameraState::set_exposure_rect() { // set areas for each camera, shouldn't be changed @@ -88,20 +97,20 @@ void CameraState::set_exposure_rect() { [0, 0, 1] ] */ - auto ae_target = ae_targets[cc.camera_num]; + auto ae_target = ae_targets[camera.cc.camera_num]; Rect xywh_ref = ae_target.first; float fl_ref = ae_target.second; ae_xywh = (Rect){ - std::max(0, buf.out_img_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), - std::max(0, buf.out_img_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), - std::min((int)(fl_pix / fl_ref * xywh_ref.w), buf.out_img_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), - std::min((int)(fl_pix / fl_ref * xywh_ref.h), buf.out_img_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) + std::max(0, camera.buf.out_img_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), + std::max(0, camera.buf.out_img_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), + std::min((int)(fl_pix / fl_ref * xywh_ref.w), camera.buf.out_img_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), + std::min((int)(fl_pix / fl_ref * xywh_ref.h), camera.buf.out_img_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) }; } void CameraState::update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain) { - float score = sensor->getExposureScore(desired_ev, exp_t, exp_g_idx, exp_gain, gain_idx); + float score = camera.sensor->getExposureScore(desired_ev, exp_t, exp_g_idx, exp_gain, gain_idx); if (score < best_ev_score) { new_exp_t = exp_t; new_exp_g = exp_g_idx; @@ -110,7 +119,7 @@ void CameraState::update_exposure_score(float desired_ev, int exp_t, int exp_g_i } void CameraState::set_camera_exposure(float grey_frac) { - if (!enabled) return; + if (!camera.enabled) return; const float dt = 0.05; const float ts_grey = 10.0; @@ -124,7 +133,8 @@ void CameraState::set_camera_exposure(float grey_frac) { // Therefore we use the target EV from 3 frames ago, the grey fraction that was just measured was the result of that control action. // TODO: Lower latency to 2 frames, by using the histogram outputted by the sensor we can do AE before the debayering is complete - const float cur_ev_ = cur_ev[buf.cur_frame_data.frame_id % 3]; + const float cur_ev_ = cur_ev[camera.buf.cur_frame_data.frame_id % 3]; + const auto &sensor = camera.sensor; // Scale target grey between 0.1 and 0.4 depending on lighting conditions float new_target_grey = std::clamp(0.4 - 0.3 * log2(1.0 + sensor->target_grey_factor*cur_ev_) / log2(6000.0), 0.1, 0.4); @@ -194,72 +204,69 @@ void CameraState::set_camera_exposure(float grey_frac) { dc_gain_enabled = enable_dc_gain; float gain = analog_gain_frac * get_gain_factor(); - cur_ev[buf.cur_frame_data.frame_id % 3] = exposure_time * gain; + cur_ev[camera.buf.cur_frame_data.frame_id % 3] = exposure_time * gain; // Processing a frame takes right about 50ms, so we need to wait a few ms // so we don't send i2c commands around the frame start. - int ms = (nanos_since_boot() - buf.cur_frame_data.timestamp_sof) / 1000000; + int ms = (nanos_since_boot() - camera.buf.cur_frame_data.timestamp_sof) / 1000000; if (ms < 60) { util::sleep_for(60 - ms); } - // LOGE("ae - camera %d, cur_t %.5f, sof %.5f, dt %.5f", cc.camera_num, 1e-9 * nanos_since_boot(), 1e-9 * buf.cur_frame_data.timestamp_sof, 1e-9 * (nanos_since_boot() - buf.cur_frame_data.timestamp_sof)); + // LOGE("ae - camera %d, cur_t %.5f, sof %.5f, dt %.5f", camera.cc.camera_num, 1e-9 * nanos_since_boot(), 1e-9 * camera.buf.cur_frame_data.timestamp_sof, 1e-9 * (nanos_since_boot() - camera.buf.cur_frame_data.timestamp_sof)); auto exp_reg_array = sensor->getExposureRegisters(exposure_time, new_exp_g, dc_gain_enabled); - sensors_i2c(exp_reg_array.data(), exp_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, sensor->data_word); + camera.sensors_i2c(exp_reg_array.data(), exp_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, camera.sensor->data_word); } void CameraState::run() { - util::set_thread_name(cc.publish_name); + util::set_thread_name(camera.cc.publish_name); - std::vector pubs = {cc.publish_name}; - if (cc.stream_type == VISION_STREAM_ROAD) pubs.push_back("thumbnail"); + std::vector pubs = {camera.cc.publish_name}; + if (camera.cc.stream_type == VISION_STREAM_ROAD) pubs.push_back("thumbnail"); PubMaster pm(pubs); for (uint32_t cnt = 0; !do_exit; ++cnt) { // Acquire the buffer; continue if acquisition fails - if (!buf.acquire(exposure_time)) continue; + if (!camera.buf.acquire(exposure_time)) continue; MessageBuilder msg; - auto framed = (msg.initEvent().*cc.init_camera_state)(); - framed.setFrameId(buf.cur_frame_data.frame_id); - framed.setRequestId(buf.cur_frame_data.request_id); - framed.setTimestampEof(buf.cur_frame_data.timestamp_eof); - framed.setTimestampSof(buf.cur_frame_data.timestamp_sof); + auto framed = (msg.initEvent().*camera.cc.init_camera_state)(); + const FrameMetadata &meta = camera.buf.cur_frame_data; + framed.setFrameId(meta.frame_id); + framed.setRequestId(meta.request_id); + framed.setTimestampEof(meta.timestamp_eof); + framed.setTimestampSof(meta.timestamp_sof); framed.setIntegLines(exposure_time); framed.setGain(analog_gain_frac * get_gain_factor()); framed.setHighConversionGain(dc_gain_enabled); framed.setMeasuredGreyFraction(measured_grey_fraction); framed.setTargetGreyFraction(target_grey_fraction); - framed.setProcessingTime(buf.cur_frame_data.processing_time); + framed.setProcessingTime(meta.processing_time); - const float ev = cur_ev[buf.cur_frame_data.frame_id % 3]; - const float perc = util::map_val(ev, sensor->min_ev, sensor->max_ev, 0.0f, 100.0f); + const float ev = cur_ev[meta.frame_id % 3]; + const float perc = util::map_val(ev, camera.sensor->min_ev, camera.sensor->max_ev, 0.0f, 100.0f); framed.setExposureValPercent(perc); - framed.setSensor(sensor->image_sensor); + framed.setSensor(camera.sensor->image_sensor); // Log raw frames for road camera - if (env_log_raw_frames && cc.stream_type == VISION_STREAM_ROAD && cnt % 100 == 5) { // no overlap with qlog decimation - framed.setImage(get_raw_frame_image(&buf)); + if (env_log_raw_frames && camera.cc.stream_type == VISION_STREAM_ROAD && cnt % 100 == 5) { // no overlap with qlog decimation + framed.setImage(get_raw_frame_image(&camera.buf)); } // Process camera registers and set camera exposure - sensor->processRegisters((uint8_t *)buf.cur_camera_buf->addr, framed); - set_camera_exposure(set_exposure_target(&buf, ae_xywh, 2, cc.stream_type != VISION_STREAM_DRIVER ? 2 : 4)); + camera.sensor->processRegisters((uint8_t *)camera.buf.cur_camera_buf->addr, framed); + set_camera_exposure(set_exposure_target(&camera.buf, ae_xywh, 2, camera.cc.stream_type != VISION_STREAM_DRIVER ? 2 : 4)); // Send the message - pm.send(cc.publish_name, msg); - if (cc.stream_type == VISION_STREAM_ROAD && cnt % 100 == 3) { - publish_thumbnail(&pm, &buf); // this takes 10ms??? + pm.send(camera.cc.publish_name, msg); + if (camera.cc.stream_type == VISION_STREAM_ROAD && cnt % 100 == 3) { + publish_thumbnail(&pm, &camera.buf); // this takes 10ms??? } } } void camerad_thread() { - /* - TODO: future cleanups - - centralize enabled handling - - open/init/etc mess - */ + // TODO: centralize enabled handling cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); const cl_context_properties props[] = {CL_CONTEXT_PRIORITY_HINT_QCOM, CL_PRIORITY_HINT_HIGH_QCOM, 0}; @@ -272,34 +279,23 @@ void camerad_thread() { m.init(); // *** per-cam init *** - std::vector cams = { - new CameraState(&m, ROAD_CAMERA_CONFIG), - new CameraState(&m, WIDE_ROAD_CAMERA_CONFIG), - new CameraState(&m, DRIVER_CAMERA_CONFIG), - }; - for (auto cam : cams) cam->camera_open(); - for (auto cam : cams) cam->camera_init(&v, device_id, ctx); - for (auto cam : cams) cam->init(); - v.start_listener(); - - LOG("-- Starting threads"); - std::vector threads; - for (auto cam : cams) { - if (cam->enabled) threads.emplace_back(&CameraState::run, cam); + std::vector> cams; + for (const auto &config : {ROAD_CAMERA_CONFIG, WIDE_ROAD_CAMERA_CONFIG, DRIVER_CAMERA_CONFIG}) { + auto cam = std::make_unique(&m, config); + cam->init(&v, device_id ,ctx); + cams.emplace_back(std::move(cam)); } + v.start_listener(); + // start devices LOG("-- Starting devices"); - for (auto cam : cams) cam->sensors_start(); + for (auto &cam : cams) cam->camera.sensors_start(); // poll events LOG("-- Dequeueing Video events"); while (!do_exit) { - struct pollfd fds[1] = {{0}}; - - fds[0].fd = m.video0_fd; - fds[0].events = POLLPRI; - + struct pollfd fds[1] = {{.fd = m.video0_fd, .events = POLLPRI}}; int ret = poll(fds, std::size(fds), 1000); if (ret < 0) { if (errno == EINTR || errno == EAGAIN) continue; @@ -320,9 +316,9 @@ void camerad_thread() { do_exit = do_exit || event_data->u.frame_msg.frame_id > (1*20); } - for (auto cam : cams) { - if (event_data->session_hdl == cam->session_handle) { - cam->handle_camera_event(event_data); + for (auto &cam : cams) { + if (event_data->session_hdl == cam->camera.session_handle) { + cam->camera.handle_camera_event(event_data); break; } } @@ -333,8 +329,4 @@ void camerad_thread() { LOGE("VIDIOC_DQEVENT failed, errno=%d", errno); } } - - LOG(" ************** STOPPING **************"); - for (auto &t : threads) t.join(); - for (auto cam : cams) delete cam; } diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index a02ec01d28..6e967b60cc 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -218,7 +218,7 @@ int SpectraCamera::clear_req_queue() { return ret; } -void SpectraCamera::camera_open() { +void SpectraCamera::camera_open(VisionIpcServer *v, cl_device_id device_id, cl_context ctx) { if (!enabled) return; if (!openSensor()) { @@ -229,10 +229,6 @@ void SpectraCamera::camera_open() { configISP(); configCSIPHY(); linkDevices(); -} - -void SpectraCamera::camera_init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx) { - if (!enabled) return; LOGD("camera init %d", cc.camera_num); buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, cc.stream_type); diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h index a42540cc8f..9dd9f0341d 100644 --- a/system/camerad/cameras/spectra.h +++ b/system/camerad/cameras/spectra.h @@ -63,11 +63,10 @@ public: SpectraCamera(SpectraMaster *master, const CameraConfig &config); ~SpectraCamera(); - void camera_open(); + void camera_open(VisionIpcServer *v, cl_device_id device_id, cl_context ctx); void handle_camera_event(const cam_req_mgr_message *event_data); void camera_close(); void camera_map_bufs(); - void camera_init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx); void config_isp(int io_mem_handle, int fence, int request_id, int buf0_idx); int clear_req_queue(); From 8d50970aefb3057cf5325d2535851c6f83a19d03 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Fri, 20 Sep 2024 14:42:21 -0700 Subject: [PATCH 112/214] New steer limit warning (#33608) * New steer limit * Update selfdrived.py * Update selfdrived.py * Update selfdrived.py * Update ref --- selfdrive/selfdrived/selfdrived.py | 34 ++++++++---------------- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 12 insertions(+), 24 deletions(-) diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 4559c82bd6..18ac61dec8 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -17,6 +17,7 @@ from openpilot.common.gps import get_gps_location_service from openpilot.selfdrive.selfdrived.events import Events, ET from openpilot.selfdrive.selfdrived.state import StateMachine from openpilot.selfdrive.selfdrived.alertmanager import AlertManager, set_offroad_alert +from openpilot.selfdrive.controls.lib.latcontrol import MIN_LATERAL_CONTROL_SPEED from openpilot.system.hardware import HARDWARE from openpilot.system.version import get_build_metadata @@ -304,30 +305,17 @@ class SelfdriveD: if CS.steeringPressed: self.last_steering_pressed_frame = self.sm.frame recent_steer_pressed = (self.sm.frame - self.last_steering_pressed_frame)*DT_CTRL < 2.0 - lac = getattr(self.sm['controlsState'].lateralControlState, self.sm['controlsState'].lateralControlState.which()) + controlstate = self.sm['controlsState'] + lac = getattr(controlstate.lateralControlState, controlstate.lateralControlState.which()) if lac.active and not recent_steer_pressed and not self.CP.notCar: - if self.CP.lateralTuning.which() == 'torque': - undershooting = abs(lac.desiredLateralAccel) / abs(1e-3 + lac.actualLateralAccel) > 1.2 - turning = abs(lac.desiredLateralAccel) > 1.0 - good_speed = CS.vEgo > 5 - max_torque = abs(self.sm['carOutput'].actuatorsOutput.steer) > 0.99 - if undershooting and turning and good_speed and max_torque: - self.events.add(EventName.steerSaturated) - elif lac.saturated: - # TODO probably should not use dpath_points but curvature - dpath_points = self.sm['modelV2'].position.y - if len(dpath_points): - # Check if we deviated from the path - # TODO use desired vs actual curvature - if self.CP.steerControlType == car.CarParams.SteerControlType.angle: - steering_value = self.sm['carControl'].actuators.steeringAngleDeg - else: - steering_value = self.sm['carControl'].actuators.steer - - left_deviation = steering_value > 0 and dpath_points[0] < -0.20 - right_deviation = steering_value < 0 and dpath_points[0] > 0.20 - if left_deviation or right_deviation: - self.events.add(EventName.steerSaturated) + clipped_speed = max(CS.vEgo, MIN_LATERAL_CONTROL_SPEED) + actual_lateral_accel = controlstate.curvature * (clipped_speed**2) + desired_lateral_accel = controlstate.desiredCurvature * (clipped_speed**2) + undershooting = abs(desired_lateral_accel) / abs(1e-3 + actual_lateral_accel) > 1.2 + turning = abs(desired_lateral_accel) > 1.0 + good_speed = CS.vEgo > 5 + if undershooting and turning and good_speed and lac.saturated: + self.events.add(EventName.steerSaturated) # Check for FCW stock_long_is_braking = self.enabled and not self.CP.openpilotLongitudinalControl and CS.aEgo < -1.25 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index e08f65f499..04b3c0a6fd 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -dbaa29106eb93267699c822e4937126b4307805a \ No newline at end of file +96c2e2ab2e3a11476f1207c531893cc8e45d2b3c From b2976631d283c54a3343fbf81a7f667ed030e398 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Fri, 20 Sep 2024 15:00:34 -0700 Subject: [PATCH 113/214] onnxmodel fp16_to_fp32: misc improvements (#33615) --- selfdrive/modeld/runners/onnxmodel.py | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/selfdrive/modeld/runners/onnxmodel.py b/selfdrive/modeld/runners/onnxmodel.py index 69b44a5a97..a570e34305 100644 --- a/selfdrive/modeld/runners/onnxmodel.py +++ b/selfdrive/modeld/runners/onnxmodel.py @@ -14,8 +14,12 @@ def attributeproto_fp16_to_fp32(attr): attr.data_type = 1 attr.raw_data = float32_list.astype(np.float32).tobytes() -def convert_fp16_to_fp32(path): - model = onnx.load(path) +def convert_fp16_to_fp32(onnx_path_or_bytes): + if isinstance(onnx_path_or_bytes, bytes): + model = onnx.load_from_string(onnx_path_or_bytes) + elif isinstance(onnx_path_or_bytes, str): + model = onnx.load(onnx_path_or_bytes) + for i in model.graph.initializer: if i.data_type == 10: attributeproto_fp16_to_fp32(i) @@ -23,6 +27,8 @@ def convert_fp16_to_fp32(path): if i.type.tensor_type.elem_type == 10: i.type.tensor_type.elem_type = 1 for i in model.graph.node: + if i.op_type == 'Cast' and i.attribute[0].i == 10: + i.attribute[0].i = 1 for a in i.attribute: if hasattr(a, 't'): if a.t.data_type == 10: From 0c0b6588649ea04ae2ab221ad3a2088bc7020895 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 20 Sep 2024 16:54:17 -0700 Subject: [PATCH 114/214] Lexus ES TSS2: reduce longitudinal integral and compensate for road pitch (#33616) bump --- opendbc_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc_repo b/opendbc_repo index b937eefca1..0771622149 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit b937eefca19a70f38ddd2a9ffbc9d331f581ec9d +Subproject commit 07716221498c17e1f8fd4252868fb6250e23141d From 6fff91d91e1995db1a2c9fcb7486a7dd4840a872 Mon Sep 17 00:00:00 2001 From: Comma Device Date: Sat, 21 Sep 2024 00:55:42 +0000 Subject: [PATCH 115/214] new tici updater build --- system/hardware/tici/updater | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/system/hardware/tici/updater b/system/hardware/tici/updater index 11ce7809d0..23cdc140f4 100755 --- a/system/hardware/tici/updater +++ b/system/hardware/tici/updater @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:8db3f973663e59921fcc9e5d5600a346c1e229a2e8481a874ef996d97303dc4e -size 16631712 +oid sha256:eba5f44e6a763e1f74d1c718993218adcc72cba4caafe99b595fa701151a4c54 +size 10448792 From 2b37624deee846ce425df40b5a44746249854861 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 23 Sep 2024 05:11:59 +0800 Subject: [PATCH 116/214] encoderd: use const reference for VisionBuf access (#33621) use const reference for VisionBuf access --- system/loggerd/encoderd.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/loggerd/encoderd.cc b/system/loggerd/encoderd.cc index 4186e13ef1..feb9a921ec 100644 --- a/system/loggerd/encoderd.cc +++ b/system/loggerd/encoderd.cc @@ -59,7 +59,7 @@ void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { // init encoders if (encoders.empty()) { - VisionBuf buf_info = vipc_client.buffers[0]; + const VisionBuf &buf_info = vipc_client.buffers[0]; LOGW("encoder %s init %zux%zu", cam_info.thread_name, buf_info.width, buf_info.height); assert(buf_info.width > 0 && buf_info.height > 0); From 0bdad1fee07acaa2d91a8d6d2aee8be5a8355e35 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 23 Sep 2024 05:12:07 +0800 Subject: [PATCH 117/214] loggerd: direct Initialize params instead of copy (#33622) Direct Initialize Instead of Copy --- system/loggerd/logger.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/loggerd/logger.cc b/system/loggerd/logger.cc index 8234cd84ad..213aa69d3e 100644 --- a/system/loggerd/logger.cc +++ b/system/loggerd/logger.cc @@ -40,7 +40,7 @@ kj::Array logger_build_init_data() { init.setOsVersion(util::read_file("/VERSION")); // log params - auto params = Params(util::getenv("PARAMS_COPY_PATH", "")); + Params params(util::getenv("PARAMS_COPY_PATH", "")); std::map params_map = params.readAll(); init.setGitCommit(params_map["GitCommit"]); From 312a1b2a6565c98bfc237deede4fe5ada20f8690 Mon Sep 17 00:00:00 2001 From: Robin Reckmann Date: Mon, 23 Sep 2024 06:15:01 +0900 Subject: [PATCH 118/214] camerad: fix: Explicitly include necessary headers (#33623) camerad: Explicitly include necessary headers --- system/camerad/cameras/spectra.h | 2 ++ system/camerad/sensors/ar0231.cc | 1 + system/camerad/sensors/os04c10.cc | 2 ++ system/camerad/sensors/ox03c10.cc | 2 ++ 4 files changed, 7 insertions(+) diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h index 9dd9f0341d..e9e83ddb38 100644 --- a/system/camerad/cameras/spectra.h +++ b/system/camerad/cameras/spectra.h @@ -1,6 +1,8 @@ #pragma once +#include #include +#include #include #include "media/cam_req_mgr.h" diff --git a/system/camerad/sensors/ar0231.cc b/system/camerad/sensors/ar0231.cc index ce8b0c0a4b..db709e355a 100644 --- a/system/camerad/sensors/ar0231.cc +++ b/system/camerad/sensors/ar0231.cc @@ -1,4 +1,5 @@ #include +#include #include "common/swaglog.h" #include "system/camerad/sensors/sensor.h" diff --git a/system/camerad/sensors/os04c10.cc b/system/camerad/sensors/os04c10.cc index e651d6ff7a..a741aaf4fe 100644 --- a/system/camerad/sensors/os04c10.cc +++ b/system/camerad/sensors/os04c10.cc @@ -1,3 +1,5 @@ +#include + #include "system/camerad/sensors/sensor.h" namespace { diff --git a/system/camerad/sensors/ox03c10.cc b/system/camerad/sensors/ox03c10.cc index 94efa0ea24..80b9c79212 100644 --- a/system/camerad/sensors/ox03c10.cc +++ b/system/camerad/sensors/ox03c10.cc @@ -1,3 +1,5 @@ +#include + #include "system/camerad/sensors/sensor.h" namespace { From d5039bcbbe80a0de030cbc415ff317aba30a0308 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 22 Sep 2024 14:24:37 -0700 Subject: [PATCH 119/214] camerad: reduce internal ISP buffer count (#33619) --- system/camerad/cameras/spectra.cc | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index 6e967b60cc..6e855f08e8 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -711,8 +711,7 @@ void SpectraCamera::configISP() { LOGD("acquire isp dev"); // config ISP - // TODO: unclear where this 15 comes from - alloc_w_mmu_hdl(m->video0_fd, 15*ALIGNED_SIZE(buf0_size, buf0_alignment), (uint32_t*)&buf0_handle, buf0_alignment, + alloc_w_mmu_hdl(m->video0_fd, FRAME_BUF_COUNT*ALIGNED_SIZE(buf0_size, buf0_alignment), (uint32_t*)&buf0_handle, buf0_alignment, CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, m->device_iommu, m->cdm_iommu); config_isp(0, 0, 1, 0); From 62d044c794f8e000ab1410333e6ffe99a58bbabd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 22 Sep 2024 15:49:12 -0700 Subject: [PATCH 120/214] camerad: IFE config definitions (#33624) * camerad: more definitions for IFE config * comment --- system/camerad/cameras/spectra.cc | 18 +++++++++++------- system/camerad/cameras/spectra.h | 11 +++++++++-- 2 files changed, 20 insertions(+), 9 deletions(-) diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index 6e855f08e8..ef771a64b7 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -302,7 +302,7 @@ int SpectraCamera::sensors_init() { auto pkt = mm.alloc(size, &cam_packet_handle); pkt->num_cmd_buf = 2; pkt->kmd_cmd_buf_index = -1; - pkt->header.op_code = 0x1000000 | CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE; + pkt->header.op_code = CSLDeviceTypeImageSensor | CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE; pkt->header.size = size; struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; @@ -391,7 +391,11 @@ int SpectraCamera::sensors_init() { return ret; } -void SpectraCamera::config_isp(int io_mem_handle, int fence, int request_id, int buf0_idx) { +void SpectraCamera::config_ife(int io_mem_handle, int fence, int request_id, int buf0_idx) { + /* + Handles initial + per-frame IFE config. + IFE = Image Front End + */ int size = sizeof(struct cam_packet) + sizeof(struct cam_cmd_buf_desc)*2; if (io_mem_handle != 0) { size += sizeof(struct cam_buf_io_cfg); @@ -401,10 +405,10 @@ void SpectraCamera::config_isp(int io_mem_handle, int fence, int request_id, int auto pkt = mm.alloc(size, &cam_packet_handle); if (io_mem_handle != 0) { - pkt->header.op_code = 0xf000001; + pkt->header.op_code = CSLDeviceTypeIFE | OpcodesIFEUpdate; // 0xf000001 pkt->header.request_id = request_id; } else { - pkt->header.op_code = 0xf000000; + pkt->header.op_code = CSLDeviceTypeIFE | OpcodesIFEInitialConfig; // 0xf000000 pkt->header.request_id = 1; } pkt->header.size = size; @@ -595,7 +599,7 @@ void SpectraCamera::enqueue_buffer(int i, bool dp) { sensors_poke(request_id); // submit request to the ife - config_isp(buf_handle[i], sync_objs[i], request_id, i); + config_ife(buf_handle[i], sync_objs[i], request_id, i); } void SpectraCamera::camera_map_bufs() { @@ -710,11 +714,11 @@ void SpectraCamera::configISP() { isp_dev_handle = *isp_dev_handle_; LOGD("acquire isp dev"); - // config ISP + // config IFE alloc_w_mmu_hdl(m->video0_fd, FRAME_BUF_COUNT*ALIGNED_SIZE(buf0_size, buf0_alignment), (uint32_t*)&buf0_handle, buf0_alignment, CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, m->device_iommu, m->cdm_iommu); - config_isp(0, 0, 1, 0); + config_ife(0, 0, 1, 0); } void SpectraCamera::configCSIPHY() { diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h index e9e83ddb38..5796f47098 100644 --- a/system/camerad/cameras/spectra.h +++ b/system/camerad/cameras/spectra.h @@ -16,10 +16,17 @@ const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py -// For use with the Spectra 280 ISP in the SDM845 +// For use with the Titan 170 ISP in the SDM845 // https://github.com/commaai/agnos-kernel-sdm845 +// CSLDeviceType/CSLPacketOpcodesIFE from camx +// cam_packet_header.op_code = (device << 24) | (opcode); +#define CSLDeviceTypeImageSensor (0x1 << 24) +#define CSLDeviceTypeIFE (0xF << 24) +#define OpcodesIFEInitialConfig 0x0 +#define OpcodesIFEUpdate 0x1 + std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1); int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle); int device_control(int fd, int op_code, int session_handle, int dev_handle); @@ -69,7 +76,7 @@ public: void handle_camera_event(const cam_req_mgr_message *event_data); void camera_close(); void camera_map_bufs(); - void config_isp(int io_mem_handle, int fence, int request_id, int buf0_idx); + void config_ife(int io_mem_handle, int fence, int request_id, int buf0_idx); int clear_req_queue(); void enqueue_buffer(int i, bool dp); From 900c2c83bd446b49bae35548b7403195e3a8670a Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Mon, 23 Sep 2024 16:39:36 -0400 Subject: [PATCH 121/214] docs: car port info cleanup (#33630) * GC, now duplicated and out of place * typo fix * link to official video with better slides * expansion and cleanup --- docs/car-porting/what-is-a-car-port.md | 31 ++++++++++++++++++++------ selfdrive/car/README.md | 19 ---------------- 2 files changed, 24 insertions(+), 26 deletions(-) delete mode 100644 selfdrive/car/README.md diff --git a/docs/car-porting/what-is-a-car-port.md b/docs/car-porting/what-is-a-car-port.md index 622fe9e75e..55cce94da1 100644 --- a/docs/car-porting/what-is-a-car-port.md +++ b/docs/car-porting/what-is-a-car-port.md @@ -1,22 +1,39 @@ # What is a car port? -A car port enables openpilot support on a particular car. Each car model openpilot supports needs to be individually ported. All car ports live in `openpilot/selfdrive/car/car_specific.py` and `opendbc_repo/opendbc/car`. +A car port enables openpilot support on a particular car. Each car model openpilot supports needs to be individually ported. The complexity of a car port varies depending on many factors including: -The complexity of a car port varies depending on many factors including: * existing openpilot support for similar cars * architecture and APIs available in the car # Structure of a car port + +Virtually all car-specific code is contained in two other repositories: [opendbc](https://github.com/commaai/opendbc) and [panda](https://github.com/commaai/panda). + +## opendbc + +Each car brand is supported by a standard interface structure in `opendbc/car/[brand]`: + * `interface.py`: Interface for the car, defines the CarInterface class -* `carstate.py`: Reads CAN from car and builds openpilot CarState message -* `carcontroller.py`: Builds CAN messages to send to car +* `carstate.py`: Reads CAN messages from the car and builds openpilot CarState messages +* `carcontroller.py`: Control logic for executing openpilot CarControl actions on the car +* `[brand]can.py`: Composes CAN messages for carcontroller to send * `values.py`: Limits for actuation, general constants for cars, and supported car documentation -* `radar_interface.py`: Interface for parsing radar points from the car +* `radar_interface.py`: Interface for parsing radar points from the car, if applicable + +## panda + +* `board/safety/safety_[brand].h`: Brand-specific safety logic +* `tests/safety/test_[brand].py`: Brand-specific safety CI tests + +## openpilot + +For historical reasons, openpilot still contains a small amount of car-specific logic. This will eventually be migrated to opendbc or otherwise removed. +* `selfdrive/car/car_specific.py`: Brand-specific event logic -# Overiew +# Overview [Jason Young](https://github.com/jyoung8607) gave a talk at COMMA_CON with an overview of the car porting process. The talk is available on YouTube: -https://youtu.be/KcfzEHB6ms4?si=5szh1PX6TksOCKmM +https://www.youtube.com/watch?v=XxPS5TpTUnI diff --git a/selfdrive/car/README.md b/selfdrive/car/README.md deleted file mode 100644 index 2c49cf2051..0000000000 --- a/selfdrive/car/README.md +++ /dev/null @@ -1,19 +0,0 @@ -## Car port structure - -### interface.py -Generic interface to send and receive messages from CAN (controlsd uses this to communicate with car) - -### fingerprints.py -Fingerprints for matching to a specific car - -### carcontroller.py -Builds CAN messages to send to car - -##### carstate.py -Reads CAN from car and builds openpilot CarState message - -##### values.py -Limits for actuation, general constants for cars, and supported car documentation - -##### radar_interface.py -Interface for parsing radar points from the car From caa33c319358f9cc0ac58c3a2ec206d4b0fdd608 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 24 Sep 2024 04:48:24 +0800 Subject: [PATCH 122/214] ui: refactor hud updating and rendering into HudRenderer class (#33458) refactor hud updating and rendering into DriverMonitorRenderer class --- selfdrive/ui/SConscript | 2 +- selfdrive/ui/qt/onroad/annotated_camera.cc | 92 +---------------- selfdrive/ui/qt/onroad/annotated_camera.h | 15 +-- selfdrive/ui/qt/onroad/hud.cc | 109 +++++++++++++++++++++ selfdrive/ui/qt/onroad/hud.h | 23 +++++ selfdrive/ui/translations/main_ar.ts | 30 +++--- selfdrive/ui/translations/main_de.ts | 30 +++--- selfdrive/ui/translations/main_es.ts | 30 +++--- selfdrive/ui/translations/main_fr.ts | 30 +++--- selfdrive/ui/translations/main_ja.ts | 30 +++--- selfdrive/ui/translations/main_ko.ts | 30 +++--- selfdrive/ui/translations/main_pt-BR.ts | 30 +++--- selfdrive/ui/translations/main_th.ts | 30 +++--- selfdrive/ui/translations/main_tr.ts | 30 +++--- selfdrive/ui/translations/main_zh-CHS.ts | 30 +++--- selfdrive/ui/translations/main_zh-CHT.ts | 30 +++--- 16 files changed, 302 insertions(+), 269 deletions(-) create mode 100644 selfdrive/ui/qt/onroad/hud.cc create mode 100644 selfdrive/ui/qt/onroad/hud.h diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 1ea4d44dc4..da652f7bfd 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -31,7 +31,7 @@ qt_src = ["main.cc", "ui.cc", "qt/sidebar.cc", "qt/body.cc", "qt/offroad/software_settings.cc", "qt/offroad/onboarding.cc", "qt/offroad/driverview.cc", "qt/offroad/experimental_mode.cc", "qt/onroad/onroad_home.cc", "qt/onroad/annotated_camera.cc", - "qt/onroad/buttons.cc", "qt/onroad/alerts.cc", "qt/onroad/driver_monitoring.cc"] + "qt/onroad/buttons.cc", "qt/onroad/alerts.cc", "qt/onroad/driver_monitoring.cc", "qt/onroad/hud.cc"] # build translation files with open(File("translations/languages.json").abspath) as f: diff --git a/selfdrive/ui/qt/onroad/annotated_camera.cc b/selfdrive/ui/qt/onroad/annotated_camera.cc index c528501cbe..fd8ad19c2e 100644 --- a/selfdrive/ui/qt/onroad/annotated_camera.cc +++ b/selfdrive/ui/qt/onroad/annotated_camera.cc @@ -6,7 +6,6 @@ #include #include "common/swaglog.h" -#include "selfdrive/ui/qt/onroad/buttons.h" #include "selfdrive/ui/qt/util.h" // Window that shows camera view and variety of info drawn on top @@ -23,98 +22,11 @@ AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget *par } void AnnotatedCameraWidget::updateState(const UIState &s) { - const int SET_SPEED_NA = 255; - const SubMaster &sm = *(s.sm); - - const bool cs_alive = sm.alive("carState"); - const auto cs = sm["controlsState"].getControlsState(); - const auto car_state = sm["carState"].getCarState(); - - is_metric = s.scene.is_metric; - - // Handle older routes where vCruise was in controlsState - float v_cruise = car_state.getVCruiseCluster() == 0.0 ? cs.getVCruiseDEPRECATED() : car_state.getVCruiseCluster(); - setSpeed = cs_alive ? v_cruise : SET_SPEED_NA; - is_cruise_set = setSpeed > 0 && (int)setSpeed != SET_SPEED_NA; - if (is_cruise_set && !is_metric) { - setSpeed *= KM_TO_MILE; - } - - // Handle older routes where vEgoCluster is not set - v_ego_cluster_seen = v_ego_cluster_seen || car_state.getVEgoCluster() != 0.0; - float v_ego = v_ego_cluster_seen ? car_state.getVEgoCluster() : car_state.getVEgo(); - speed = cs_alive ? std::max(0.0, v_ego) : 0.0; - speed *= is_metric ? MS_TO_KPH : MS_TO_MPH; - - speedUnit = is_metric ? tr("km/h") : tr("mph"); - status = s.status; - // update engageability/experimental mode button experimental_btn->updateState(s); - - // update DM icon dmon.updateState(s); } -void AnnotatedCameraWidget::drawHud(QPainter &p) { - p.save(); - - // Header gradient - QLinearGradient bg(0, UI_HEADER_HEIGHT - (UI_HEADER_HEIGHT / 2.5), 0, UI_HEADER_HEIGHT); - bg.setColorAt(0, QColor::fromRgbF(0, 0, 0, 0.45)); - bg.setColorAt(1, QColor::fromRgbF(0, 0, 0, 0)); - p.fillRect(0, 0, width(), UI_HEADER_HEIGHT, bg); - - QString speedStr = QString::number(std::nearbyint(speed)); - QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed)) : "–"; - - // Draw outer box + border to contain set speed - const QSize default_size = {172, 204}; - QSize set_speed_size = default_size; - if (is_metric) set_speed_size.rwidth() = 200; - - QRect set_speed_rect(QPoint(60 + (default_size.width() - set_speed_size.width()) / 2, 45), set_speed_size); - p.setPen(QPen(whiteColor(75), 6)); - p.setBrush(blackColor(166)); - p.drawRoundedRect(set_speed_rect, 32, 32); - - // Draw MAX - QColor max_color = QColor(0x80, 0xd8, 0xa6, 0xff); - QColor set_speed_color = whiteColor(); - if (is_cruise_set) { - if (status == STATUS_DISENGAGED) { - max_color = whiteColor(); - } else if (status == STATUS_OVERRIDE) { - max_color = QColor(0x91, 0x9b, 0x95, 0xff); - } - } else { - max_color = QColor(0xa6, 0xa6, 0xa6, 0xff); - set_speed_color = QColor(0x72, 0x72, 0x72, 0xff); - } - p.setFont(InterFont(40, QFont::DemiBold)); - p.setPen(max_color); - p.drawText(set_speed_rect.adjusted(0, 27, 0, 0), Qt::AlignTop | Qt::AlignHCenter, tr("MAX")); - p.setFont(InterFont(90, QFont::Bold)); - p.setPen(set_speed_color); - p.drawText(set_speed_rect.adjusted(0, 77, 0, 0), Qt::AlignTop | Qt::AlignHCenter, setSpeedStr); - - // current speed - p.setFont(InterFont(176, QFont::Bold)); - drawText(p, rect().center().x(), 210, speedStr); - p.setFont(InterFont(66)); - drawText(p, rect().center().x(), 290, speedUnit, 200); - - p.restore(); -} - -void AnnotatedCameraWidget::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { - QRect real_rect = p.fontMetrics().boundingRect(text); - real_rect.moveCenter({x, y - real_rect.height() / 2}); - - p.setPen(QColor(0xff, 0xff, 0xff, alpha)); - p.drawText(real_rect.x(), real_rect.bottom(), text); -} - void AnnotatedCameraWidget::initializeGL() { CameraWidget::initializeGL(); qInfo() << "OpenGL version:" << QString((const char*)glGetString(GL_VERSION)); @@ -333,8 +245,8 @@ void AnnotatedCameraWidget::paintGL() { } dmon.draw(painter, rect()); - - drawHud(painter); + hud.updateState(*s); + hud.draw(painter, rect()); double cur_draw_t = millis_since_boot(); double dt = cur_draw_t - prev_draw_t; diff --git a/selfdrive/ui/qt/onroad/annotated_camera.h b/selfdrive/ui/qt/onroad/annotated_camera.h index 3820de5d86..324a6d7458 100644 --- a/selfdrive/ui/qt/onroad/annotated_camera.h +++ b/selfdrive/ui/qt/onroad/annotated_camera.h @@ -2,7 +2,7 @@ #include #include - +#include "selfdrive/ui/qt/onroad/hud.h" #include "selfdrive/ui/qt/onroad/buttons.h" #include "selfdrive/ui/qt/onroad/driver_monitoring.h" #include "selfdrive/ui/qt/widgets/cameraview.h" @@ -15,18 +15,10 @@ public: void updateState(const UIState &s); private: - void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255); - QVBoxLayout *main_layout; ExperimentalButton *experimental_btn; DriverMonitorRenderer dmon; - float speed; - QString speedUnit; - float setSpeed; - bool is_cruise_set = false; - bool is_metric = false; - bool v_ego_cluster_seen = false; - int status = STATUS_DISENGAGED; + HudRenderer hud; std::unique_ptr pm; int skip_frame_count = 0; @@ -39,10 +31,7 @@ protected: mat4 calcFrameMatrix() override; void drawLaneLines(QPainter &painter, const UIState *s); void drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd); - void drawHud(QPainter &p); inline QColor redColor(int alpha = 255) { return QColor(201, 34, 49, alpha); } - inline QColor whiteColor(int alpha = 255) { return QColor(255, 255, 255, alpha); } - inline QColor blackColor(int alpha = 255) { return QColor(0, 0, 0, alpha); } double prev_draw_t = 0; FirstOrderFilter fps_filter; diff --git a/selfdrive/ui/qt/onroad/hud.cc b/selfdrive/ui/qt/onroad/hud.cc new file mode 100644 index 0000000000..ebd95dab43 --- /dev/null +++ b/selfdrive/ui/qt/onroad/hud.cc @@ -0,0 +1,109 @@ +#include "selfdrive/ui/qt/onroad/hud.h" + +#include + +#include "selfdrive/ui/qt/util.h" + +constexpr int SET_SPEED_NA = 255; + +HudRenderer::HudRenderer() {} + +void HudRenderer::updateState(const UIState &s) { + is_metric = s.scene.is_metric; + status = s.status; + + const SubMaster &sm = *(s.sm); + if (!sm.alive("carState")) { + is_cruise_set = false; + set_speed = SET_SPEED_NA; + speed = 0.0; + return; + } + + const auto &controls_state = sm["controlsState"].getControlsState(); + const auto &car_state = sm["carState"].getCarState(); + + // Handle older routes where vCruiseCluster is not set + set_speed = car_state.getVCruiseCluster() == 0.0 ? controls_state.getVCruiseDEPRECATED() : car_state.getVCruiseCluster(); + is_cruise_set = set_speed > 0 && set_speed != SET_SPEED_NA; + + if (is_cruise_set && !is_metric) { + set_speed *= KM_TO_MILE; + } + + // Handle older routes where vEgoCluster is not set + v_ego_cluster_seen = v_ego_cluster_seen || car_state.getVEgoCluster() != 0.0; + float v_ego = v_ego_cluster_seen ? car_state.getVEgoCluster() : car_state.getVEgo(); + speed = std::max(0.0f, v_ego * (is_metric ? MS_TO_KPH : MS_TO_MPH)); +} + +void HudRenderer::draw(QPainter &p, const QRect &surface_rect) { + p.save(); + + // Draw header gradient + QLinearGradient bg(0, UI_HEADER_HEIGHT - (UI_HEADER_HEIGHT / 2.5), 0, UI_HEADER_HEIGHT); + bg.setColorAt(0, QColor::fromRgbF(0, 0, 0, 0.45)); + bg.setColorAt(1, QColor::fromRgbF(0, 0, 0, 0)); + p.fillRect(0, 0, surface_rect.width(), UI_HEADER_HEIGHT, bg); + + + drawSetSpeed(p, surface_rect); + drawCurrentSpeed(p, surface_rect); + + p.restore(); +} + +void HudRenderer::drawSetSpeed(QPainter &p, const QRect &surface_rect) { + // Draw outer box + border to contain set speed + const QSize default_size = {172, 204}; + QSize set_speed_size = is_metric ? QSize(200, 204) : default_size; + QRect set_speed_rect(QPoint(60 + (default_size.width() - set_speed_size.width()) / 2, 45), set_speed_size); + + // Draw set speed box + p.setPen(QPen(QColor(255, 255, 255, 75), 6)); + p.setBrush(QColor(0, 0, 0, 166)); + p.drawRoundedRect(set_speed_rect, 32, 32); + + // Colors based on status + QColor max_color = QColor(0xa6, 0xa6, 0xa6, 0xff); + QColor set_speed_color = QColor(0x72, 0x72, 0x72, 0xff); + if (is_cruise_set) { + if (status == STATUS_DISENGAGED) { + max_color = QColor(255, 255, 255); + } else if (status == STATUS_OVERRIDE) { + max_color = QColor(0x91, 0x9b, 0x95, 0xff); + } else { + max_color = QColor(0x80, 0xd8, 0xa6, 0xff); + set_speed_color = QColor(255, 255, 255); + } + } + + // Draw "MAX" text + p.setFont(InterFont(40, QFont::DemiBold)); + p.setPen(max_color); + p.drawText(set_speed_rect.adjusted(0, 27, 0, 0), Qt::AlignTop | Qt::AlignHCenter, tr("MAX")); + + // Draw set speed + QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(set_speed)) : "–"; + p.setFont(InterFont(90, QFont::Bold)); + p.setPen(set_speed_color); + p.drawText(set_speed_rect.adjusted(0, 77, 0, 0), Qt::AlignTop | Qt::AlignHCenter, setSpeedStr); +} + +void HudRenderer::drawCurrentSpeed(QPainter &p, const QRect &surface_rect) { + QString speedStr = QString::number(std::nearbyint(speed)); + + p.setFont(InterFont(176, QFont::Bold)); + drawText(p, surface_rect.center().x(), 210, speedStr); + + p.setFont(InterFont(66)); + drawText(p, surface_rect.center().x(), 290, is_metric ? tr("km/h") : tr("mph"), 200); +} + +void HudRenderer::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { + QRect real_rect = p.fontMetrics().boundingRect(text); + real_rect.moveCenter({x, y - real_rect.height() / 2}); + + p.setPen(QColor(0xff, 0xff, 0xff, alpha)); + p.drawText(real_rect.x(), real_rect.bottom(), text); +} diff --git a/selfdrive/ui/qt/onroad/hud.h b/selfdrive/ui/qt/onroad/hud.h new file mode 100644 index 0000000000..9151b23a4d --- /dev/null +++ b/selfdrive/ui/qt/onroad/hud.h @@ -0,0 +1,23 @@ +#pragma once + +#include +#include "selfdrive/ui/ui.h" + +class HudRenderer : public QObject { +public: + HudRenderer(); + void updateState(const UIState &s); + void draw(QPainter &p, const QRect &surface_rect); + +private: + void drawSetSpeed(QPainter &p, const QRect &surface_rect); + void drawCurrentSpeed(QPainter &p, const QRect &surface_rect); + void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255); + + float speed = 0; + float set_speed = 0; + bool is_cruise_set = false; + bool is_metric = false; + bool v_ego_cluster_seen = false; + int status = STATUS_DISENGAGED; +}; diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index d73a5771fd..5f254e9cd4 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -87,21 +87,6 @@ من أجل "%1"
- - AnnotatedCameraWidget - - km/h - كم/س - - - mph - ميل/س - - - MAX - MAX - - ConfirmationDialog @@ -289,6 +274,21 @@ تشغيل وضع الراحة + + HudRenderer + + km/h + كم/س + + + mph + ميل/س + + + MAX + MAX + + InputDialog diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index 8ad55be666..4f5997228a 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -87,21 +87,6 @@ für "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - MAX - - ConfirmationDialog @@ -289,6 +274,21 @@ ENTSPANNTER MODUS AN + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + MAX + + InputDialog diff --git a/selfdrive/ui/translations/main_es.ts b/selfdrive/ui/translations/main_es.ts index 510a2d98e0..fa50f33f15 100644 --- a/selfdrive/ui/translations/main_es.ts +++ b/selfdrive/ui/translations/main_es.ts @@ -87,21 +87,6 @@ para "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - MAX - - ConfirmationDialog @@ -289,6 +274,21 @@ MODO CHILL + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + MAX + + InputDialog diff --git a/selfdrive/ui/translations/main_fr.ts b/selfdrive/ui/translations/main_fr.ts index 80cca809e0..566ed32f11 100644 --- a/selfdrive/ui/translations/main_fr.ts +++ b/selfdrive/ui/translations/main_fr.ts @@ -87,21 +87,6 @@ pour "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mi/h - - - MAX - MAX - - ConfirmationDialog @@ -289,6 +274,21 @@ MODE DÉTENTE ACTIVÉ + + HudRenderer + + km/h + km/h + + + mph + mi/h + + + MAX + MAX + + InputDialog diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 2b8f7d2429..90c8aba00b 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -87,21 +87,6 @@ ネットワーク名:%1 - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - 最高速度 - - ConfirmationDialog @@ -289,6 +274,21 @@ チルモード + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + 最高速度 + + InputDialog diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 935342d546..6d01b1289f 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -87,21 +87,6 @@ "%1"에 접속하려면 비밀번호가 필요합니다 - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - MAX - - ConfirmationDialog @@ -289,6 +274,21 @@ 안정 모드 사용 + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + MAX + + InputDialog diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 1c1ebff15b..ba50e97141 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -87,21 +87,6 @@ para "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - LIMITE - - ConfirmationDialog @@ -289,6 +274,21 @@ MODO CHILL ON + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + LIMITE + + InputDialog diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index 06841222cc..6d89c049b1 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -87,21 +87,6 @@ สำหรับ "%1" - - AnnotatedCameraWidget - - km/h - กม./ชม. - - - mph - ไมล์/ชม. - - - MAX - สูงสุด - - ConfirmationDialog @@ -289,6 +274,21 @@ คุณกำลังใช้โหมดชิล + + HudRenderer + + km/h + กม./ชม. + + + mph + ไมล์/ชม. + + + MAX + สูงสุด + + InputDialog diff --git a/selfdrive/ui/translations/main_tr.ts b/selfdrive/ui/translations/main_tr.ts index f934b9d9cc..663ad8c281 100644 --- a/selfdrive/ui/translations/main_tr.ts +++ b/selfdrive/ui/translations/main_tr.ts @@ -87,21 +87,6 @@ için "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - MAX - - ConfirmationDialog @@ -289,6 +274,21 @@ + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + MAX + + InputDialog diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index d900202515..494b1bc170 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -87,21 +87,6 @@ 网络名称:"%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - 最高定速 - - ConfirmationDialog @@ -289,6 +274,21 @@ 轻松模式运行 + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + 最高定速 + + InputDialog diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 91b1cf3866..7ce6ac6d20 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -87,21 +87,6 @@ 給 "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - 最高 - - ConfirmationDialog @@ -289,6 +274,21 @@ 輕鬆模式 ON + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + 最高 + + InputDialog From e8bea2c78ffa92685ece511e9b554122aaf1a79d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Mon, 23 Sep 2024 14:26:28 -0700 Subject: [PATCH 123/214] Tomb Raider Model (#33629) * 69acff08-5383-4103-beea-822f0d228c76/160 * 53f39907-4763-4d19-ba26-e757527c2b61/200 * 21afb89f-1397-4652-b423-abc2da32417a/200 * 21afb89f-1397-4652-b423-abc2da32417a/400 * 53f39907-4763-4d19-ba26-e757527c2b61/400 * 3fb967fd-16a8-4569-ba57-359e54deeab3/395 * Try other policy again * 3fb967fd-16a8-4569-ba57-359e54deeab3/400 * 0136cabf-539a-4a43-bc7f-06c3654a493c/4400 * 473c0686-1ac9-4c05-9b0b-d1f1afdb6cc3/400 * 83b7993d-51a9-4e3f-904e-3fcd5763c231/400 * 021566c7-cff3-431d-8da2-17a96c888c5f/400 * Fix bugs * Update longitudinal_planner.py * Update fill_model_msg.py * 8be6b59d-4449-42fd-b8e0-93c48387070f/400 * f670a748-3591-4489-a0b3-215118ddad01/400 * 790a2950-c713-4eec-838b-4f55f4fe0ccb/400 * Update model ref * Plans start at ego * Update ref --- selfdrive/controls/lib/drive_helpers.py | 4 ++-- selfdrive/controls/radard.py | 4 ++-- selfdrive/modeld/fill_model_msg.py | 7 ------- selfdrive/modeld/models/supercombo.onnx | 4 ++-- selfdrive/modeld/parse_model_outputs.py | 1 - selfdrive/test/longitudinal_maneuvers/plant.py | 1 + selfdrive/test/process_replay/model_replay_ref_commit | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 8 files changed, 9 insertions(+), 16 deletions(-) diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 64cbf473d6..369aeaf984 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -22,7 +22,7 @@ def clip_curvature(v_ego, prev_curvature, new_curvature): def get_speed_error(modelV2: log.ModelDataV2, v_ego: float) -> float: # ToDo: Try relative error, and absolute speed - if len(modelV2.temporalPose.trans): - vel_err = clip(modelV2.temporalPose.trans[0] - v_ego, -MAX_VEL_ERR, MAX_VEL_ERR) + if len(modelV2.velocity.x): + vel_err = clip(modelV2.velocity.x[0] - v_ego, -MAX_VEL_ERR, MAX_VEL_ERR) return float(vel_err) return 0.0 diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index f577025fa4..a5987b4bcc 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -243,8 +243,8 @@ class RadarD: self.radar_state.radarErrors = list(rr.errors) self.radar_state.carStateMonoTime = sm.logMonoTime['carState'] - if len(sm['modelV2'].temporalPose.trans): - model_v_ego = sm['modelV2'].temporalPose.trans[0] + if len(sm['modelV2'].velocity.x): + model_v_ego = sm['modelV2'].velocity.x[0] else: model_v_ego = self.v_ego leads_v3 = sm['modelV2'].leadsV3 diff --git a/selfdrive/modeld/fill_model_msg.py b/selfdrive/modeld/fill_model_msg.py index 9cdd7e4c52..18dd9c7bac 100644 --- a/selfdrive/modeld/fill_model_msg.py +++ b/selfdrive/modeld/fill_model_msg.py @@ -168,13 +168,6 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D (publish_state.prev_brake_3ms2_probs > ModelConstants.FCW_THRESHOLDS_3MS2).all() meta.hardBrakePredicted = hard_brake_predicted.item() - # temporal pose - temporal_pose = modelV2.temporalPose - temporal_pose.trans = net_output_data['sim_pose'][0,:3].tolist() - temporal_pose.transStd = net_output_data['sim_pose_stds'][0,:3].tolist() - temporal_pose.rot = net_output_data['sim_pose'][0,3:].tolist() - temporal_pose.rotStd = net_output_data['sim_pose_stds'][0,3:].tolist() - # confidence if vipc_frame_id % (2*ModelConstants.MODEL_FREQ) == 0: # any disengage prob diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 2e1a60a23e..111cb76dbb 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:39786068cae1ed8c0dc34ef80c281dfcc67ed18a50e06b90765c49bcfdbf7db4 -size 51453312 +oid sha256:d42319e42e8ba1a818c845ee0c687ece6afd98e59fef142895be33dd230974c2 +size 62481231 diff --git a/selfdrive/modeld/parse_model_outputs.py b/selfdrive/modeld/parse_model_outputs.py index 03d03c5e1c..d57b6eab3f 100644 --- a/selfdrive/modeld/parse_model_outputs.py +++ b/selfdrive/modeld/parse_model_outputs.py @@ -87,7 +87,6 @@ class Parser: self.parse_mdn('road_edges', outs, in_N=0, out_N=0, out_shape=(ModelConstants.NUM_ROAD_EDGES,ModelConstants.IDX_N,ModelConstants.LANE_LINES_WIDTH)) self.parse_mdn('pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,)) self.parse_mdn('road_transform', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,)) - self.parse_mdn('sim_pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,)) self.parse_mdn('wide_from_device_euler', outs, in_N=0, out_N=0, out_shape=(ModelConstants.WIDE_FROM_DEVICE_WIDTH,)) self.parse_mdn('lead', outs, in_N=ModelConstants.LEAD_MHP_N, out_N=ModelConstants.LEAD_MHP_SELECTION, out_shape=(ModelConstants.LEAD_TRAJ_LEN,ModelConstants.LEAD_WIDTH)) diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index 85e2ddf8df..21f2b3b57f 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -107,6 +107,7 @@ class Plant: model.modelV2.position = position velocity = log.XYZTData.new_message() velocity.x = [float(x) for x in (self.speed + 0.5) * np.ones_like(ModelConstants.T_IDXS)] + velocity.x[0] = float(self.speed) # always start at current speed model.modelV2.velocity = velocity acceleration = log.XYZTData.new_message() acceleration.x = [float(x) for x in np.zeros_like(ModelConstants.T_IDXS)] diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 66971ebde1..315a15975b 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -32fe8cf4a0daa8d10a689c9ae2e51a879151c87c +f0504b66f3f736b5bea39cc01e1a073e3be95659 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 04b3c0a6fd..e154284e3d 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -96c2e2ab2e3a11476f1207c531893cc8e45d2b3c +d8a02c23f530dd236553b47ff7f0355929fe15fc From 35581d31ebf4ffa228ab100decc393b446a5e3ce Mon Sep 17 00:00:00 2001 From: Mauricio Alvarez Leon <65101411+BBBmau@users.noreply.github.com> Date: Mon, 23 Sep 2024 15:32:08 -0700 Subject: [PATCH 124/214] update bounties link in `CONTRIBUTING.md` (#33631) --- docs/CONTRIBUTING.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/CONTRIBUTING.md b/docs/CONTRIBUTING.md index c66b20c88e..d455fa6fd3 100644 --- a/docs/CONTRIBUTING.md +++ b/docs/CONTRIBUTING.md @@ -39,7 +39,7 @@ All of these are examples of good PRs: ### First contribution -[Bounties](https://comma.ai/bounties) are the best place to get started. +[Projects / openpilot bounties](https://github.com/orgs/commaai/projects/26/views/1?pane=info) is the best place to get started and goes in-depth on what's expected when working on a bounty. There's lot of bounties that don't require a comma 3/3X or a car. ## Pull Requests From 23b1f2d646cf5e9dcdded7a264b69399d9e39867 Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Mon, 23 Sep 2024 18:16:14 -0700 Subject: [PATCH 125/214] fix set speed color (#33634) color --- selfdrive/ui/qt/onroad/hud.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/onroad/hud.cc b/selfdrive/ui/qt/onroad/hud.cc index ebd95dab43..50b563b228 100644 --- a/selfdrive/ui/qt/onroad/hud.cc +++ b/selfdrive/ui/qt/onroad/hud.cc @@ -68,13 +68,13 @@ void HudRenderer::drawSetSpeed(QPainter &p, const QRect &surface_rect) { QColor max_color = QColor(0xa6, 0xa6, 0xa6, 0xff); QColor set_speed_color = QColor(0x72, 0x72, 0x72, 0xff); if (is_cruise_set) { + set_speed_color = QColor(255, 255, 255); if (status == STATUS_DISENGAGED) { max_color = QColor(255, 255, 255); } else if (status == STATUS_OVERRIDE) { max_color = QColor(0x91, 0x9b, 0x95, 0xff); } else { max_color = QColor(0x80, 0xd8, 0xa6, 0xff); - set_speed_color = QColor(255, 255, 255); } } From 73013bc6d62ffe4a3553b0ae0606e254b12a3aa0 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 23 Sep 2024 18:39:42 -0700 Subject: [PATCH 126/214] Lexus ES TSS2: reduce braking overshoot (#33628) bump --- opendbc_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc_repo b/opendbc_repo index 0771622149..0b7648ad2c 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 07716221498c17e1f8fd4252868fb6250e23141d +Subproject commit 0b7648ad2cb048b5f55a338dbd26cada01671124 From 251e2e94002494dbcad109245339991940779d36 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Mon, 23 Sep 2024 19:06:52 -0700 Subject: [PATCH 127/214] Clip sigmoid overlfow (#33635) * No more C sigmoid * Clipping * Need to cast to float * Update ref * Clip * Model refg --- selfdrive/modeld/dmonitoringmodeld.py | 24 +++++++++---------- selfdrive/modeld/models/commonmodel.cc | 6 +---- selfdrive/modeld/models/commonmodel.h | 2 -- selfdrive/modeld/models/commonmodel.pxd | 2 -- selfdrive/modeld/models/commonmodel_pyx.pyx | 4 +--- selfdrive/modeld/parse_model_outputs.py | 4 +++- .../process_replay/model_replay_ref_commit | 2 +- 7 files changed, 18 insertions(+), 26 deletions(-) diff --git a/selfdrive/modeld/dmonitoringmodeld.py b/selfdrive/modeld/dmonitoringmodeld.py index a388bf089c..0187184a7a 100755 --- a/selfdrive/modeld/dmonitoringmodeld.py +++ b/selfdrive/modeld/dmonitoringmodeld.py @@ -14,7 +14,7 @@ from openpilot.common.swaglog import cloudlog from openpilot.common.params import Params from openpilot.common.realtime import set_realtime_priority from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime -from openpilot.selfdrive.modeld.models.commonmodel_pyx import sigmoid +from openpilot.selfdrive.modeld.parse_model_outputs import sigmoid CALIB_LEN = 3 REG_SCALE = 0.25 @@ -88,15 +88,15 @@ def fill_driver_state(msg, ds_result: DriverStateResult): msg.faceOrientationStd = [math.exp(x) for x in ds_result.face_orientation_std] msg.facePosition = [x * REG_SCALE for x in ds_result.face_position[:2]] msg.facePositionStd = [math.exp(x) for x in ds_result.face_position_std[:2]] - msg.faceProb = sigmoid(ds_result.face_prob) - msg.leftEyeProb = sigmoid(ds_result.left_eye_prob) - msg.rightEyeProb = sigmoid(ds_result.right_eye_prob) - msg.leftBlinkProb = sigmoid(ds_result.left_blink_prob) - msg.rightBlinkProb = sigmoid(ds_result.right_blink_prob) - msg.sunglassesProb = sigmoid(ds_result.sunglasses_prob) - msg.occludedProb = sigmoid(ds_result.occluded_prob) - msg.readyProb = [sigmoid(x) for x in ds_result.ready_prob] - msg.notReadyProb = [sigmoid(x) for x in ds_result.not_ready_prob] + msg.faceProb = float(sigmoid(ds_result.face_prob)) + msg.leftEyeProb = float(sigmoid(ds_result.left_eye_prob)) + msg.rightEyeProb = float(sigmoid(ds_result.right_eye_prob)) + msg.leftBlinkProb = float(sigmoid(ds_result.left_blink_prob)) + msg.rightBlinkProb = float(sigmoid(ds_result.right_blink_prob)) + msg.sunglassesProb = float(sigmoid(ds_result.sunglasses_prob)) + msg.occludedProb = float(sigmoid(ds_result.occluded_prob)) + msg.readyProb = [float(sigmoid(x)) for x in ds_result.ready_prob] + msg.notReadyProb = [float(sigmoid(x)) for x in ds_result.not_ready_prob] def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: int, execution_time: float, dsp_execution_time: float): model_result = ctypes.cast(model_output.ctypes.data, ctypes.POINTER(DMonitoringModelResult)).contents @@ -105,8 +105,8 @@ def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: ds.frameId = frame_id ds.modelExecutionTime = execution_time ds.dspExecutionTime = dsp_execution_time - ds.poorVisionProb = sigmoid(model_result.poor_vision_prob) - ds.wheelOnRightProb = sigmoid(model_result.wheel_on_right_prob) + ds.poorVisionProb = float(sigmoid(model_result.poor_vision_prob)) + ds.wheelOnRightProb = float(sigmoid(model_result.wheel_on_right_prob)) ds.rawPredictions = model_output.tobytes() if SEND_RAW_PRED else b'' fill_driver_state(ds.leftDriverData, model_result.driver_state_lhd) fill_driver_state(ds.rightDriverData, model_result.driver_state_rhd) diff --git a/selfdrive/modeld/models/commonmodel.cc b/selfdrive/modeld/models/commonmodel.cc index 523ce00e43..57c14dfa88 100644 --- a/selfdrive/modeld/models/commonmodel.cc +++ b/selfdrive/modeld/models/commonmodel.cc @@ -47,8 +47,4 @@ ModelFrame::~ModelFrame() { CL_CHECK(clReleaseMemObject(u_cl)); CL_CHECK(clReleaseMemObject(y_cl)); CL_CHECK(clReleaseCommandQueue(q)); -} - -float sigmoid(float input) { - return 1 / (1 + expf(-input)); -} +} \ No newline at end of file diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h index 2cf79094a6..0b5d87fd6c 100644 --- a/selfdrive/modeld/models/commonmodel.h +++ b/selfdrive/modeld/models/commonmodel.h @@ -16,8 +16,6 @@ #include "selfdrive/modeld/transforms/loadyuv.h" #include "selfdrive/modeld/transforms/transform.h" -float sigmoid(float input); - class ModelFrame { public: ModelFrame(cl_device_id device_id, cl_context context); diff --git a/selfdrive/modeld/models/commonmodel.pxd b/selfdrive/modeld/models/commonmodel.pxd index 7c3eb0b3d7..f37014219d 100644 --- a/selfdrive/modeld/models/commonmodel.pxd +++ b/selfdrive/modeld/models/commonmodel.pxd @@ -12,8 +12,6 @@ cdef extern from "common/clutil.h": cl_context cl_create_context(cl_device_id) cdef extern from "selfdrive/modeld/models/commonmodel.h": - float sigmoid(float) - cppclass ModelFrame: int buf_size ModelFrame(cl_device_id, cl_context) diff --git a/selfdrive/modeld/models/commonmodel_pyx.pyx b/selfdrive/modeld/models/commonmodel_pyx.pyx index ecbe644e09..46ac575cc2 100644 --- a/selfdrive/modeld/models/commonmodel_pyx.pyx +++ b/selfdrive/modeld/models/commonmodel_pyx.pyx @@ -8,10 +8,8 @@ from libc.string cimport memcpy from msgq.visionipc.visionipc cimport cl_mem from msgq.visionipc.visionipc_pyx cimport VisionBuf, CLContext as BaseCLContext from .commonmodel cimport CL_DEVICE_TYPE_DEFAULT, cl_get_device_id, cl_create_context -from .commonmodel cimport mat3, sigmoid as cppSigmoid, ModelFrame as cppModelFrame +from .commonmodel cimport mat3, ModelFrame as cppModelFrame -def sigmoid(x): - return cppSigmoid(x) cdef class CLContext(BaseCLContext): def __cinit__(self): diff --git a/selfdrive/modeld/parse_model_outputs.py b/selfdrive/modeld/parse_model_outputs.py index d57b6eab3f..61dfca0a4f 100644 --- a/selfdrive/modeld/parse_model_outputs.py +++ b/selfdrive/modeld/parse_model_outputs.py @@ -2,7 +2,9 @@ import numpy as np from openpilot.selfdrive.modeld.constants import ModelConstants def sigmoid(x): - return 1. / (1. + np.exp(-x)) + # -11 is around 10**14, more causes float16 overflow + clipped_x = np.clip(x, -11, np.inf) + return 1. / (1. + np.exp(-clipped_x)) def softmax(x, axis=-1): x -= np.max(x, axis=axis, keepdims=True) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 315a15975b..de6f6027c4 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -f0504b66f3f736b5bea39cc01e1a073e3be95659 +9d4d653d8cc361fe2ba53f74fd8fcfe1f1d559ed From d82c4509ea6f6e85da04bd8ba9175c35fb91caf0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Kacper=20R=C4=85czy?= Date: Mon, 23 Sep 2024 20:47:28 -0700 Subject: [PATCH 128/214] joystickd: split into joystickd and joystick_control (#33632) * Split joystickd into joystickd and joystick_control * Update process config * Undeprecate testJoystick * Static analysis fixes * Mark as +x * Update README * Add testJoystick back to services * reset if testJoystick not received * Fix quotes * Remove self * Add a send thread instead * Add joystick_control into process config * Add main * Add additional condition * Fix imports --- cereal/log.capnp | 2 +- cereal/services.py | 1 + system/manager/process_config.py | 12 +- system/webrtc/tests/test_stream_session.py | 2 +- tools/joystick/README.md | 20 +-- tools/joystick/joystick_control.py | 147 +++++++++++++++++++++ tools/joystick/joystickd.py | 141 +++----------------- 7 files changed, 186 insertions(+), 139 deletions(-) create mode 100755 tools/joystick/joystick_control.py diff --git a/cereal/log.capnp b/cereal/log.capnp index 87be2ceb99..c955cbf154 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -2413,6 +2413,7 @@ struct Event { uiDebug @102 :UIDebug; # *********** debug *********** + testJoystick @52 :Joystick; roadEncodeData @86 :EncodeData; driverEncodeData @87 :EncodeData; wideRoadEncodeData @88 :EncodeData; @@ -2482,6 +2483,5 @@ struct Event { uiPlanDEPRECATED @106 :UiPlan; liveLocationKalmanDEPRECATED @72 :LiveLocationKalman; liveTracksDEPRECATED @16 :List(LiveTracksDEPRECATED); - testJoystickDEPRECATED @52 :Joystick; } } diff --git a/cereal/services.py b/cereal/services.py index e56f8f0c1b..771338f507 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -75,6 +75,7 @@ _services: dict[str, tuple] = { # debug "uiDebug": (True, 0., 1), + "testJoystick": (True, 0.), "alertDebug": (True, 20., 5), "roadEncodeData": (False, 20.), "driverEncodeData": (False, 20.), diff --git a/system/manager/process_config.py b/system/manager/process_config.py index 538c55813b..bdb549fa41 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -1,4 +1,5 @@ import os +import operator from cereal import car from openpilot.common.params import Params @@ -53,6 +54,12 @@ def only_onroad(started: bool, params, CP: car.CarParams) -> bool: def only_offroad(started, params, CP: car.CarParams) -> bool: return not started +def or_(*fns): + return lambda *args: operator.or_(*(fn(*args) for fn in fns)) + +def and_(*fns): + return lambda *args: operator.and_(*(fn(*args) for fn in fns)) + procs = [ DaemonProcess("manage_athenad", "system.athena.manage_athenad", "AthenadPid"), @@ -75,8 +82,8 @@ procs = [ NativeProcess("pandad", "selfdrive/pandad", ["./pandad"], always_run, enabled=False), PythonProcess("calibrationd", "selfdrive.locationd.calibrationd", only_onroad), PythonProcess("torqued", "selfdrive.locationd.torqued", only_onroad), - PythonProcess("controlsd", "selfdrive.controls.controlsd", not_joystick), - PythonProcess("joystickd", "tools.joystick.joystickd", joystick), + PythonProcess("controlsd", "selfdrive.controls.controlsd", and_(not_joystick, iscar)), + PythonProcess("joystickd", "tools.joystick.joystickd", or_(joystick, notcar)), PythonProcess("selfdrived", "selfdrive.selfdrived.selfdrived", only_onroad), PythonProcess("card", "selfdrive.car.card", only_onroad), PythonProcess("deleter", "system.loggerd.deleter", always_run), @@ -100,6 +107,7 @@ procs = [ NativeProcess("bridge", "cereal/messaging", ["./bridge"], notcar), PythonProcess("webrtcd", "system.webrtc.webrtcd", notcar), PythonProcess("webjoystick", "tools.bodyteleop.web", notcar), + PythonProcess("joystick", "tools.joystick.joystick_control", and_(joystick, iscar)), ] managed_processes = {p.name: p for p in procs} diff --git a/system/webrtc/tests/test_stream_session.py b/system/webrtc/tests/test_stream_session.py index 6683c65804..113fa5e7e6 100644 --- a/system/webrtc/tests/test_stream_session.py +++ b/system/webrtc/tests/test_stream_session.py @@ -50,7 +50,7 @@ class TestStreamSession: tested_msgs = [ {"type": "customReservedRawData0", "data": "test"}, # primitive {"type": "can", "data": [{"address": 0, "dat": "", "src": 0}]}, # list - {"type": "testJoystickDEPRECATED", "data": {"axes": [0, 0], "buttons": [False]}}, # dict + {"type": "testJoystick", "data": {"axes": [0, 0], "buttons": [False]}}, # dict ] mocked_pubmaster = mocker.MagicMock(spec=messaging.PubMaster) diff --git a/tools/joystick/README.md b/tools/joystick/README.md index aea93dad53..eb67060ca8 100644 --- a/tools/joystick/README.md +++ b/tools/joystick/README.md @@ -2,33 +2,33 @@ **Hardware needed**: device running openpilot, laptop, joystick (optional) -With joystickd, you can connect your laptop to your comma device over the network and debug controls using a joystick or keyboard. -joystickd uses [inputs](https://pypi.org/project/inputs) which supports many common gamepads and joysticks. +With joystick_control, you can connect your laptop to your comma device over the network and debug controls using a joystick or keyboard. +joystick_control uses [inputs](https://pypi.org/project/inputs) which supports many common gamepads and joysticks. ## Usage -The car must be off, and openpilot must be offroad before starting `joystickd`. +The car must be off, and openpilot must be offroad before starting `joystick_control`. ### Using a keyboard -SSH into your comma device and start joystickd with the following command: +SSH into your comma device and start joystick_control with the following command: ```shell -tools/joystick/joystickd.py --keyboard +tools/joystick/joystick_control.py --keyboard ``` The available buttons and axes will print showing their key mappings. In general, the WASD keys control gas and brakes and steering torque in 5% increments. ### Joystick on your comma three -Plug the joystick into your comma three aux USB-C port. Then, SSH into the device and start `joystickd.py`. +Plug the joystick into your comma three aux USB-C port. Then, SSH into the device and start `joystick_control.py`. ### Joystick on your laptop -In order to use a joystick over the network, we need to run joystickd locally from your laptop and have it send `testJoystick` packets over the network to the comma device. +In order to use a joystick over the network, we need to run joystick_control locally from your laptop and have it send `testJoystick` packets over the network to the comma device. 1. Connect a joystick to your PC. -2. Connect your laptop to your comma device's hotspot and open a new SSH shell. Since joystickd is being run on your laptop, we need to write a parameter to let controlsd know to start in joystick debug mode: +2. Connect your laptop to your comma device's hotspot and open a new SSH shell. Since joystick_control is being run on your laptop, we need to write a parameter to let controlsd know to start in joystick debug mode: ```shell # on your comma device echo -n "1" > /data/params/d/JoystickDebugMode @@ -38,11 +38,11 @@ In order to use a joystick over the network, we need to run joystickd locally fr # on your comma device cereal/messaging/bridge {LAPTOP_IP} testJoystick ``` -4. Start joystickd on your laptop in ZMQ mode. +4. Start joystick_control on your laptop in ZMQ mode. ```shell # on your laptop export ZMQ=1 - tools/joystick/joystickd.py + tools/joystick/joystick_control.py ``` --- diff --git a/tools/joystick/joystick_control.py b/tools/joystick/joystick_control.py new file mode 100755 index 0000000000..d31546e058 --- /dev/null +++ b/tools/joystick/joystick_control.py @@ -0,0 +1,147 @@ +#!/usr/bin/env python3 +import os +import argparse +import threading +from inputs import UnpluggedError, get_gamepad + +from cereal import messaging +from openpilot.common.numpy_fast import interp, clip +from openpilot.common.params import Params +from openpilot.common.realtime import Ratekeeper +from openpilot.system.hardware import HARDWARE +from openpilot.tools.lib.kbhit import KBHit + +EXPO = 0.4 + + +class Keyboard: + def __init__(self): + self.kb = KBHit() + self.axis_increment = 0.05 # 5% of full actuation each key press + self.axes_map = {'w': 'gb', 's': 'gb', + 'a': 'steer', 'd': 'steer'} + self.axes_values = {'gb': 0., 'steer': 0.} + self.axes_order = ['gb', 'steer'] + self.cancel = False + + def update(self): + key = self.kb.getch().lower() + self.cancel = False + if key == 'r': + self.axes_values = {ax: 0. for ax in self.axes_values} + elif key == 'c': + self.cancel = True + elif key in self.axes_map: + axis = self.axes_map[key] + incr = self.axis_increment if key in ['w', 'a'] else -self.axis_increment + self.axes_values[axis] = clip(self.axes_values[axis] + incr, -1, 1) + else: + return False + return True + + +class Joystick: + def __init__(self): + # This class supports a PlayStation 5 DualSense controller on the comma 3X + # TODO: find a way to get this from API or detect gamepad/PC, perhaps "inputs" doesn't support it + self.cancel_button = 'BTN_NORTH' # BTN_NORTH=X/triangle + if HARDWARE.get_device_type() == 'pc': + accel_axis = 'ABS_Z' + steer_axis = 'ABS_RX' + # TODO: once the longcontrol API is finalized, we can replace this with outputting gas/brake and steering + self.flip_map = {'ABS_RZ': accel_axis} + else: + accel_axis = 'ABS_RX' + steer_axis = 'ABS_Z' + self.flip_map = {'ABS_RY': accel_axis} + + self.min_axis_value = {accel_axis: 0., steer_axis: 0.} + self.max_axis_value = {accel_axis: 255., steer_axis: 255.} + self.axes_values = {accel_axis: 0., steer_axis: 0.} + self.axes_order = [accel_axis, steer_axis] + self.cancel = False + + def update(self): + try: + joystick_event = get_gamepad()[0] + except (OSError, UnpluggedError): + self.axes_values = {ax: 0. for ax in self.axes_values} + return False + + event = (joystick_event.code, joystick_event.state) + + # flip left trigger to negative accel + if event[0] in self.flip_map: + event = (self.flip_map[event[0]], -event[1]) + + if event[0] == self.cancel_button: + if event[1] == 1: + self.cancel = True + elif event[1] == 0: # state 0 is falling edge + self.cancel = False + elif event[0] in self.axes_values: + self.max_axis_value[event[0]] = max(event[1], self.max_axis_value[event[0]]) + self.min_axis_value[event[0]] = min(event[1], self.min_axis_value[event[0]]) + + norm = -interp(event[1], [self.min_axis_value[event[0]], self.max_axis_value[event[0]]], [-1., 1.]) + norm = norm if abs(norm) > 0.03 else 0. # center can be noisy, deadzone of 3% + self.axes_values[event[0]] = EXPO * norm ** 3 + (1 - EXPO) * norm # less action near center for fine control + else: + return False + return True + + +def send_thread(joystick): + pm = messaging.PubMaster(['testJoystick']) + + rk = Ratekeeper(100, print_delay_threshold=None) + + while True: + if rk.frame % 20 == 0: + print('\n' + ', '.join(f'{name}: {round(v, 3)}' for name, v in joystick.axes_values.items())) + + joystick_msg = messaging.new_message('testJoystick') + joystick_msg.valid = True + joystick_msg.testJoystick.axes = [joystick.axes_values[ax] for ax in joystick.axes_order] + + pm.send('testJoystick', joystick_msg) + + rk.keep_time() + + +def joystick_control_thread(joystick): + Params().put_bool('JoystickDebugMode', True) + threading.Thread(target=send_thread, args=(joystick,), daemon=True).start() + while True: + joystick.update() + + +def main(): + joystick_control_thread(Joystick()) + + +if __name__ == '__main__': + parser = argparse.ArgumentParser(description='Publishes events from your joystick to control your car.\n' + + 'openpilot must be offroad before starting joystick_control. This tool supports ' + + 'a PlayStation 5 DualSense controller on the comma 3X.', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('--keyboard', action='store_true', help='Use your keyboard instead of a joystick') + args = parser.parse_args() + + if not Params().get_bool("IsOffroad") and "ZMQ" not in os.environ: + print("The car must be off before running joystick_control.") + exit() + + print() + if args.keyboard: + print('Gas/brake control: `W` and `S` keys') + print('Steering control: `A` and `D` keys') + print('Buttons') + print('- `R`: Resets axes') + print('- `C`: Cancel cruise control') + else: + print('Using joystick, make sure to run cereal/messaging/bridge on your device if running over the network!') + print('If not running on a comma device, the mapping may need to be adjusted.') + + joystick = Keyboard() if args.keyboard else Joystick() + joystick_control_thread(joystick) diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index f39dec7d4b..f8c000c259 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -1,117 +1,30 @@ #!/usr/bin/env python3 -import os -import argparse -import threading -from inputs import UnpluggedError, get_gamepad + import math from cereal import messaging, car +from openpilot.common.numpy_fast import clip from openpilot.common.realtime import DT_CTRL, Ratekeeper -from openpilot.common.numpy_fast import interp, clip from openpilot.common.params import Params from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel -from openpilot.system.hardware import HARDWARE -from openpilot.tools.lib.kbhit import KBHit -EXPO = 0.4 MAX_LAT_ACCEL = 2.5 -class Keyboard: - def __init__(self): - self.kb = KBHit() - self.axis_increment = 0.05 # 5% of full actuation each key press - self.axes_map = {'w': 'gb', 's': 'gb', - 'a': 'steer', 'd': 'steer'} - self.axes_values = {'gb': 0., 'steer': 0.} - self.axes_order = ['gb', 'steer'] - self.cancel = False - - def update(self): - key = self.kb.getch().lower() - self.cancel = False - if key == 'r': - self.axes_values = {ax: 0. for ax in self.axes_values} - elif key == 'c': - self.cancel = True - elif key in self.axes_map: - axis = self.axes_map[key] - incr = self.axis_increment if key in ['w', 'a'] else -self.axis_increment - self.axes_values[axis] = clip(self.axes_values[axis] + incr, -1, 1) - else: - return False - return True - - -class Joystick: - def __init__(self): - # This class supports a PlayStation 5 DualSense controller on the comma 3X - # TODO: find a way to get this from API or detect gamepad/PC, perhaps "inputs" doesn't support it - self.cancel_button = 'BTN_NORTH' # BTN_NORTH=X/triangle - if HARDWARE.get_device_type() == 'pc': - accel_axis = 'ABS_Z' - steer_axis = 'ABS_RX' - # TODO: once the longcontrol API is finalized, we can replace this with outputting gas/brake and steering - self.flip_map = {'ABS_RZ': accel_axis} - else: - accel_axis = 'ABS_RX' - steer_axis = 'ABS_Z' - self.flip_map = {'ABS_RY': accel_axis} - - self.min_axis_value = {accel_axis: 0., steer_axis: 0.} - self.max_axis_value = {accel_axis: 255., steer_axis: 255.} - self.axes_values = {accel_axis: 0., steer_axis: 0.} - self.axes_order = [accel_axis, steer_axis] - self.cancel = False - - def update(self): - try: - joystick_event = get_gamepad()[0] - except (OSError, UnpluggedError): - self.axes_values = {ax: 0. for ax in self.axes_values} - return False - - event = (joystick_event.code, joystick_event.state) - - # flip left trigger to negative accel - if event[0] in self.flip_map: - event = (self.flip_map[event[0]], -event[1]) - - if event[0] == self.cancel_button: - if event[1] == 1: - self.cancel = True - elif event[1] == 0: # state 0 is falling edge - self.cancel = False - elif event[0] in self.axes_values: - self.max_axis_value[event[0]] = max(event[1], self.max_axis_value[event[0]]) - self.min_axis_value[event[0]] = min(event[1], self.min_axis_value[event[0]]) - - norm = -interp(event[1], [self.min_axis_value[event[0]], self.max_axis_value[event[0]]], [-1., 1.]) - norm = norm if abs(norm) > 0.03 else 0. # center can be noisy, deadzone of 3% - self.axes_values[event[0]] = EXPO * norm ** 3 + (1 - EXPO) * norm # less action near center for fine control - else: - return False - return True - - -def send_thread(joystick): +def joystickd_thread(): params = Params() cloudlog.info("joystickd is waiting for CarParams") CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) VM = VehicleModel(CP) - sm = messaging.SubMaster(['carState', 'onroadEvents', 'liveParameters', 'selfdriveState'], frequency=1. / DT_CTRL) + sm = messaging.SubMaster(['carState', 'onroadEvents', 'liveParameters', 'selfdriveState', 'testJoystick'], frequency=1. / DT_CTRL) pm = messaging.PubMaster(['carControl', 'controlsState']) rk = Ratekeeper(100, print_delay_threshold=None) while 1: sm.update(0) - joystick_axes = [joystick.axes_values[a] for a in joystick.axes_order] - if rk.frame % 20 == 0: - print('\n' + ', '.join(f'{name}: {round(v, 3)}' for name, v in joystick.axes_values.items())) - cc_msg = messaging.new_message('carControl') cc_msg.valid = True CC = cc_msg.carControl @@ -121,6 +34,14 @@ def send_thread(joystick): actuators = CC.actuators + # reset joystick if it hasn't been received in a while + should_reset_joystick = sm.recv_frame['testJoystick'] == 0 or (sm.frame - sm.recv_frame['testJoystick'])*DT_CTRL > 0.2 + + if not should_reset_joystick: + joystick_axes = sm['testJoystick'].axes + else: + joystick_axes = [0.0, 0.0] + if CC.longActive: actuators.accel = 4.0 * clip(joystick_axes[0], -1, 1) @@ -142,39 +63,9 @@ def send_thread(joystick): rk.keep_time() -def joystick_thread(joystick): - Params().put_bool('JoystickDebugMode', True) - threading.Thread(target=send_thread, args=(joystick,), daemon=True).start() - while True: - joystick.update() +def main(): + joystickd_thread() -def main(): - joystick_thread(Joystick()) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser(description='Publishes events from your joystick to control your car.\n' + - 'openpilot must be offroad before starting joystickd. This tool supports ' + - 'a PlayStation 5 DualSense controller on the comma 3X.', - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument('--keyboard', action='store_true', help='Use your keyboard instead of a joystick') - args = parser.parse_args() - - if not Params().get_bool("IsOffroad") and "ZMQ" not in os.environ: - print("The car must be off before running joystickd.") - exit() - - print() - if args.keyboard: - print('Gas/brake control: `W` and `S` keys') - print('Steering control: `A` and `D` keys') - print('Buttons') - print('- `R`: Resets axes') - print('- `C`: Cancel cruise control') - else: - print('Using joystick, make sure to run cereal/messaging/bridge on your device if running over the network!') - print('If not running on a comma device, the mapping may need to be adjusted.') - - joystick = Keyboard() if args.keyboard else Joystick() - joystick_thread(joystick) +if __name__ == "__main__": + main() From 6dfc154c5943b9b6d458c5de11c6ca8aabfd5e15 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 25 Sep 2024 01:15:01 +0800 Subject: [PATCH 129/214] ci: add OVERRIDE and DISENGAGED state to ui report (#33639) add state --- .github/workflows/ui_preview.yaml | 2 +- selfdrive/ui/tests/test_ui/run.py | 13 +++++++++++++ 2 files changed, 14 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ui_preview.yaml b/.github/workflows/ui_preview.yaml index 7880ecdea6..a2033f8180 100644 --- a/.github/workflows/ui_preview.yaml +++ b/.github/workflows/ui_preview.yaml @@ -84,7 +84,7 @@ jobs: run: >- sudo apt-get install -y imagemagick - scenes="homescreen settings_device settings_toggles offroad_alert update_available prime onroad onroad_sidebar onroad_wide onroad_wide_sidebar onroad_alert_small onroad_alert_mid onroad_alert_full driver_camera body keyboard" + scenes="homescreen settings_device settings_toggles offroad_alert update_available prime onroad onroad_disengaged onroad_override onroad_sidebar onroad_wide onroad_wide_sidebar onroad_alert_small onroad_alert_mid onroad_alert_full driver_camera body keyboard" A=($scenes) DIFF="" diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index eee0ada266..8c9db5a3f3 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -77,6 +77,17 @@ def setup_onroad(click, pm: PubMaster): packet_id += 1 time.sleep(0.05) +def setup_onroad_disengaged(click, pm: PubMaster): + DATA['selfdriveState'].selfdriveState.enabled = False + setup_onroad(click, pm) + DATA['selfdriveState'].selfdriveState.enabled = True + +def setup_onroad_override(click, pm: PubMaster): + DATA['selfdriveState'].selfdriveState.state = log.SelfdriveState.OpenpilotState.overriding + setup_onroad(click, pm) + DATA['selfdriveState'].selfdriveState.state = log.SelfdriveState.OpenpilotState.enabled + + def setup_onroad_wide(click, pm: PubMaster): DATA['selfdriveState'].selfdriveState.experimentalMode = True DATA["carState"].carState.vEgo = 1 @@ -165,6 +176,8 @@ CASES = { "settings_device": setup_settings_device, "settings_toggles": setup_settings_toggles, "onroad": setup_onroad, + "onroad_disengaged": setup_onroad_disengaged, + "onroad_override": setup_onroad_override, "onroad_sidebar": setup_onroad_sidebar, "onroad_alert_small": setup_onroad_alert_small, "onroad_alert_mid": setup_onroad_alert_mid, From deb6b72091df94c1ac24a73be7ad6c9d7b096dc5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Tue, 24 Sep 2024 10:51:30 -0700 Subject: [PATCH 130/214] Safe exp in parsing (#33640) --- selfdrive/modeld/parse_model_outputs.py | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/selfdrive/modeld/parse_model_outputs.py b/selfdrive/modeld/parse_model_outputs.py index 61dfca0a4f..4367e9db8a 100644 --- a/selfdrive/modeld/parse_model_outputs.py +++ b/selfdrive/modeld/parse_model_outputs.py @@ -1,17 +1,19 @@ import numpy as np from openpilot.selfdrive.modeld.constants import ModelConstants -def sigmoid(x): +def safe_exp(x, out=None): # -11 is around 10**14, more causes float16 overflow - clipped_x = np.clip(x, -11, np.inf) - return 1. / (1. + np.exp(-clipped_x)) + return np.exp(np.clip(x, -np.inf, 11), out=out) + +def sigmoid(x): + return 1. / (1. + safe_exp(-x)) def softmax(x, axis=-1): x -= np.max(x, axis=axis, keepdims=True) if x.dtype == np.float32 or x.dtype == np.float64: - np.exp(x, out=x) + safe_exp(x, out=x) else: - x = np.exp(x) + x = safe_exp(x) x /= np.sum(x, axis=axis, keepdims=True) return x @@ -46,7 +48,7 @@ class Parser: n_values = (raw.shape[2] - out_N)//2 pred_mu = raw[:,:,:n_values] - pred_std = np.exp(raw[:,:,n_values: 2*n_values]) + pred_std = safe_exp(raw[:,:,n_values: 2*n_values]) if in_N > 1: weights = np.zeros((raw.shape[0], in_N, out_N), dtype=raw.dtype) From 3b7a60499ef02342861b626ad255dcd874982df8 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Tue, 24 Sep 2024 15:02:43 -0400 Subject: [PATCH 131/214] tools: fix car porting notebooks (#33641) * ford_vin_fingerprint fixes and updates * subaru_fuzzy_fingerprint partial fixes * subaru_long_accel: fixes * subaru_steer_temp_fault fixes * subaru_fuzzy_fingerprint more fixes --- .../examples/ford_vin_fingerprint.ipynb | 71 +++-- .../examples/subaru_fuzzy_fingerprint.ipynb | 249 +++++++++--------- .../examples/subaru_long_accel.ipynb | 21 +- .../examples/subaru_steer_temp_fault.ipynb | 15 +- 4 files changed, 196 insertions(+), 160 deletions(-) diff --git a/tools/car_porting/examples/ford_vin_fingerprint.ipynb b/tools/car_porting/examples/ford_vin_fingerprint.ipynb index 21d1cb62c0..7b0dd656da 100644 --- a/tools/car_porting/examples/ford_vin_fingerprint.ipynb +++ b/tools/car_porting/examples/ford_vin_fingerprint.ipynb @@ -2,19 +2,32 @@ "cells": [ { "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [], + "execution_count": 12, + "metadata": { + "jupyter": { + "is_executing": true + } + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Got 9 Ford cars from opendbc\n" + ] + } + ], "source": [ "\"\"\"In this example, we use the public comma car segments database to check if vin fingerprinting is feasible for ford.\"\"\"\n", "\n", "from openpilot.tools.lib.logreader import LogReader\n", "from openpilot.tools.lib.comma_car_segments import get_comma_car_segments_database\n", - "from openpilot.selfdrive.car.ford.values import CAR\n", + "from opendbc.car.ford.values import CAR\n", "\n", "database = get_comma_car_segments_database()\n", "\n", - "platforms = [c.value for c in CAR]" + "platforms = [c.value for c in CAR]\n", + "print(f\"Got {len(platforms)} Ford cars from opendbc\")" ] }, { @@ -54,21 +67,24 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 13, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "Got 287 segments for platform FORD BRONCO SPORT 1ST GEN, sampling 5 segments\n", - "Got 137 segments for platform FORD ESCAPE 4TH GEN, sampling 5 segments\n", - "Got 1041 segments for platform FORD EXPLORER 6TH GEN, sampling 5 segments\n", - "Got 5 segments for platform FORD F-150 14TH GEN, sampling 5 segments\n", - "Got 56 segments for platform FORD FOCUS 4TH GEN, sampling 5 segments\n", - "Got 637 segments for platform FORD MAVERICK 1ST GEN, sampling 5 segments\n", - "Got 3 segments for platform FORD F-150 LIGHTNING 1ST GEN, sampling 3 segments\n", - "Got 3 segments for platform FORD MUSTANG MACH-E 1ST GEN, sampling 3 segments\n" + "Collecting segments from commaCarSegments dataset:\n", + "Got 287 segments for platform FORD_BRONCO_SPORT_MK1, sampling 5 segments\n", + "Got 137 segments for platform FORD_ESCAPE_MK4, sampling 5 segments\n", + "Got 1041 segments for platform FORD_EXPLORER_MK6, sampling 5 segments\n", + "Got 5 segments for platform FORD_F_150_MK14, sampling 5 segments\n", + "Got 3 segments for platform FORD_F_150_LIGHTNING_MK1, sampling 3 segments\n", + "Got 56 segments for platform FORD_FOCUS_MK4, sampling 5 segments\n", + "Got 637 segments for platform FORD_MAVERICK_MK1, sampling 5 segments\n", + "Got 3 segments for platform FORD_MUSTANG_MACH_E_MK1, sampling 3 segments\n", + "Skipping platform: FORD_RANGER_MK2, no data available\n", + "Segment collection finished\n" ] } ], @@ -79,6 +95,7 @@ "\n", "VINS_TO_CHECK = set()\n", "\n", + "print(\"Collecting segments from commaCarSegments dataset:\")\n", "for platform in platforms:\n", " if platform not in database:\n", " print(f\"Skipping platform: {platform}, no data available\")\n", @@ -97,31 +114,33 @@ " CP = lr.first(\"carParams\")\n", " if \"FORD\" not in CP.carFingerprint:\n", " print(segment, CP.carFingerprint)\n", - " VINS_TO_CHECK.add((CP.carVin, CP.carFingerprint))" + " VINS_TO_CHECK.add((CP.carVin, CP.carFingerprint))\n", + "\n", + "print(\"Segment collection finished\")" ] }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 16, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "vin: 3FTTW8E34PRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False\n", + "vin: 3FMCR9B69NRXXXXXX real platform: FORD BRONCO SPORT 1ST GEN determined platform: mock correct: False\n", "vin: 00000000000XXXXXX real platform: FORD F-150 14TH GEN determined platform: mock correct: False\n", + "vin: 1FMCU9J94MUXXXXXX real platform: FORD ESCAPE 4TH GEN determined platform: mock correct: False\n", "vin: 3FMTK3SU0MMXXXXXX real platform: FORD MUSTANG MACH-E 1ST GEN determined platform: FORD MUSTANG MACH-E 1ST GEN correct: True\n", + "vin: 1FM5K8HC7MGXXXXXX real platform: FORD EXPLORER 6TH GEN determined platform: mock correct: False\n", + "vin: 5LM5J7XC9LGXXXXXX real platform: FORD EXPLORER 6TH GEN determined platform: mock correct: False\n", "vin: 1FTVW1EL4NWXXXXXX real platform: FORD F-150 LIGHTNING 1ST GEN determined platform: FORD F-150 LIGHTNING 1ST GEN correct: True\n", "vin: WF0NXXGCHNJXXXXXX real platform: FORD FOCUS 4TH GEN determined platform: mock correct: False\n", - "vin: 1FMCU9J94MUXXXXXX real platform: FORD ESCAPE 4TH GEN determined platform: mock correct: False\n", - "vin: 3FTTW8E33NRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False\n", - "vin: 3FMCR9B69NRXXXXXX real platform: FORD BRONCO SPORT 1ST GEN determined platform: mock correct: False\n", + "vin: 3FTTW8E99NRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False\n", "vin: 1FM5K8GC7LGXXXXXX real platform: FORD EXPLORER 6TH GEN determined platform: mock correct: False\n", - "vin: 5LM5J7XC9LGXXXXXX real platform: FORD EXPLORER 6TH GEN determined platform: mock correct: False\n", + "vin: 3FTTW8E33NRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False\n", "vin: 5LM5J7XC1LGXXXXXX real platform: FORD EXPLORER 6TH GEN determined platform: mock correct: False\n", - "vin: 3FTTW8F97NRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False\n", - "vin: 3FTTW8E99NRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False\n" + "vin: 3FTTW8E3XPRXXXXXX real platform: FORD MAVERICK 1ST GEN determined platform: mock correct: False\n" ] } ], @@ -134,7 +153,7 @@ ], "metadata": { "kernelspec": { - "display_name": ".venv", + "display_name": "Python 3 (ipykernel)", "language": "python", "name": "python3" }, @@ -148,9 +167,9 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.11.4" + "version": "3.12.3" } }, "nbformat": 4, - "nbformat_minor": 2 + "nbformat_minor": 4 } diff --git a/tools/car_porting/examples/subaru_fuzzy_fingerprint.ipynb b/tools/car_porting/examples/subaru_fuzzy_fingerprint.ipynb index 1048011c05..708e55865b 100644 --- a/tools/car_porting/examples/subaru_fuzzy_fingerprint.ipynb +++ b/tools/car_porting/examples/subaru_fuzzy_fingerprint.ipynb @@ -2,32 +2,24 @@ "cells": [ { "cell_type": "code", - "execution_count": null, + "execution_count": 6, "metadata": {}, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "kj/filesystem-disk-unix.c++:1703: warning: PWD environment variable doesn't match current directory; pwd = /home/batman\n" - ] - } - ], + "outputs": [], "source": [ - "from cereal import car\n", - "from openpilot.selfdrive.car.subaru.values import CAR, SubaruFlags\n", - "from openpilot.selfdrive.car.subaru.fingerprints import FW_VERSIONS\n", + "from opendbc.car import structs\n", + "from opendbc.car.subaru.values import CAR, SubaruFlags\n", + "from opendbc.car.subaru.fingerprints import FW_VERSIONS\n", "\n", "TEST_PLATFORMS = set(CAR) - CAR.with_flags(SubaruFlags.PREGLOBAL)\n", "\n", - "Ecu = car.CarParams.Ecu\n", + "Ecu = structs.CarParams.Ecu\n", "\n", "FW_BY_ECU = {platform: {ecu: versions for (ecu, addr, sub_addr), versions in fw_versions.items()} for platform, fw_versions in FW_VERSIONS.items()}" ] }, { "cell_type": "code", - "execution_count": null, + "execution_count": 7, "metadata": {}, "outputs": [], "source": [ @@ -59,7 +51,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 8, "metadata": {}, "outputs": [], "source": [ @@ -83,64 +75,66 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 9, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "SUBARU IMPREZA LIMITED 2019 08 not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", - "SUBARU IMPREZA LIMITED 2019 08 not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", - "SUBARU IMPREZA LIMITED 2019 0c not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", - "SUBARU IMPREZA LIMITED 2019 0c not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", - "SUBARU IMPREZA LIMITED 2019 2e not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", - "SUBARU IMPREZA LIMITED 2019 3f not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", - "correct_year=True platform=SUBARU OUTBACK 7TH GEN year=2023 years=[2023]\n", - "correct_year=True platform=SUBARU OUTBACK 7TH GEN year=2023 years=[2023]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2022 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU OUTBACK 6TH GEN year=2022 years=[2020, 2021, 2022]\n", - "correct_year=False platform=SUBARU CROSSTREK HYBRID 2020 year=2019 years=[2020]\n", - "correct_year=False platform=SUBARU CROSSTREK HYBRID 2020 year=2021 years=[2020]\n", - "correct_year=False platform=SUBARU FORESTER HYBRID 2020 year=2019 years=[2020]\n", - "correct_year=True platform=SUBARU LEGACY 7TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU LEGACY 7TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU LEGACY 7TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU LEGACY 7TH GEN year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU IMPREZA LIMITED 2019 year=2019 years=[2017, 2018, 2019]\n", - "correct_year=True platform=SUBARU IMPREZA LIMITED 2019 year=2019 years=[2017, 2018, 2019]\n", - "correct_year=True platform=SUBARU IMPREZA LIMITED 2019 year=2018 years=[2017, 2018, 2019]\n", - "correct_year=True platform=SUBARU IMPREZA LIMITED 2019 year=2019 years=[2017, 2018, 2019]\n", - "correct_year=True platform=SUBARU IMPREZA LIMITED 2019 year=2019 years=[2017, 2018, 2019]\n", - "correct_year=True platform=SUBARU IMPREZA LIMITED 2019 year=2019 years=[2017, 2018, 2019]\n", - "correct_year=False platform=SUBARU FORESTER 2022 year=2021 years=[2022, 2023, 2024]\n", - "correct_year=False platform=SUBARU FORESTER 2022 year=2021 years=[2022, 2023, 2024]\n", - "correct_year=True platform=SUBARU FORESTER 2022 year=2022 years=[2022, 2023, 2024]\n", - "correct_year=True platform=SUBARU FORESTER 2022 year=2022 years=[2022, 2023, 2024]\n", - "correct_year=False platform=SUBARU IMPREZA SPORT 2020 year=2019 years=[2020, 2021, 2022]\n", - "correct_year=False platform=SUBARU IMPREZA SPORT 2020 year=2019 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU IMPREZA SPORT 2020 year=2020 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU IMPREZA SPORT 2020 year=2021 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU IMPREZA SPORT 2020 year=2021 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU IMPREZA SPORT 2020 year=2021 years=[2020, 2021, 2022]\n", - "correct_year=True platform=SUBARU ASCENT 2023 year=2023 years=[2023]\n", - "correct_year=True platform=SUBARU ASCENT LIMITED 2019 year=2019 years=[2019, 2020, 2021]\n", - "correct_year=True platform=SUBARU ASCENT LIMITED 2019 year=2021 years=[2019, 2020, 2021]\n", - "correct_year=False platform=SUBARU FORESTER 2019 year=2018 years=[2019, 2020, 2021]\n", - "correct_year=False platform=SUBARU FORESTER 2019 year=2018 years=[2019, 2020, 2021]\n", - "correct_year=True platform=SUBARU FORESTER 2019 year=2019 years=[2019, 2020, 2021]\n", - "correct_year=True platform=SUBARU FORESTER 2019 year=2019 years=[2019, 2020, 2021]\n", - "correct_year=True platform=SUBARU FORESTER 2019 year=2020 years=[2019, 2020, 2021]\n", - "correct_year=True platform=SUBARU FORESTER 2019 year=2020 years=[2019, 2020, 2021]\n" + "SUBARU_IMPREZA 08 not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", + "SUBARU_IMPREZA 08 not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", + "SUBARU_IMPREZA 0c not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", + "SUBARU_IMPREZA 0c not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", + "SUBARU_IMPREZA 2e not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", + "SUBARU_IMPREZA 3f not in dict_keys([b'\\x18', b'\\x19', b' ', b'!', b'\"', b'#'])\n", + "correct_year=False platform=SUBARU_FORESTER year=2018 years=[2019, 2020, 2021]\n", + "correct_year=False platform=SUBARU_FORESTER year=2018 years=[2019, 2020, 2021]\n", + "correct_year=True platform=SUBARU_FORESTER year=2019 years=[2019, 2020, 2021]\n", + "correct_year=True platform=SUBARU_FORESTER year=2019 years=[2019, 2020, 2021]\n", + "correct_year=True platform=SUBARU_FORESTER year=2019 years=[2019, 2020, 2021]\n", + "correct_year=True platform=SUBARU_FORESTER year=2020 years=[2019, 2020, 2021]\n", + "correct_year=True platform=SUBARU_FORESTER year=2020 years=[2019, 2020, 2021]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2022 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_OUTBACK year=2022 years=[2020, 2021, 2022]\n", + "correct_year=False platform=SUBARU_FORESTER_HYBRID year=2019 years=[2020]\n", + "correct_year=False platform=SUBARU_CROSSTREK_HYBRID year=2019 years=[2020]\n", + "correct_year=False platform=SUBARU_CROSSTREK_HYBRID year=2021 years=[2020]\n", + "correct_year=True platform=SUBARU_ASCENT_2023 year=2023 years=[2023]\n", + "correct_year=True platform=SUBARU_IMPREZA year=2019 years=[2017, 2018, 2019]\n", + "correct_year=True platform=SUBARU_IMPREZA year=2019 years=[2017, 2018, 2019]\n", + "correct_year=True platform=SUBARU_IMPREZA year=2018 years=[2017, 2018, 2019]\n", + "correct_year=True platform=SUBARU_IMPREZA year=2019 years=[2017, 2018, 2019]\n", + "correct_year=True platform=SUBARU_IMPREZA year=2019 years=[2017, 2018, 2019]\n", + "correct_year=True platform=SUBARU_IMPREZA year=2019 years=[2017, 2018, 2019]\n", + "correct_year=False platform=SUBARU_FORESTER_2022 year=2021 years=[2022, 2023, 2024]\n", + "correct_year=False platform=SUBARU_FORESTER_2022 year=2021 years=[2022, 2023, 2024]\n", + "correct_year=True platform=SUBARU_FORESTER_2022 year=2022 years=[2022, 2023, 2024]\n", + "correct_year=True platform=SUBARU_FORESTER_2022 year=2022 years=[2022, 2023, 2024]\n", + "correct_year=True platform=SUBARU_ASCENT year=2019 years=[2019, 2020, 2021]\n", + "correct_year=True platform=SUBARU_ASCENT year=2021 years=[2019, 2020, 2021]\n", + "correct_year=True platform=SUBARU_OUTBACK_2023 year=2023 years=[2023]\n", + "correct_year=True platform=SUBARU_OUTBACK_2023 year=2023 years=[2023]\n", + "correct_year=False platform=SUBARU_IMPREZA_2020 year=2019 years=[2020, 2021, 2022]\n", + "correct_year=False platform=SUBARU_IMPREZA_2020 year=2019 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_IMPREZA_2020 year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_IMPREZA_2020 year=2021 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_IMPREZA_2020 year=2021 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_IMPREZA_2020 year=2021 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_IMPREZA_2020 year=2021 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_LEGACY year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_LEGACY year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_LEGACY year=2020 years=[2020, 2021, 2022]\n", + "correct_year=True platform=SUBARU_LEGACY year=2020 years=[2020, 2021, 2022]\n" ] } ], @@ -160,64 +154,66 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 10, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "in_possible_platforms=True platform=SUBARU OUTBACK 7TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 7TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU OUTBACK 6TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU CROSSTREK HYBRID 2020 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU CROSSTREK HYBRID 2020 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU FORESTER HYBRID 2020 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n", - "in_possible_platforms=True platform=SUBARU LEGACY 7TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU LEGACY 7TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU LEGACY 7TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU LEGACY 7TH GEN platforms=['SUBARU OUTBACK 6TH GEN', 'SUBARU LEGACY 7TH GEN', 'SUBARU OUTBACK 7TH GEN']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA LIMITED 2019 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU FORESTER 2022 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n", - "in_possible_platforms=True platform=SUBARU FORESTER 2022 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n", - "in_possible_platforms=True platform=SUBARU FORESTER 2022 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n", - "in_possible_platforms=True platform=SUBARU FORESTER 2022 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA SPORT 2020 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA SPORT 2020 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA SPORT 2020 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA SPORT 2020 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA SPORT 2020 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU IMPREZA SPORT 2020 platforms=['SUBARU IMPREZA LIMITED 2019', 'SUBARU IMPREZA SPORT 2020', 'SUBARU CROSSTREK HYBRID 2020']\n", - "in_possible_platforms=True platform=SUBARU ASCENT 2023 platforms=['SUBARU ASCENT LIMITED 2019', 'SUBARU ASCENT 2023']\n", - "in_possible_platforms=True platform=SUBARU ASCENT LIMITED 2019 platforms=['SUBARU ASCENT LIMITED 2019', 'SUBARU ASCENT 2023']\n", - "in_possible_platforms=True platform=SUBARU ASCENT LIMITED 2019 platforms=['SUBARU ASCENT LIMITED 2019', 'SUBARU ASCENT 2023']\n", - "in_possible_platforms=True platform=SUBARU FORESTER 2019 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n", - "in_possible_platforms=True platform=SUBARU FORESTER 2019 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n", - "in_possible_platforms=True platform=SUBARU FORESTER 2019 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n", - "in_possible_platforms=True platform=SUBARU FORESTER 2019 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n", - "in_possible_platforms=True platform=SUBARU FORESTER 2019 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n", - "in_possible_platforms=True platform=SUBARU FORESTER 2019 platforms=['SUBARU FORESTER 2019', 'SUBARU FORESTER HYBRID 2020', 'SUBARU FORESTER 2022']\n" + "in_possible_platforms=True platform=SUBARU_FORESTER platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER_HYBRID platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_CROSSTREK_HYBRID platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_CROSSTREK_HYBRID platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_ASCENT_2023 platforms=['SUBARU_ASCENT', 'SUBARU_ASCENT_2023']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER_2022 platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER_2022 platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER_2022 platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_FORESTER_2022 platforms=['SUBARU_FORESTER', 'SUBARU_FORESTER_HYBRID', 'SUBARU_FORESTER_2022']\n", + "in_possible_platforms=True platform=SUBARU_ASCENT platforms=['SUBARU_ASCENT', 'SUBARU_ASCENT_2023']\n", + "in_possible_platforms=True platform=SUBARU_ASCENT platforms=['SUBARU_ASCENT', 'SUBARU_ASCENT_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK_2023 platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_OUTBACK_2023 platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA_2020 platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA_2020 platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA_2020 platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA_2020 platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA_2020 platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA_2020 platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_IMPREZA_2020 platforms=['SUBARU_IMPREZA', 'SUBARU_IMPREZA_2020', 'SUBARU_CROSSTREK_HYBRID']\n", + "in_possible_platforms=True platform=SUBARU_LEGACY platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_LEGACY platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_LEGACY platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n", + "in_possible_platforms=True platform=SUBARU_LEGACY platforms=['SUBARU_OUTBACK', 'SUBARU_LEGACY', 'SUBARU_OUTBACK_2023']\n" ] } ], @@ -231,11 +227,18 @@ "for platform, possible_platforms in codes:\n", " test_platform_code(platform, possible_platforms)" ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] } ], "metadata": { "kernelspec": { - "display_name": ".venv", + "display_name": "Python 3 (ipykernel)", "language": "python", "name": "python3" }, @@ -249,9 +252,9 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.11.4" + "version": "3.12.3" } }, "nbformat": 4, - "nbformat_minor": 2 + "nbformat_minor": 4 } diff --git a/tools/car_porting/examples/subaru_long_accel.ipynb b/tools/car_porting/examples/subaru_long_accel.ipynb index 35b92702a7..d4a4705d95 100644 --- a/tools/car_porting/examples/subaru_long_accel.ipynb +++ b/tools/car_porting/examples/subaru_long_accel.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": null, + "execution_count": 1, "metadata": {}, "outputs": [], "source": [ @@ -14,7 +14,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ @@ -22,8 +22,8 @@ "import numpy as np\n", "\n", "from opendbc.can.parser import CANParser\n", + "from opendbc.car.subaru.values import DBC\n", "\n", - "from openpilot.selfdrive.car.subaru.values import DBC\n", "from openpilot.selfdrive.pandad import can_capnp_to_list\n", "from openpilot.tools.lib.logreader import LogReader\n", "\n", @@ -64,7 +64,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 4, "metadata": {}, "outputs": [], "source": [ @@ -95,11 +95,18 @@ "ax.set_ylabel(\"Acceleration\")\n", "ax.scatter(cruise_brake[valid_brake], -acceleration[valid_brake])" ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] } ], "metadata": { "kernelspec": { - "display_name": "Python 3", + "display_name": "Python 3 (ipykernel)", "language": "python", "name": "python3" }, @@ -113,9 +120,9 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.11.4" + "version": "3.12.3" } }, "nbformat": 4, - "nbformat_minor": 2 + "nbformat_minor": 4 } diff --git a/tools/car_porting/examples/subaru_steer_temp_fault.ipynb b/tools/car_porting/examples/subaru_steer_temp_fault.ipynb index 8b762fecb8..10abe8ed31 100644 --- a/tools/car_porting/examples/subaru_steer_temp_fault.ipynb +++ b/tools/car_porting/examples/subaru_steer_temp_fault.ipynb @@ -25,8 +25,8 @@ "import numpy as np\n", "\n", "from opendbc.can.parser import CANParser\n", + "from opendbc.car.subaru.values import CanBus, DBC\n", "\n", - "from openpilot.selfdrive.car.subaru.values import CanBus, DBC\n", "from openpilot.selfdrive.pandad import can_capnp_to_list\n", "from openpilot.tools.lib.logreader import LogReader\n", "\n", @@ -85,11 +85,18 @@ "\n", " plt.show()\n" ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] } ], "metadata": { "kernelspec": { - "display_name": "Python 3", + "display_name": "Python 3 (ipykernel)", "language": "python", "name": "python3" }, @@ -103,9 +110,9 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.11.4" + "version": "3.12.3" } }, "nbformat": 4, - "nbformat_minor": 2 + "nbformat_minor": 4 } From 811bf06f8cde2db3da11172e9da585a6eba5edcf Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 25 Sep 2024 03:03:08 +0800 Subject: [PATCH 132/214] replay: improve README with clearer instructions and example (#33560) improve README with clearer instructions and example --- tools/replay/README.md | 70 +++++++++++++++++++++++++++++++++++------- 1 file changed, 59 insertions(+), 11 deletions(-) diff --git a/tools/replay/README.md b/tools/replay/README.md index 67cfcd75a6..65a1e7a0b3 100644 --- a/tools/replay/README.md +++ b/tools/replay/README.md @@ -1,31 +1,55 @@ # Replay -## Replay driving data +`replay` allows you to simulate a driving session by replaying all messages logged during the use of openpilot. This provides a way to analyze and visualize system behavior as if it were live. -`replay` replays all the messages logged while running openpilot. +## Setup + +Before starting a replay, you need to authenticate with your comma account using `auth.py`. This will allow you to access your routes from the server. ```bash -# Log in via browser to have access to routes from your comma account +# Authenticate to access routes from your comma account: python3 tools/lib/auth.py +``` -# Start a replay +## Replay a Remote Route +You can replay a route from your comma account by specifying the route name. + +```bash +# Start a replay with a specific route: tools/replay/replay # Example: tools/replay/replay 'a2a0ccea32023010|2023-07-27--13-01-19' -# or use --demo to replay the default demo route: + +# Replay the default demo route: tools/replay/replay --demo +``` -# watch the replay with the normal openpilot UI -cd selfdrive/ui && ./ui +## Replay a Local Route +To replay a route stored locally on your machine, specify the route name and provide the path to the directory where the route files are stored. -# or try out radar point visualization in Rerun: -python3 replay/rp_visualization.py +```bash +# Replay a local route +tools/replay/replay --data_dir="/path_to/route" + +# Example: +# If you have a local route stored at /path_to_routes with segments like: +# a2a0ccea32023010|2023-07-27--13-01-19--0 +# a2a0ccea32023010|2023-07-27--13-01-19--1 +# You can replay it like this: +tools/replay/replay "a2a0ccea32023010|2023-07-27--13-01-19" --data-dir="/path_to_routes" +``` -# NOTE: To visualize radar points, make sure tools/replay/replay is running. +## Send Messages via ZMQ +By default, replay sends messages via MSGQ. To switch to ZMQ, set the ZMQ environment variable. + +```bash +# Start replay and send messages via ZMQ: +ZMQ=1 tools/replay/replay ``` -## usage +## Usage +For more information on available options and arguments, use the help command: ``` bash $ tools/replay/replay -h @@ -57,6 +81,30 @@ Arguments: connect.comma.ai ``` +## Visualize the Replay in the Openpilot UI +To visualize the replay within the openpilot UI, run the following commands: + +```bash +tools/replay/replay +cd selfdrive/ui && ./ui +``` + +## Try Radar Point Visualization with Rerun +To visualize radar points, run rp_visualization.py while tools/replay/replay is active. + +```bash +tools/replay/replay +python3 replay/rp_visualization.py +``` + +## Work with plotjuggler +If you want to use replay with plotjuggler, you can stream messages by running: + +```bash +tools/replay/replay +tools/plotjuggler/juggle.py --stream +``` + ## watch3 watch all three cameras simultaneously from your comma three routes with watch3 From 1f198ff9c95f33d782ee4a36e61d9367e6d12241 Mon Sep 17 00:00:00 2001 From: commaci-public <60409688+commaci-public@users.noreply.github.com> Date: Tue, 24 Sep 2024 13:56:49 -0700 Subject: [PATCH 133/214] [bot] Update Python packages (#33626) * Update Python packages * fix build --------- Co-authored-by: Vehicle Researcher Co-authored-by: Maxime Desroches --- panda | 2 +- selfdrive/pandad/panda.h | 2 +- uv.lock | 80 ++++++++++++++++++++-------------------- 3 files changed, 42 insertions(+), 42 deletions(-) diff --git a/panda b/panda index 93aedd987b..2037a2ead7 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 93aedd987bda7e267210689b877eb87f288fc6ab +Subproject commit 2037a2ead7257deadf6165734fd19b9b87de6eb7 diff --git a/selfdrive/pandad/panda.h b/selfdrive/pandad/panda.h index af31c2316e..2491f2eb74 100644 --- a/selfdrive/pandad/panda.h +++ b/selfdrive/pandad/panda.h @@ -12,7 +12,7 @@ #include "cereal/gen/cpp/car.capnp.h" #include "cereal/gen/cpp/log.capnp.h" #include "panda/board/health.h" -#include "panda/board/can_definitions.h" +#include "panda/board/can.h" #include "selfdrive/pandad/panda_comms.h" #define USB_TX_SOFT_LIMIT (0x100U) diff --git a/uv.lock b/uv.lock index 3d60cefd68..2be225145b 100644 --- a/uv.lock +++ b/uv.lock @@ -174,7 +174,7 @@ wheels = [ [[package]] name = "azure-identity" -version = "1.17.1" +version = "1.18.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "azure-core" }, @@ -183,9 +183,9 @@ dependencies = [ { name = "msal-extensions" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/51/c9/f7e3926686a89670ce641b360bd2da9a2d7a12b3e532403462d99f81e9d5/azure-identity-1.17.1.tar.gz", hash = "sha256:32ecc67cc73f4bd0595e4f64b1ca65cd05186f4fe6f98ed2ae9f1aa32646efea", size = 246652 } +sdist = { url = "https://files.pythonhosted.org/packages/b3/5d/1c7da35dd640b4a95a38f980bb6b0b56c4e91d5b3d518ac11a2c4ebf5f62/azure_identity-1.18.0.tar.gz", hash = "sha256:f567579a65d8932fa913c76eddf3305101a15e5727a5e4aa5df649a0f553d4c3", size = 263322 } wheels = [ - { url = "https://files.pythonhosted.org/packages/49/83/a777861351e7b99e7c84ff3b36bab35e87b6e5d36e50b6905e148c696515/azure_identity-1.17.1-py3-none-any.whl", hash = "sha256:db8d59c183b680e763722bfe8ebc45930e6c57df510620985939f7f3191e0382", size = 173229 }, + { url = "https://files.pythonhosted.org/packages/b0/71/1d1bb387b6acaa5daa3e703c70dde3d54823ccd229bd6730de6e724f296e/azure_identity-1.18.0-py3-none-any.whl", hash = "sha256:bccf6106245b49ff41d0c4cd7b72851c5a2ba3a32cef7589da246f5727f26f02", size = 187179 }, ] [[package]] @@ -1757,16 +1757,16 @@ sdist = { url = "https://files.pythonhosted.org/packages/a3/a6/b8e451f6cff1c99b4 [[package]] name = "protobuf" -version = "5.28.1" +version = "5.28.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/3c/0b/7a997c8939f698d72bdea14d57116e43d3051fffb3b2964c30938c4a08e6/protobuf-5.28.1.tar.gz", hash = "sha256:42597e938f83bb7f3e4b35f03aa45208d49ae8d5bcb4bc10b9fc825e0ab5e423", size = 422422 } +sdist = { url = "https://files.pythonhosted.org/packages/b1/a4/4579a61de526e19005ceeb93e478b61d77aa38c8a85ad958ff16a9906549/protobuf-5.28.2.tar.gz", hash = "sha256:59379674ff119717404f7454647913787034f03fe7049cbef1d74a97bb4593f0", size = 422494 } wheels = [ - { url = "https://files.pythonhosted.org/packages/5a/d6/6dedb8a2fbbeb4ac92bb9dd830f77800bbe353799eb8b11d2659beffb9f4/protobuf-5.28.1-cp310-abi3-win32.whl", hash = "sha256:fc063acaf7a3d9ca13146fefb5b42ac94ab943ec6e978f543cd5637da2d57957", size = 419673 }, - { url = "https://files.pythonhosted.org/packages/28/ff/6af7b6fad3bd85820f00f3753a2ebd6bdd9dbf29da5a4252e9f402bdfe2a/protobuf-5.28.1-cp310-abi3-win_amd64.whl", hash = "sha256:4c7f5cb38c640919791c9f74ea80c5b82314c69a8409ea36f2599617d03989af", size = 431486 }, - { url = "https://files.pythonhosted.org/packages/99/80/46b61e647a9386f5dc836e9660818f79afd80a4d5802535ec07a7c6aa16e/protobuf-5.28.1-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:4304e4fceb823d91699e924a1fdf95cde0e066f3b1c28edb665bda762ecde10f", size = 414743 }, - { url = "https://files.pythonhosted.org/packages/b3/21/33dbf04427a11c2de5fb835bb37c5d1522e9d5556a92df0acd13644860a9/protobuf-5.28.1-cp38-abi3-manylinux2014_aarch64.whl", hash = "sha256:0dfd86d2b5edf03d91ec2a7c15b4e950258150f14f9af5f51c17fa224ee1931f", size = 316526 }, - { url = "https://files.pythonhosted.org/packages/c0/be/bac52549cab1aaab112d380b3f2a80a348ba7083a80bf4ff4be4fb5a6729/protobuf-5.28.1-cp38-abi3-manylinux2014_x86_64.whl", hash = "sha256:51f09caab818707ab91cf09cc5c156026599cf05a4520779ccbf53c1b352fb25", size = 316613 }, - { url = "https://files.pythonhosted.org/packages/51/3d/71fae0078424ba8ea70b222b6fa56ef771a9918ab91cee806c2abc9d57fa/protobuf-5.28.1-py3-none-any.whl", hash = "sha256:c529535e5c0effcf417682563719e5d8ac8d2b93de07a56108b4c2d436d7a29a", size = 169572 }, + { url = "https://files.pythonhosted.org/packages/e9/30/231764750e0987755b7b8d66771f161e5f002e165d27b72154c776dbabf7/protobuf-5.28.2-cp310-abi3-win32.whl", hash = "sha256:eeea10f3dc0ac7e6b4933d32db20662902b4ab81bf28df12218aa389e9c2102d", size = 419662 }, + { url = "https://files.pythonhosted.org/packages/7d/46/3fdf7462160135aee6a530f1ec66665b5b4132fa2e1002ab971bc6ec2589/protobuf-5.28.2-cp310-abi3-win_amd64.whl", hash = "sha256:2c69461a7fcc8e24be697624c09a839976d82ae75062b11a0972e41fd2cd9132", size = 431479 }, + { url = "https://files.pythonhosted.org/packages/37/45/d2a760580f8f2ed2825ba44cb370e0a4011ddef85e728f46ea3dd565a8a5/protobuf-5.28.2-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:a8b9403fc70764b08d2f593ce44f1d2920c5077bf7d311fefec999f8c40f78b7", size = 414736 }, + { url = "https://files.pythonhosted.org/packages/e6/23/ed718dc18e6a561445ece1e7a17d2dda0c634ad9cf663102b47f10005d8f/protobuf-5.28.2-cp38-abi3-manylinux2014_aarch64.whl", hash = "sha256:35cfcb15f213449af7ff6198d6eb5f739c37d7e4f1c09b5d0641babf2cc0c68f", size = 316518 }, + { url = "https://files.pythonhosted.org/packages/23/08/a1ce0415a115c2b703bfa798f06f0e43ca91dbe29d6180bf86a9287b15e2/protobuf-5.28.2-cp38-abi3-manylinux2014_x86_64.whl", hash = "sha256:5e8a95246d581eef20471b5d5ba010d55f66740942b95ba9b872d918c459452f", size = 316605 }, + { url = "https://files.pythonhosted.org/packages/9b/55/f24e3b801d2e108c48aa2b1b59bb791b5cffba89465cbbf66fc98de89270/protobuf-5.28.2-py3-none-any.whl", hash = "sha256:52235802093bd8a2811abbe8bf0ab9c5f54cca0a751fdd3f6ac2a21438bffece", size = 169566 }, ] [[package]] @@ -4525,11 +4525,11 @@ wheels = [ [[package]] name = "pyreadline3" -version = "3.5.2" +version = "3.5.4" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e2/59/0ec5d342dcc3ce475781ca1a76080b9acaa187f85a52cf021bdfe86089a4/pyreadline3-3.5.2.tar.gz", hash = "sha256:ba82292e52c5a3bb256b291af0c40b457c1e8699cac9a873abbcaac8aef3a1bb", size = 90396 } +sdist = { url = "https://files.pythonhosted.org/packages/0f/49/4cea918a08f02817aabae639e3d0ac046fef9f9180518a3ad394e22da148/pyreadline3-3.5.4.tar.gz", hash = "sha256:8d57d53039a1c75adba8e50dd3d992b28143480816187ea5efbd5c78e6c885b7", size = 99839 } wheels = [ - { url = "https://files.pythonhosted.org/packages/9f/f9/c59c7bc50c3c4d6875b35e278b3e16e957d883fb2d7518d76f2c4a37fb97/pyreadline3-3.5.2-py3-none-any.whl", hash = "sha256:a87d56791e2965b2b187e2ea33dcf664600842c997c0623c95cf8ef07db83de9", size = 80399 }, + { url = "https://files.pythonhosted.org/packages/5a/dc/491b7661614ab97483abf2056be1deee4dc2490ecbf7bff9ab5cdbac86e1/pyreadline3-3.5.4-py3-none-any.whl", hash = "sha256:eaf8e6cc3c49bcccf145fc6067ba8643d1df34d604a1ec0eccbf7a18e6d3fae6", size = 83178 }, ] [[package]] @@ -4762,7 +4762,7 @@ wheels = [ [[package]] name = "pywinctl" -version = "0.4" +version = "0.4.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "ewmhlib", marker = "sys_platform == 'linux'" }, @@ -4774,7 +4774,7 @@ dependencies = [ { name = "typing-extensions" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/ff/53/a7234a6b6d0c5cf295950166498623046422a333d8af79a26552ab40b9a6/PyWinCtl-0.4-py3-none-any.whl", hash = "sha256:8c4a92bd57e35fd280c5c04f048cc822e236abffe2fa17351096b0e28907172d", size = 60338 }, + { url = "https://files.pythonhosted.org/packages/be/33/8e4f632210b28fc9e998a9ab990e7ed97ecd2800cc50038e3800e1d85dbe/PyWinCtl-0.4.1-py3-none-any.whl", hash = "sha256:4d875e22969e1c6239d8c73156193630aaab876366167b8d97716f956384b089", size = 63158 }, ] [[package]] @@ -4961,27 +4961,27 @@ wheels = [ [[package]] name = "ruff" -version = "0.6.5" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/96/3f/29b2d3d90f811f6fb5b90242309f4668cd8c2482aab86ffc23099000545b/ruff-0.6.5.tar.gz", hash = "sha256:4d32d87fab433c0cf285c3683dd4dae63be05fd7a1d65b3f5bf7cdd05a6b96fb", size = 2476127 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/64/05/cc62df44b5a0271b29f11d687aa89e85943e0d26e5bb773dbc1456d9885d/ruff-0.6.5-py3-none-linux_armv6l.whl", hash = "sha256:7e4e308f16e07c95fc7753fc1aaac690a323b2bb9f4ec5e844a97bb7fbebd748", size = 9770988 }, - { url = "https://files.pythonhosted.org/packages/09/3d/89dac56ab7053d5b7cba723c9cae1a29b7a2978174c67e2441525ee00343/ruff-0.6.5-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:932cd69eefe4daf8c7d92bd6689f7e8182571cb934ea720af218929da7bd7d69", size = 9423303 }, - { url = "https://files.pythonhosted.org/packages/70/76/dc04654d26beace866a3c9e0c87112304e3d6406e1ee8ca0d9bebbd82d91/ruff-0.6.5-py3-none-macosx_11_0_arm64.whl", hash = "sha256:3a8d42d11fff8d3143ff4da41742a98f8f233bf8890e9fe23077826818f8d680", size = 9134078 }, - { url = "https://files.pythonhosted.org/packages/da/52/6a492cffcd2c6e243043937ab52811b6ebb10cb5b77a68cc98e7676ceaef/ruff-0.6.5-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a50af6e828ee692fb10ff2dfe53f05caecf077f4210fae9677e06a808275754f", size = 10105094 }, - { url = "https://files.pythonhosted.org/packages/59/7c/fd76a583ae59a276537d71921d616a83ec7774027d0812049afb6af8a07f/ruff-0.6.5-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:794ada3400a0d0b89e3015f1a7e01f4c97320ac665b7bc3ade24b50b54cb2972", size = 9542751 }, - { url = "https://files.pythonhosted.org/packages/56/5b/4e8928fa11412b16ecf7d7755fe45db6dfa7abce32841f6aec33bae3a7da/ruff-0.6.5-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:381413ec47f71ce1d1c614f7779d88886f406f1fd53d289c77e4e533dc6ea200", size = 10358844 }, - { url = "https://files.pythonhosted.org/packages/bd/a8/315ea8f71b111c8fb2b681c88a3e7a707d74308eb1435dc6ee3e6637a286/ruff-0.6.5-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:52e75a82bbc9b42e63c08d22ad0ac525117e72aee9729a069d7c4f235fc4d276", size = 11075199 }, - { url = "https://files.pythonhosted.org/packages/d9/1c/3a3728d42db52bfe418d8c913b453531766be1383719573f2458e8b59990/ruff-0.6.5-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:09c72a833fd3551135ceddcba5ebdb68ff89225d30758027280968c9acdc7810", size = 10661186 }, - { url = "https://files.pythonhosted.org/packages/d4/0c/ae25e213461aab274822081923d747f02929d71843c42b8f56018a7ec636/ruff-0.6.5-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:800c50371bdcb99b3c1551d5691e14d16d6f07063a518770254227f7f6e8c178", size = 11747444 }, - { url = "https://files.pythonhosted.org/packages/c4/e3/9d0ff218c7663ab9d53abe02911bec03d32b8ced7f78c1c49c2af84903a2/ruff-0.6.5-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8e25ddd9cd63ba1f3bd51c1f09903904a6adf8429df34f17d728a8fa11174253", size = 10266302 }, - { url = "https://files.pythonhosted.org/packages/ac/03/f158cc24120bf277b0cd7906ba509a2db74531003663500a0d1781cd7448/ruff-0.6.5-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:7291e64d7129f24d1b0c947ec3ec4c0076e958d1475c61202497c6aced35dd19", size = 10104976 }, - { url = "https://files.pythonhosted.org/packages/91/d0/0bacdffc234e588ec05834186ad11ec8281a6ca598d0106892497bbcfa44/ruff-0.6.5-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:9ad7dfbd138d09d9a7e6931e6a7e797651ce29becd688be8a0d4d5f8177b4b0c", size = 9625374 }, - { url = "https://files.pythonhosted.org/packages/1a/ad/721003cde8abd9f50bff74acbcb21852531036451d48a1abddba4dd84025/ruff-0.6.5-py3-none-musllinux_1_2_i686.whl", hash = "sha256:005256d977021790cc52aa23d78f06bb5090dc0bfbd42de46d49c201533982ae", size = 9959661 }, - { url = "https://files.pythonhosted.org/packages/37/84/8d70a3eacaacb65b4bb1461fc1a59e37ff165152b7e507692109117c877f/ruff-0.6.5-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:482c1e6bfeb615eafc5899127b805d28e387bd87db38b2c0c41d271f5e58d8cc", size = 10327408 }, - { url = "https://files.pythonhosted.org/packages/54/7e/6b0a9ab30428a9e3d9607f6dd2e4fb743594d42bd1b6ba7b7b239acda921/ruff-0.6.5-py3-none-win32.whl", hash = "sha256:cf4d3fa53644137f6a4a27a2b397381d16454a1566ae5335855c187fbf67e4f5", size = 8012512 }, - { url = "https://files.pythonhosted.org/packages/d8/88/176f50162a219e3039f21e9e4323869fc62bf8d3afb4147a390d6c744bd8/ruff-0.6.5-py3-none-win_amd64.whl", hash = "sha256:3e42a57b58e3612051a636bc1ac4e6b838679530235520e8f095f7c44f706ff9", size = 8804438 }, - { url = "https://files.pythonhosted.org/packages/67/a0/1b488bbe35a7ff8296fdea1ec1a9c2676cecc7e42bda63860f9397d59140/ruff-0.6.5-py3-none-win_arm64.whl", hash = "sha256:51935067740773afdf97493ba9b8231279e9beef0f2a8079188c4776c25688e0", size = 8179780 }, +version = "0.6.7" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/8d/7c/3045a526c57cef4b5ec4d5d154692e31429749a49810a53e785de334c4f6/ruff-0.6.7.tar.gz", hash = "sha256:44e52129d82266fa59b587e2cd74def5637b730a69c4542525dfdecfaae38bd5", size = 3073785 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/22/c4/1c5c636f83f905c537785016e9cdd7a36df53c025a2d07940580ecb37bcf/ruff-0.6.7-py3-none-linux_armv6l.whl", hash = "sha256:08277b217534bfdcc2e1377f7f933e1c7957453e8a79764d004e44c40db923f2", size = 10336748 }, + { url = "https://files.pythonhosted.org/packages/84/d9/aa15a56be7ad796f4d7625362aff588f9fc013bbb7323a63571628a2cf2d/ruff-0.6.7-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:c6707a32e03b791f4448dc0dce24b636cbcdee4dd5607adc24e5ee73fd86c00a", size = 9958833 }, + { url = "https://files.pythonhosted.org/packages/27/25/5dd1c32bfc3ad3136c8ebe84312d1bdd2e6c908ac7f60692ec009b7050a8/ruff-0.6.7-py3-none-macosx_11_0_arm64.whl", hash = "sha256:533d66b7774ef224e7cf91506a7dafcc9e8ec7c059263ec46629e54e7b1f90ab", size = 9633369 }, + { url = "https://files.pythonhosted.org/packages/0e/3e/01b25484f3cb08fe6fddedf1f55f3f3c0af861a5b5f5082fbe60ab4b2596/ruff-0.6.7-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:17a86aac6f915932d259f7bec79173e356165518859f94649d8c50b81ff087e9", size = 10637415 }, + { url = "https://files.pythonhosted.org/packages/8a/c9/5bb9b849e4777e0f961de43edf95d2af0ab34999a5feee957be096887876/ruff-0.6.7-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:b3f8822defd260ae2460ea3832b24d37d203c3577f48b055590a426a722d50ef", size = 10097389 }, + { url = "https://files.pythonhosted.org/packages/52/cf/e08f1c290c7d848ddfb2ae811f24f445c18e1d3e50e01c38ffa7f5a50494/ruff-0.6.7-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9ba4efe5c6dbbb58be58dd83feedb83b5e95c00091bf09987b4baf510fee5c99", size = 10951440 }, + { url = "https://files.pythonhosted.org/packages/a2/2d/ca8aa0da5841913c302d8034c6de0ce56c401c685184d8dd23cfdd0003f9/ruff-0.6.7-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:525201b77f94d2b54868f0cbe5edc018e64c22563da6c5c2e5c107a4e85c1c0d", size = 11708900 }, + { url = "https://files.pythonhosted.org/packages/89/fc/9a83c57baee977c82392e19a328b52cebdaf61601af3d99498e278ef5104/ruff-0.6.7-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8854450839f339e1049fdbe15d875384242b8e85d5c6947bb2faad33c651020b", size = 11258892 }, + { url = "https://files.pythonhosted.org/packages/d3/a3/254cc7afef702c68ae9079290c2a1477ae0e81478589baf745026d8a4eb5/ruff-0.6.7-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2f0b62056246234d59cbf2ea66e84812dc9ec4540518e37553513392c171cb18", size = 12367932 }, + { url = "https://files.pythonhosted.org/packages/9f/55/53f10c1bd8c3b2ae79aed18e62b22c6346f9296aa0ec80489b8442bd06a9/ruff-0.6.7-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6b1462fa56c832dc0cea5b4041cfc9c97813505d11cce74ebc6d1aae068de36b", size = 10838629 }, + { url = "https://files.pythonhosted.org/packages/84/72/fb335c2b25432c63d15383ecbd7bfc1915e68cdf8d086a08042052144255/ruff-0.6.7-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:02b083770e4cdb1495ed313f5694c62808e71764ec6ee5db84eedd82fd32d8f5", size = 10648824 }, + { url = "https://files.pythonhosted.org/packages/92/a8/d57e135a8ad99b6a0c6e2a5c590bcacdd57f44340174f4409c3893368610/ruff-0.6.7-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:0c05fd37013de36dfa883a3854fae57b3113aaa8abf5dea79202675991d48624", size = 10174368 }, + { url = "https://files.pythonhosted.org/packages/a7/6f/1a30a6e81dcf2fa9ff3f7011eb87fe76c12a3c6bba74db6a1977d763de1f/ruff-0.6.7-py3-none-musllinux_1_2_i686.whl", hash = "sha256:f49c9caa28d9bbfac4a637ae10327b3db00f47d038f3fbb2195c4d682e925b14", size = 10514383 }, + { url = "https://files.pythonhosted.org/packages/0b/25/df6f2575bc9fe43a6dedfd8dee12896f09a94303e2c828d5f85856bb69a0/ruff-0.6.7-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:a0e1655868164e114ba43a908fd2d64a271a23660195017c17691fb6355d59bb", size = 10902340 }, + { url = "https://files.pythonhosted.org/packages/68/62/f2c1031e2fb7b94f9bf0603744e73db4ef90081b0eb1b9639a6feefd52ea/ruff-0.6.7-py3-none-win32.whl", hash = "sha256:a939ca435b49f6966a7dd64b765c9df16f1faed0ca3b6f16acdf7731969deb35", size = 8448033 }, + { url = "https://files.pythonhosted.org/packages/97/80/193d1604a3f7d75eb1b2a7ce6bf0fdbdbc136889a65caacea6ffb29501b1/ruff-0.6.7-py3-none-win_amd64.whl", hash = "sha256:590445eec5653f36248584579c06252ad2e110a5d1f32db5420de35fb0e1c977", size = 9273543 }, + { url = "https://files.pythonhosted.org/packages/8e/a8/4abb5a9f58f51e4b1ea386be5ab2e547035bc1ee57200d1eca2f8909a33e/ruff-0.6.7-py3-none-win_arm64.whl", hash = "sha256:b28f0d5e2f771c1fe3c7a45d3f53916fc74a480698c4b5731f0bea61e52137c8", size = 8618044 }, ] [[package]] @@ -5146,14 +5146,14 @@ sdist = { url = "https://files.pythonhosted.org/packages/c7/d9/401c0a7be089e0282 [[package]] name = "sympy" -version = "1.13.2" +version = "1.13.3" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "mpmath" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/94/15/4a041424c7187f41cce678f5a02189b244e9aac61a18b45cd415a3a470f3/sympy-1.13.2.tar.gz", hash = "sha256:401449d84d07be9d0c7a46a64bd54fe097667d5e7181bfe67ec777be9e01cb13", size = 7532926 } +sdist = { url = "https://files.pythonhosted.org/packages/11/8a/5a7fd6284fa8caac23a26c9ddf9c30485a48169344b4bd3b0f02fef1890f/sympy-1.13.3.tar.gz", hash = "sha256:b27fd2c6530e0ab39e275fc9b683895367e51d5da91baa8d3d64db2565fec4d9", size = 7533196 } wheels = [ - { url = "https://files.pythonhosted.org/packages/c1/f9/6845bf8fca0eaf847da21c5d5bc6cd92797364662824a11d3f836423a1a5/sympy-1.13.2-py3-none-any.whl", hash = "sha256:c51d75517712f1aed280d4ce58506a4a88d635d6b5dd48b39102a7ae1f3fcfe9", size = 6189289 }, + { url = "https://files.pythonhosted.org/packages/99/ff/c87e0622b1dadea79d2fb0b25ade9ed98954c9033722eb707053d310d4f3/sympy-1.13.3-py3-none-any.whl", hash = "sha256:54612cf55a62755ee71824ce692986f23c88ffa77207b30c1368eda4a7060f73", size = 6189483 }, ] [[package]] From fda0b70c10d5e7ff0b9a8d769e09a056ae1db058 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 25 Sep 2024 06:06:04 +0800 Subject: [PATCH 134/214] ui/hud: add Q_OBJECT macro (#33638) add Q_OBJECT --- selfdrive/ui/qt/onroad/hud.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/ui/qt/onroad/hud.h b/selfdrive/ui/qt/onroad/hud.h index 9151b23a4d..0b1220a27a 100644 --- a/selfdrive/ui/qt/onroad/hud.h +++ b/selfdrive/ui/qt/onroad/hud.h @@ -4,6 +4,8 @@ #include "selfdrive/ui/ui.h" class HudRenderer : public QObject { + Q_OBJECT + public: HudRenderer(); void updateState(const UIState &s); From 17b29f42af73aca89e00cded4877b0f809fa6112 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Tue, 24 Sep 2024 20:44:49 -0400 Subject: [PATCH 135/214] tools: notebook for HKG alt message validation (#33647) --- .../examples/hkg_canfd_gear_message.ipynb | 277 ++++++++++++++++++ 1 file changed, 277 insertions(+) create mode 100644 tools/car_porting/examples/hkg_canfd_gear_message.ipynb diff --git a/tools/car_porting/examples/hkg_canfd_gear_message.ipynb b/tools/car_porting/examples/hkg_canfd_gear_message.ipynb new file mode 100644 index 0000000000..5fdbdda684 --- /dev/null +++ b/tools/car_porting/examples/hkg_canfd_gear_message.ipynb @@ -0,0 +1,277 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 62, + "id": "228a6736-de31-4255-9d72-a6ff391b968d", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Found 6 qualifying vehicles:\n", + " KIA_EV6\n", + " HYUNDAI_KONA_EV_2ND_GEN\n", + " HYUNDAI_IONIQ_5\n", + " KIA_NIRO_EV_2ND_GEN\n", + " HYUNDAI_IONIQ_6\n", + " GENESIS_GV60_EV_1ST_GEN\n" + ] + } + ], + "source": [ + "from opendbc.car import structs\n", + "from opendbc.car.hyundai.values import CAR, HyundaiFlags\n", + "from opendbc.car.hyundai.fingerprints import FW_VERSIONS\n", + "\n", + "TEST_PLATFORMS = set(CAR.with_flags(HyundaiFlags.CANFD)) & set(CAR.with_flags(HyundaiFlags.EV)) # CAN-FD electric vehicles only\n", + "#TEST_PLATFORMS = set(CAR.with_flags(HyundaiFlags.CANFD)) - set(CAR.with_flags(HyundaiFlags.EV)) # CAN-FD hybrid and ICE vehicles only\n", + "\n", + "print(f\"Found {len(TEST_PLATFORMS)} qualifying vehicles:\")\n", + "for platform in TEST_PLATFORMS:\n", + " print(f\" {platform}\")" + ] + }, + { + "cell_type": "code", + "execution_count": 63, + "id": "ed1c8aec-c274-4c61-b83d-711ea194bf86", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Collecting segments from commaCarSegments dataset:\n", + "Got 1300 segments for platform KIA_EV6, sampling 5 segments\n", + "Got 9 segments for platform HYUNDAI_KONA_EV_2ND_GEN, sampling 5 segments\n", + "Got 1570 segments for platform HYUNDAI_IONIQ_5, sampling 5 segments\n", + "Got 34 segments for platform KIA_NIRO_EV_2ND_GEN, sampling 5 segments\n", + "Got 974 segments for platform HYUNDAI_IONIQ_6, sampling 5 segments\n", + "Got 157 segments for platform GENESIS_GV60_EV_1ST_GEN, sampling 5 segments\n", + "Collected 30 segments for analysis\n" + ] + } + ], + "source": [ + "import random\n", + "\n", + "from openpilot.tools.lib.logreader import LogReader\n", + "from openpilot.tools.lib.comma_car_segments import get_comma_car_segments_database\n", + "from opendbc.car.hyundai.values import CAR\n", + "\n", + "database = get_comma_car_segments_database()\n", + "TEST_SEGMENTS = []\n", + "\n", + "MAX_SEGS_PER_PLATFORM = 5 # TODO: Increase this to search more segments\n", + "\n", + "print(\"Collecting segments from commaCarSegments dataset:\")\n", + "for platform in TEST_PLATFORMS:\n", + " assert(platform in database)\n", + " #if platform not in database:\n", + " # print(f\"Skipping platform: {platform}, no data available\")\n", + " # continue\n", + " \n", + " all_segments = database[platform]\n", + "\n", + " NUM_SEGMENTS = min(len(all_segments), MAX_SEGS_PER_PLATFORM)\n", + "\n", + " print(f\"Got {len(all_segments)} segments for platform {platform}, sampling {NUM_SEGMENTS} segments\")\n", + "\n", + " TEST_SEGMENTS.extend(random.sample(all_segments, NUM_SEGMENTS))\n", + "\n", + "print(f\"Collected {len(TEST_SEGMENTS)} segments for analysis\")\n" + ] + }, + { + "cell_type": "code", + "execution_count": 64, + "id": "0c75e8f2-4f5f-4f89-b8db-5223a6534a9f", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Analyzing segment ff2bd20623fcaeaa/2023-11-26--16-27-04/5/s for KIA EV6 2022\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 3f1a6480f940cf9a/2024-01-10--23-06-11/16/s for KIA EV6 2022\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment b0a9998109ed0053/2023-12-15--11-10-18/12/s for KIA EV6 2022\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 6e14aa2ed85025df/2023-11-15--13-18-12/24/s for KIA EV6 2022\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment a43f21df3a1ca12d/2024-01-25--08-56-22/16/s for KIA EV6 2022\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 1618132d68afc876/2023-12-05--13-49-24/11/s for HYUNDAI KONA ELECTRIC 2ND GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 1618132d68afc876/2023-11-26--12-31-18/17/s for HYUNDAI KONA ELECTRIC 2ND GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 1618132d68afc876/2023-12-05--11-51-44/3/s for HYUNDAI KONA ELECTRIC 2ND GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 1618132d68afc876/2023-08-27--09-32-14/13/s for HYUNDAI KONA 2ND GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 1618132d68afc876/2024-01-25--15-07-04/24/s for HYUNDAI KONA ELECTRIC 2ND GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 223780ed74116bc2/2023-11-16--09-44-56/15/s for HYUNDAI IONIQ 5 2022\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment ba9951252624f37d/2024-01-20--22-33-23/118/s for HYUNDAI IONIQ 5 2022\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 8379b28e51ceb3b1/2023-11-09--23-21-58/92/s for HYUNDAI IONIQ 5 2022\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 26fac43e27cd6091/2023-11-06--12-23-21/9/s for HYUNDAI IONIQ 5 2022\n", + " GEAR_SHIFTER gear=1.0\n", + " ACCELERATOR gear=0.0\n", + "Analyzing segment 5edb897a0ec7a477/2024-01-13--20-41-36/101/s for HYUNDAI IONIQ 5 2022\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 66cf8ea23b7c2789/2023-12-04--13-48-53/5/s for KIA NIRO EV 2ND GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment b153671049a867b3/2023-12-10--20-31-37/2/s for KIA NIRO EV 2ND GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment b153671049a867b3/2023-12-03--21-08-30/14/s for KIA NIRO EV 2ND GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment b153671049a867b3/2023-11-07--19-52-23/0/s for KIA NIRO EV 2ND GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment b153671049a867b3/2023-07-12--19-25-18/6/s for KIA NIRO EV 2ND GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 9ea4578ee2b1abcb/2023-11-18--07-59-26/11/s for HYUNDAI IONIQ 6 2023\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 0ad7facc77922c3e/2023-12-21--17-47-25/18/s for HYUNDAI IONIQ 6 2023\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 26968f888e7330d3/2024-01-02--11-18-37/8/s for HYUNDAI IONIQ 6 2023\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 9ea4578ee2b1abcb/2023-11-27--21-03-24/33/s for HYUNDAI IONIQ 6 2023\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment df7fdd56970d90fe/2024-01-07--01-04-39/26/s for HYUNDAI IONIQ 6 2023\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 94542b2d06f7a9a6/2023-12-11--14-45-44/0/s for GENESIS GV60 ELECTRIC 1ST GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 94542b2d06f7a9a6/2023-12-11--20-57-09/8/s for GENESIS GV60 ELECTRIC 1ST GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 94542b2d06f7a9a6/2024-01-03--12-52-38/5/s for GENESIS GV60 ELECTRIC 1ST GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 94542b2d06f7a9a6/2024-01-19--19-57-52/47/s for GENESIS GV60 ELECTRIC 1ST GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analyzing segment 94542b2d06f7a9a6/2024-01-03--13-01-23/1/s for GENESIS GV60 ELECTRIC 1ST GEN\n", + " GEAR_SHIFTER gear=4.0\n", + " ACCELERATOR gear=5.0\n", + "Analysis finished\n" + ] + } + ], + "source": [ + "import copy\n", + "import matplotlib.pyplot as plt\n", + "import numpy as np\n", + "\n", + "from opendbc.can.parser import CANParser\n", + "from opendbc.car.hyundai.values import DBC\n", + "from opendbc.car.hyundai.hyundaicanfd import CanBus\n", + "\n", + "from openpilot.selfdrive.pandad import can_capnp_to_list\n", + "from openpilot.tools.lib.logreader import LogReader\n", + "\n", + "message_names = [\"GEAR_SHIFTER\", \"ACCELERATOR\", \"GEAR\", \"GEAR_ALT\", \"GEAR_ALT_2\"]\n", + "\n", + "for segment in TEST_SEGMENTS:\n", + " lr = LogReader(segment)\n", + " CP = lr.first(\"carParams\")\n", + " if CP is None:\n", + " continue\n", + "\n", + " can_msgs = [msg for msg in lr if msg.which() == \"can\"]\n", + " parser_messages = []\n", + " for name in message_names:\n", + " parser_messages.append((name, 0))\n", + " cp = CANParser(DBC[platform][\"pt\"], parser_messages, CanBus(CP).ECAN)\n", + "\n", + " parsed_message_history = []\n", + " examples = []\n", + "\n", + " for msg in can_msgs:\n", + " cp.update_strings(can_capnp_to_list([msg.as_builder().to_bytes()]))\n", + " parsed_message_history.append(copy.copy(cp.vl))\n", + "\n", + " print(f\"Analyzing segment {segment:<44} for {CP.carFingerprint}\")\n", + " for name in message_names:\n", + " if parsed_message_history[0][name][\"CHECKSUM\"] != 0: # Message is present for this segment\n", + " gear_prev = parsed_message_history[0][name][\"GEAR\"]\n", + " print(f\" {name:<15} gear={gear_prev}\")\n", + " for i, parsed_messages in enumerate(parsed_message_history):\n", + " gear = parsed_messages[name][\"GEAR\"]\n", + " if gear != gear_prev:\n", + " print(f\" *** Signal transition found! ***\")\n", + " examples.append(i)\n", + " gear_prev = gear\n", + "\n", + "print(f\"Analysis finished\")\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "7724dd97-f62e-4fd3-9f64-63d49be669d2", + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "9f393e00-8efd-40fb-a41e-d312531a83e8", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.3" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} From 903ea9d8f314027f50a73e69e30c2ceb898e75d5 Mon Sep 17 00:00:00 2001 From: James <91348155+FrogAi@users.noreply.github.com> Date: Tue, 24 Sep 2024 19:39:00 -0700 Subject: [PATCH 136/214] Fix double "DEPRECATED" in "longitudinalActuatorDelayLowerBound" (#33648) Fix double "DEPRECATED" in "longitudinalActuatorDelayLowerBoundDEPRECATEDDEPRECATED" --- cereal/car.capnp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index d08d89c1d9..6af474c0ee 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -714,5 +714,5 @@ struct CarParams { brakeMaxVDEPRECATED @16 :List(Float32); directAccelControlDEPRECATED @30 :Bool; maxSteeringAngleDegDEPRECATED @54 :Float32; - longitudinalActuatorDelayLowerBoundDEPRECATEDDEPRECATED @61 :Float32; + longitudinalActuatorDelayLowerBoundDEPRECATED @61 :Float32; } From 92fff4d4863f1da320c5f684dd3284256c2aa22b Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Tue, 24 Sep 2024 20:09:07 -0700 Subject: [PATCH 137/214] always on DM: filter green alert at low speeds (#33644) * disable visual too under 25 * seperate * rename --- selfdrive/monitoring/helpers.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/selfdrive/monitoring/helpers.py b/selfdrive/monitoring/helpers.py index 2a7979221a..54c81daeab 100644 --- a/selfdrive/monitoring/helpers.py +++ b/selfdrive/monitoring/helpers.py @@ -57,7 +57,7 @@ class DRIVER_MONITOR_SETTINGS: self._POSESTD_THRESHOLD = 0.3 self._HI_STD_FALLBACK_TIME = int(10 / self._DT_DMON) # fall back to wheel touch if model is uncertain for 10s self._DISTRACTED_FILTER_TS = 0.25 # 0.6Hz - self._ALWAYS_ON_ALERT_MIN_SPEED = 7 + self._ALWAYS_ON_ALERT_MIN_SPEED = 11 self._POSE_CALIB_MIN_SPEED = 13 # 30 mph self._POSE_OFFSET_MIN_COUNT = int(60 / self._DT_DMON) # valid data counts before calibration completes, 1min cumulative @@ -337,9 +337,9 @@ class DriverMonitoring: _reaching_audible = self.awareness - self.step_change <= self.threshold_prompt _reaching_terminal = self.awareness - self.step_change <= 0 - standstill_exemption = standstill and _reaching_audible + standstill_orange_exemption = standstill and _reaching_audible always_on_red_exemption = always_on_valid and not op_engaged and _reaching_terminal - always_on_lowspeed_exemption = always_on_valid and not op_engaged and car_speed < self.settings._ALWAYS_ON_ALERT_MIN_SPEED and _reaching_audible + always_on_lowspeed_exemption = always_on_valid and not op_engaged and car_speed < self.settings._ALWAYS_ON_ALERT_MIN_SPEED certainly_distracted = self.driver_distraction_filter.x > 0.63 and self.driver_distracted and self.face_detected maybe_distracted = self.hi_stds > self.settings._HI_STD_FALLBACK_TIME or not self.face_detected @@ -347,7 +347,7 @@ class DriverMonitoring: if certainly_distracted or maybe_distracted: # should always be counting if distracted unless at standstill (lowspeed for always-on) and reaching orange # also will not be reaching 0 if DM is active when not engaged - if not (standstill_exemption or always_on_red_exemption or always_on_lowspeed_exemption): + if not (standstill_orange_exemption or always_on_red_exemption or (always_on_lowspeed_exemption and _reaching_audible)): self.awareness = max(self.awareness - self.step_change, -0.1) alert = None @@ -360,7 +360,7 @@ class DriverMonitoring: elif self.awareness <= self.threshold_prompt: # prompt orange alert alert = EventName.promptDriverDistracted if self.active_monitoring_mode else EventName.promptDriverUnresponsive - elif self.awareness <= self.threshold_pre: + elif self.awareness <= self.threshold_pre and not always_on_lowspeed_exemption: # pre green alert alert = EventName.preDriverDistracted if self.active_monitoring_mode else EventName.preDriverUnresponsive From b4865dc4fdcd585fb7c9020ce0ca43dbf0eb1328 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 24 Sep 2024 20:33:26 -0700 Subject: [PATCH 138/214] Toyota: prevent lagged gas after heavy braking (#33649) * bump * update docs --- docs/CARS.md | 4 ++-- opendbc_repo | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 02ed887864..e94df79787 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -279,8 +279,8 @@ A supported vehicle is one that just works when you install a comma device. All |Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Volkswagen|Grand California 2019-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Jetta 2018-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Jetta GLI 2021-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Jetta 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Jetta GLI 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Volkswagen|Passat 2015-22[10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| diff --git a/opendbc_repo b/opendbc_repo index 0b7648ad2c..bda4ad475a 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 0b7648ad2cb048b5f55a338dbd26cada01671124 +Subproject commit bda4ad475aaf7a92f677ac2d50b6b7af0ffdf5fc From 87b30b291167580aae3564756441e557157f3505 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 25 Sep 2024 11:01:57 -0700 Subject: [PATCH 139/214] tici: max GPU power (#33650) --- system/hardware/tici/hardware.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index eb524dbafa..03e973fd1a 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -431,8 +431,8 @@ class Tici(HardwareBase): # *** GPU config *** # https://github.com/commaai/agnos-kernel-sdm845/blob/master/arch/arm64/boot/dts/qcom/sdm845-gpu.dtsi#L216 - sudo_write("1", "/sys/class/kgsl/kgsl-3d0/min_pwrlevel") - sudo_write("1", "/sys/class/kgsl/kgsl-3d0/max_pwrlevel") + sudo_write("0", "/sys/class/kgsl/kgsl-3d0/min_pwrlevel") + sudo_write("0", "/sys/class/kgsl/kgsl-3d0/max_pwrlevel") sudo_write("1", "/sys/class/kgsl/kgsl-3d0/force_bus_on") sudo_write("1", "/sys/class/kgsl/kgsl-3d0/force_clk_on") sudo_write("1", "/sys/class/kgsl/kgsl-3d0/force_rail_on") From 6950abb38e24202242cc4b8ba65674b1cdeec477 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 25 Sep 2024 11:16:30 -0700 Subject: [PATCH 140/214] jenkins: tmp disable test_time_to_onroad --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 799b4fbbeb..eb39781cb8 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -147,7 +147,7 @@ node { ["build openpilot", "cd system/manager && ./build.py"], ["check dirty", "release/check-dirty.sh"], ["onroad tests", "pytest selfdrive/test/test_onroad.py -s"], - ["time to onroad", "pytest selfdrive/test/test_time_to_onroad.py"], + //["time to onroad", "pytest selfdrive/test/test_time_to_onroad.py"], ]) }, 'HW + Unit Tests': { From 4490608e3c0c85038a148c939d43434865134b96 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 25 Sep 2024 11:17:50 -0700 Subject: [PATCH 141/214] Update RELEASES.md --- RELEASES.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/RELEASES.md b/RELEASES.md index 57f6979117..d69d9f8dcc 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,6 +1,8 @@ Version 0.9.8 (2024-XX-XX) ======================== +* New Tomb Raider driving model * Added toggle to enable driver monitoring even when openpilot is not engaged +* New Toyota TSS2 longitudinal tune Version 0.9.7 (2024-06-13) ======================== From ba7039785c050bb880d7da7f32c303c9d6a89c29 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Wed, 25 Sep 2024 14:21:19 -0700 Subject: [PATCH 142/214] More reasonable model replay tolerance (#33652) --- selfdrive/test/process_replay/model_replay.py | 28 ++++++++++++------- 1 file changed, 18 insertions(+), 10 deletions(-) diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index bb7c0b0a8e..269cf464a3 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -112,16 +112,24 @@ if __name__ == "__main__": 'driverStateV2.dspExecutionTime' ] if PC: - ignore += [ - 'modelV2.laneLines.0.t', - 'modelV2.laneLines.1.t', - 'modelV2.laneLines.2.t', - 'modelV2.laneLines.3.t', - 'modelV2.roadEdges.0.t', - 'modelV2.roadEdges.1.t', - ] - # TODO this tolerance is absurdly large - tolerance = 2.0 if PC else None + # TODO We ignore whole bunch so we can compare important stuff + # like posenet with reasonable tolerance + ignore += ['modelV2.acceleration.x', + 'modelV2.position.x', + 'modelV2.position.xStd', + 'modelV2.position.y', + 'modelV2.position.yStd', + 'modelV2.position.z', + 'modelV2.position.zStd', + 'drivingModelData.path.xCoefficients',] + for i in range(3): + for field in ('x', 'y', 'v', 'a'): + ignore.append(f'modelV2.leadsV3.{i}.{field}') + ignore.append(f'modelV2.leadsV3.{i}.{field}Std') + for i in range(4): + for field in ('x', 'y', 'z', 't'): + ignore.append(f'modelV2.laneLines.{i}.{field}') + tolerance = .2 if PC else None results: Any = {TEST_ROUTE: {}} log_paths: Any = {TEST_ROUTE: {"models": {'ref': BASE_URL + log_fn, 'new': log_fn}}} results[TEST_ROUTE]["models"] = compare_logs(cmp_log, log_msgs, tolerance=tolerance, ignore_fields=ignore) From 4851dacd063a742983446224b7ea84bced7a4943 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Thu, 26 Sep 2024 09:51:04 -0700 Subject: [PATCH 143/214] camerad: Replace ox LUT with function (#33653) * fast eh * need * ; --------- Co-authored-by: Comma Device --- system/camerad/sensors/ox03c10_cl.h | 43 +++++++++++++++-------------- 1 file changed, 23 insertions(+), 20 deletions(-) diff --git a/system/camerad/sensors/ox03c10_cl.h b/system/camerad/sensors/ox03c10_cl.h index 21441902fc..b8d331f50d 100644 --- a/system/camerad/sensors/ox03c10_cl.h +++ b/system/camerad/sensors/ox03c10_cl.h @@ -4,28 +4,31 @@ #define BLACK_LVL 64 #define VIGNETTE_RSZ 1.0f -constant float ox03c10_lut[] = { - 0.0000e+00, 5.9488e-08, 1.1898e-07, 1.7846e-07, 2.3795e-07, 2.9744e-07, 3.5693e-07, 4.1642e-07, 4.7591e-07, 5.3539e-07, 5.9488e-07, 6.5437e-07, 7.1386e-07, 7.7335e-07, 8.3284e-07, 8.9232e-07, 9.5181e-07, 1.0113e-06, 1.0708e-06, 1.1303e-06, 1.1898e-06, 1.2493e-06, 1.3087e-06, 1.3682e-06, 1.4277e-06, 1.4872e-06, 1.5467e-06, 1.6062e-06, 1.6657e-06, 1.7252e-06, 1.7846e-06, 1.8441e-06, 1.9036e-06, 1.9631e-06, 2.0226e-06, 2.0821e-06, 2.1416e-06, 2.2011e-06, 2.2606e-06, 2.3200e-06, 2.3795e-06, 2.4390e-06, 2.4985e-06, 2.5580e-06, 2.6175e-06, 2.6770e-06, 2.7365e-06, 2.7959e-06, 2.8554e-06, 2.9149e-06, 2.9744e-06, 3.0339e-06, 3.0934e-06, 3.1529e-06, 3.2124e-06, 3.2719e-06, 3.3313e-06, 3.3908e-06, 3.4503e-06, 3.5098e-06, 3.5693e-06, 3.6288e-06, 3.6883e-06, 3.7478e-06, 3.8072e-06, 3.8667e-06, 3.9262e-06, 3.9857e-06, 4.0452e-06, 4.1047e-06, 4.1642e-06, 4.2237e-06, 4.2832e-06, 4.3426e-06, 4.4021e-06, 4.4616e-06, 4.5211e-06, 4.5806e-06, 4.6401e-06, 4.6996e-06, 4.7591e-06, 4.8185e-06, 4.8780e-06, 4.9375e-06, 4.9970e-06, 5.0565e-06, 5.1160e-06, 5.1755e-06, 5.2350e-06, 5.2945e-06, 5.3539e-06, 5.4134e-06, 5.4729e-06, 5.5324e-06, 5.5919e-06, 5.6514e-06, 5.7109e-06, 5.7704e-06, 5.8298e-06, 5.8893e-06, 5.9488e-06, 6.0083e-06, 6.0678e-06, 6.1273e-06, 6.1868e-06, 6.2463e-06, 6.3058e-06, 6.3652e-06, 6.4247e-06, 6.4842e-06, 6.5437e-06, 6.6032e-06, 6.6627e-06, 6.7222e-06, 6.7817e-06, 6.8411e-06, 6.9006e-06, 6.9601e-06, 7.0196e-06, 7.0791e-06, 7.1386e-06, 7.1981e-06, 7.2576e-06, 7.3171e-06, 7.3765e-06, 7.4360e-06, 7.4955e-06, 7.5550e-06, 7.6145e-06, 7.6740e-06, 7.7335e-06, 7.7930e-06, 7.8524e-06, 7.9119e-06, 7.9714e-06, 8.0309e-06, 8.0904e-06, 8.1499e-06, 8.2094e-06, 8.2689e-06, 8.3284e-06, 8.3878e-06, 8.4473e-06, 8.5068e-06, 8.5663e-06, 8.6258e-06, 8.6853e-06, 8.7448e-06, 8.8043e-06, 8.8637e-06, 8.9232e-06, 8.9827e-06, 9.0422e-06, 9.1017e-06, 9.1612e-06, 9.2207e-06, 9.2802e-06, 9.3397e-06, 9.3991e-06, 9.4586e-06, 9.5181e-06, 9.5776e-06, 9.6371e-06, 9.6966e-06, 9.7561e-06, 9.8156e-06, 9.8750e-06, 9.9345e-06, 9.9940e-06, 1.0054e-05, 1.0113e-05, 1.0172e-05, 1.0232e-05, 1.0291e-05, 1.0351e-05, 1.0410e-05, 1.0470e-05, 1.0529e-05, 1.0589e-05, 1.0648e-05, 1.0708e-05, 1.0767e-05, 1.0827e-05, 1.0886e-05, 1.0946e-05, 1.1005e-05, 1.1065e-05, 1.1124e-05, 1.1184e-05, 1.1243e-05, 1.1303e-05, 1.1362e-05, 1.1422e-05, 1.1481e-05, 1.1541e-05, 1.1600e-05, 1.1660e-05, 1.1719e-05, 1.1779e-05, 1.1838e-05, 1.1898e-05, 1.1957e-05, 1.2017e-05, 1.2076e-05, 1.2136e-05, 1.2195e-05, 1.2255e-05, 1.2314e-05, 1.2374e-05, 1.2433e-05, 1.2493e-05, 1.2552e-05, 1.2612e-05, 1.2671e-05, 1.2730e-05, 1.2790e-05, 1.2849e-05, 1.2909e-05, 1.2968e-05, 1.3028e-05, 1.3087e-05, 1.3147e-05, 1.3206e-05, 1.3266e-05, 1.3325e-05, 1.3385e-05, 1.3444e-05, 1.3504e-05, 1.3563e-05, 1.3623e-05, 1.3682e-05, 1.3742e-05, 1.3801e-05, 1.3861e-05, 1.3920e-05, 1.3980e-05, 1.4039e-05, 1.4099e-05, 1.4158e-05, 1.4218e-05, 1.4277e-05, 1.4337e-05, 1.4396e-05, 1.4456e-05, 1.4515e-05, 1.4575e-05, 1.4634e-05, 1.4694e-05, 1.4753e-05, 1.4813e-05, 1.4872e-05, 1.4932e-05, 1.4991e-05, 1.5051e-05, 1.5110e-05, 1.5169e-05, // NOLINT - 1.5229e-05, 1.5288e-05, 1.5348e-05, 1.5407e-05, 1.5467e-05, 1.5526e-05, 1.5586e-05, 1.5645e-05, 1.5705e-05, 1.5764e-05, 1.5824e-05, 1.5883e-05, 1.5943e-05, 1.6002e-05, 1.6062e-05, 1.6121e-05, 1.6181e-05, 1.6240e-05, 1.6300e-05, 1.6359e-05, 1.6419e-05, 1.6478e-05, 1.6538e-05, 1.6597e-05, 1.6657e-05, 1.6716e-05, 1.6776e-05, 1.6835e-05, 1.6895e-05, 1.6954e-05, 1.7014e-05, 1.7073e-05, 1.7133e-05, 1.7192e-05, 1.7252e-05, 1.7311e-05, 1.7371e-05, 1.7430e-05, 1.7490e-05, 1.7549e-05, 1.7609e-05, 1.7668e-05, 1.7727e-05, 1.7787e-05, 1.7846e-05, 1.7906e-05, 1.7965e-05, 1.8025e-05, 1.8084e-05, 1.8144e-05, 1.8203e-05, 1.8263e-05, 1.8322e-05, 1.8382e-05, 1.8441e-05, 1.8501e-05, 1.8560e-05, 1.8620e-05, 1.8679e-05, 1.8739e-05, 1.8798e-05, 1.8858e-05, 1.8917e-05, 1.8977e-05, 1.9036e-05, 1.9096e-05, 1.9155e-05, 1.9215e-05, 1.9274e-05, 1.9334e-05, 1.9393e-05, 1.9453e-05, 1.9512e-05, 1.9572e-05, 1.9631e-05, 1.9691e-05, 1.9750e-05, 1.9810e-05, 1.9869e-05, 1.9929e-05, 1.9988e-05, 2.0048e-05, 2.0107e-05, 2.0167e-05, 2.0226e-05, 2.0285e-05, 2.0345e-05, 2.0404e-05, 2.0464e-05, 2.0523e-05, 2.0583e-05, 2.0642e-05, 2.0702e-05, 2.0761e-05, 2.0821e-05, 2.0880e-05, 2.0940e-05, 2.0999e-05, 2.1059e-05, 2.1118e-05, 2.1178e-05, 2.1237e-05, 2.1297e-05, 2.1356e-05, 2.1416e-05, 2.1475e-05, 2.1535e-05, 2.1594e-05, 2.1654e-05, 2.1713e-05, 2.1773e-05, 2.1832e-05, 2.1892e-05, 2.1951e-05, 2.2011e-05, 2.2070e-05, 2.2130e-05, 2.2189e-05, 2.2249e-05, 2.2308e-05, 2.2368e-05, 2.2427e-05, 2.2487e-05, 2.2546e-05, 2.2606e-05, 2.2665e-05, 2.2725e-05, 2.2784e-05, 2.2843e-05, 2.2903e-05, 2.2962e-05, 2.3022e-05, 2.3081e-05, 2.3141e-05, 2.3200e-05, 2.3260e-05, 2.3319e-05, 2.3379e-05, 2.3438e-05, 2.3498e-05, 2.3557e-05, 2.3617e-05, 2.3676e-05, 2.3736e-05, 2.3795e-05, 2.3855e-05, 2.3914e-05, 2.3974e-05, 2.4033e-05, 2.4093e-05, 2.4152e-05, 2.4212e-05, 2.4271e-05, 2.4331e-05, 2.4390e-05, 2.4450e-05, 2.4509e-05, 2.4569e-05, 2.4628e-05, 2.4688e-05, 2.4747e-05, 2.4807e-05, 2.4866e-05, 2.4926e-05, 2.4985e-05, 2.5045e-05, 2.5104e-05, 2.5164e-05, 2.5223e-05, 2.5282e-05, 2.5342e-05, 2.5401e-05, 2.5461e-05, 2.5520e-05, 2.5580e-05, 2.5639e-05, 2.5699e-05, 2.5758e-05, 2.5818e-05, 2.5877e-05, 2.5937e-05, 2.5996e-05, 2.6056e-05, 2.6115e-05, 2.6175e-05, 2.6234e-05, 2.6294e-05, 2.6353e-05, 2.6413e-05, 2.6472e-05, 2.6532e-05, 2.6591e-05, 2.6651e-05, 2.6710e-05, 2.6770e-05, 2.6829e-05, 2.6889e-05, 2.6948e-05, 2.7008e-05, 2.7067e-05, 2.7127e-05, 2.7186e-05, 2.7246e-05, 2.7305e-05, 2.7365e-05, 2.7424e-05, 2.7484e-05, 2.7543e-05, 2.7603e-05, 2.7662e-05, 2.7722e-05, 2.7781e-05, 2.7840e-05, 2.7900e-05, 2.7959e-05, 2.8019e-05, 2.8078e-05, 2.8138e-05, 2.8197e-05, 2.8257e-05, 2.8316e-05, 2.8376e-05, 2.8435e-05, 2.8495e-05, 2.8554e-05, 2.8614e-05, 2.8673e-05, 2.8733e-05, 2.8792e-05, 2.8852e-05, 2.8911e-05, 2.8971e-05, 2.9030e-05, 2.9090e-05, 2.9149e-05, 2.9209e-05, 2.9268e-05, 2.9328e-05, 2.9387e-05, 2.9447e-05, 2.9506e-05, 2.9566e-05, 2.9625e-05, 2.9685e-05, 2.9744e-05, 2.9804e-05, 2.9863e-05, 2.9923e-05, 2.9982e-05, 3.0042e-05, 3.0101e-05, 3.0161e-05, 3.0220e-05, 3.0280e-05, 3.0339e-05, 3.0398e-05, // NOLINT - 3.0458e-05, 3.0577e-05, 3.0697e-05, 3.0816e-05, 3.0936e-05, 3.1055e-05, 3.1175e-05, 3.1294e-05, 3.1414e-05, 3.1533e-05, 3.1652e-05, 3.1772e-05, 3.1891e-05, 3.2011e-05, 3.2130e-05, 3.2250e-05, 3.2369e-05, 3.2489e-05, 3.2608e-05, 3.2727e-05, 3.2847e-05, 3.2966e-05, 3.3086e-05, 3.3205e-05, 3.3325e-05, 3.3444e-05, 3.3563e-05, 3.3683e-05, 3.3802e-05, 3.3922e-05, 3.4041e-05, 3.4161e-05, 3.4280e-05, 3.4400e-05, 3.4519e-05, 3.4638e-05, 3.4758e-05, 3.4877e-05, 3.4997e-05, 3.5116e-05, 3.5236e-05, 3.5355e-05, 3.5475e-05, 3.5594e-05, 3.5713e-05, 3.5833e-05, 3.5952e-05, 3.6072e-05, 3.6191e-05, 3.6311e-05, 3.6430e-05, 3.6550e-05, 3.6669e-05, 3.6788e-05, 3.6908e-05, 3.7027e-05, 3.7147e-05, 3.7266e-05, 3.7386e-05, 3.7505e-05, 3.7625e-05, 3.7744e-05, 3.7863e-05, 3.7983e-05, 3.8102e-05, 3.8222e-05, 3.8341e-05, 3.8461e-05, 3.8580e-05, 3.8700e-05, 3.8819e-05, 3.8938e-05, 3.9058e-05, 3.9177e-05, 3.9297e-05, 3.9416e-05, 3.9536e-05, 3.9655e-05, 3.9775e-05, 3.9894e-05, 4.0013e-05, 4.0133e-05, 4.0252e-05, 4.0372e-05, 4.0491e-05, 4.0611e-05, 4.0730e-05, 4.0850e-05, 4.0969e-05, 4.1088e-05, 4.1208e-05, 4.1327e-05, 4.1447e-05, 4.1566e-05, 4.1686e-05, 4.1805e-05, 4.1925e-05, 4.2044e-05, 4.2163e-05, 4.2283e-05, 4.2402e-05, 4.2522e-05, 4.2641e-05, 4.2761e-05, 4.2880e-05, 4.2999e-05, 4.3119e-05, 4.3238e-05, 4.3358e-05, 4.3477e-05, 4.3597e-05, 4.3716e-05, 4.3836e-05, 4.3955e-05, 4.4074e-05, 4.4194e-05, 4.4313e-05, 4.4433e-05, 4.4552e-05, 4.4672e-05, 4.4791e-05, 4.4911e-05, 4.5030e-05, 4.5149e-05, 4.5269e-05, 4.5388e-05, 4.5508e-05, 4.5627e-05, 4.5747e-05, 4.5866e-05, 4.5986e-05, 4.6105e-05, 4.6224e-05, 4.6344e-05, 4.6463e-05, 4.6583e-05, 4.6702e-05, 4.6822e-05, 4.6941e-05, 4.7061e-05, 4.7180e-05, 4.7299e-05, 4.7419e-05, 4.7538e-05, 4.7658e-05, 4.7777e-05, 4.7897e-05, 4.8016e-05, 4.8136e-05, 4.8255e-05, 4.8374e-05, 4.8494e-05, 4.8613e-05, 4.8733e-05, 4.8852e-05, 4.8972e-05, 4.9091e-05, 4.9211e-05, 4.9330e-05, 4.9449e-05, 4.9569e-05, 4.9688e-05, 4.9808e-05, 4.9927e-05, 5.0047e-05, 5.0166e-05, 5.0286e-05, 5.0405e-05, 5.0524e-05, 5.0644e-05, 5.0763e-05, 5.0883e-05, 5.1002e-05, 5.1122e-05, 5.1241e-05, 5.1361e-05, 5.1480e-05, 5.1599e-05, 5.1719e-05, 5.1838e-05, 5.1958e-05, 5.2077e-05, 5.2197e-05, 5.2316e-05, 5.2435e-05, 5.2555e-05, 5.2674e-05, 5.2794e-05, 5.2913e-05, 5.3033e-05, 5.3152e-05, 5.3272e-05, 5.3391e-05, 5.3510e-05, 5.3630e-05, 5.3749e-05, 5.3869e-05, 5.3988e-05, 5.4108e-05, 5.4227e-05, 5.4347e-05, 5.4466e-05, 5.4585e-05, 5.4705e-05, 5.4824e-05, 5.4944e-05, 5.5063e-05, 5.5183e-05, 5.5302e-05, 5.5422e-05, 5.5541e-05, 5.5660e-05, 5.5780e-05, 5.5899e-05, 5.6019e-05, 5.6138e-05, 5.6258e-05, 5.6377e-05, 5.6497e-05, 5.6616e-05, 5.6735e-05, 5.6855e-05, 5.6974e-05, 5.7094e-05, 5.7213e-05, 5.7333e-05, 5.7452e-05, 5.7572e-05, 5.7691e-05, 5.7810e-05, 5.7930e-05, 5.8049e-05, 5.8169e-05, 5.8288e-05, 5.8408e-05, 5.8527e-05, 5.8647e-05, 5.8766e-05, 5.8885e-05, 5.9005e-05, 5.9124e-05, 5.9244e-05, 5.9363e-05, 5.9483e-05, 5.9602e-05, 5.9722e-05, 5.9841e-05, 5.9960e-05, 6.0080e-05, 6.0199e-05, 6.0319e-05, 6.0438e-05, 6.0558e-05, 6.0677e-05, 6.0797e-05, 6.0916e-05, // NOLINT - 6.1154e-05, 6.1392e-05, 6.1631e-05, 6.1869e-05, 6.2107e-05, 6.2345e-05, 6.2583e-05, 6.2821e-05, 6.3060e-05, 6.3298e-05, 6.3536e-05, 6.3774e-05, 6.4012e-05, 6.4251e-05, 6.4489e-05, 6.4727e-05, 6.4965e-05, 6.5203e-05, 6.5441e-05, 6.5680e-05, 6.5918e-05, 6.6156e-05, 6.6394e-05, 6.6632e-05, 6.6871e-05, 6.7109e-05, 6.7347e-05, 6.7585e-05, 6.7823e-05, 6.8062e-05, 6.8300e-05, 6.8538e-05, 6.8776e-05, 6.9014e-05, 6.9252e-05, 6.9491e-05, 6.9729e-05, 6.9967e-05, 7.0205e-05, 7.0443e-05, 7.0682e-05, 7.0920e-05, 7.1158e-05, 7.1396e-05, 7.1634e-05, 7.1872e-05, 7.2111e-05, 7.2349e-05, 7.2587e-05, 7.2825e-05, 7.3063e-05, 7.3302e-05, 7.3540e-05, 7.3778e-05, 7.4016e-05, 7.4254e-05, 7.4493e-05, 7.4731e-05, 7.4969e-05, 7.5207e-05, 7.5445e-05, 7.5683e-05, 7.5922e-05, 7.6160e-05, 7.6398e-05, 7.6636e-05, 7.6874e-05, 7.7113e-05, 7.7351e-05, 7.7589e-05, 7.7827e-05, 7.8065e-05, 7.8304e-05, 7.8542e-05, 7.8780e-05, 7.9018e-05, 7.9256e-05, 7.9494e-05, 7.9733e-05, 7.9971e-05, 8.0209e-05, 8.0447e-05, 8.0685e-05, 8.0924e-05, 8.1162e-05, 8.1400e-05, 8.1638e-05, 8.1876e-05, 8.2114e-05, 8.2353e-05, 8.2591e-05, 8.2829e-05, 8.3067e-05, 8.3305e-05, 8.3544e-05, 8.3782e-05, 8.4020e-05, 8.4258e-05, 8.4496e-05, 8.4735e-05, 8.4973e-05, 8.5211e-05, 8.5449e-05, 8.5687e-05, 8.5925e-05, 8.6164e-05, 8.6402e-05, 8.6640e-05, 8.6878e-05, 8.7116e-05, 8.7355e-05, 8.7593e-05, 8.7831e-05, 8.8069e-05, 8.8307e-05, 8.8545e-05, 8.8784e-05, 8.9022e-05, 8.9260e-05, 8.9498e-05, 8.9736e-05, 8.9975e-05, 9.0213e-05, 9.0451e-05, 9.0689e-05, 9.0927e-05, 9.1166e-05, 9.1404e-05, 9.1642e-05, 9.1880e-05, 9.2118e-05, 9.2356e-05, 9.2595e-05, 9.2833e-05, 9.3071e-05, 9.3309e-05, 9.3547e-05, 9.3786e-05, 9.4024e-05, 9.4262e-05, 9.4500e-05, 9.4738e-05, 9.4977e-05, 9.5215e-05, 9.5453e-05, 9.5691e-05, 9.5929e-05, 9.6167e-05, 9.6406e-05, 9.6644e-05, 9.6882e-05, 9.7120e-05, 9.7358e-05, 9.7597e-05, 9.7835e-05, 9.8073e-05, 9.8311e-05, 9.8549e-05, 9.8787e-05, 9.9026e-05, 9.9264e-05, 9.9502e-05, 9.9740e-05, 9.9978e-05, 1.0022e-04, 1.0045e-04, 1.0069e-04, 1.0093e-04, 1.0117e-04, 1.0141e-04, 1.0165e-04, 1.0188e-04, 1.0212e-04, 1.0236e-04, 1.0260e-04, 1.0284e-04, 1.0307e-04, 1.0331e-04, 1.0355e-04, 1.0379e-04, 1.0403e-04, 1.0427e-04, 1.0450e-04, 1.0474e-04, 1.0498e-04, 1.0522e-04, 1.0546e-04, 1.0569e-04, 1.0593e-04, 1.0617e-04, 1.0641e-04, 1.0665e-04, 1.0689e-04, 1.0712e-04, 1.0736e-04, 1.0760e-04, 1.0784e-04, 1.0808e-04, 1.0831e-04, 1.0855e-04, 1.0879e-04, 1.0903e-04, 1.0927e-04, 1.0951e-04, 1.0974e-04, 1.0998e-04, 1.1022e-04, 1.1046e-04, 1.1070e-04, 1.1093e-04, 1.1117e-04, 1.1141e-04, 1.1165e-04, 1.1189e-04, 1.1213e-04, 1.1236e-04, 1.1260e-04, 1.1284e-04, 1.1308e-04, 1.1332e-04, 1.1355e-04, 1.1379e-04, 1.1403e-04, 1.1427e-04, 1.1451e-04, 1.1475e-04, 1.1498e-04, 1.1522e-04, 1.1546e-04, 1.1570e-04, 1.1594e-04, 1.1618e-04, 1.1641e-04, 1.1665e-04, 1.1689e-04, 1.1713e-04, 1.1737e-04, 1.1760e-04, 1.1784e-04, 1.1808e-04, 1.1832e-04, 1.1856e-04, 1.1880e-04, 1.1903e-04, 1.1927e-04, 1.1951e-04, 1.1975e-04, 1.1999e-04, 1.2022e-04, 1.2046e-04, 1.2070e-04, 1.2094e-04, 1.2118e-04, 1.2142e-04, 1.2165e-04, 1.2189e-04, // NOLINT - 1.2213e-04, 1.2237e-04, 1.2261e-04, 1.2284e-04, 1.2308e-04, 1.2332e-04, 1.2356e-04, 1.2380e-04, 1.2404e-04, 1.2427e-04, 1.2451e-04, 1.2475e-04, 1.2499e-04, 1.2523e-04, 1.2546e-04, 1.2570e-04, 1.2594e-04, 1.2618e-04, 1.2642e-04, 1.2666e-04, 1.2689e-04, 1.2713e-04, 1.2737e-04, 1.2761e-04, 1.2785e-04, 1.2808e-04, 1.2832e-04, 1.2856e-04, 1.2880e-04, 1.2904e-04, 1.2928e-04, 1.2951e-04, 1.2975e-04, 1.2999e-04, 1.3023e-04, 1.3047e-04, 1.3070e-04, 1.3094e-04, 1.3118e-04, 1.3142e-04, 1.3166e-04, 1.3190e-04, 1.3213e-04, 1.3237e-04, 1.3261e-04, 1.3285e-04, 1.3309e-04, 1.3332e-04, 1.3356e-04, 1.3380e-04, 1.3404e-04, 1.3428e-04, 1.3452e-04, 1.3475e-04, 1.3499e-04, 1.3523e-04, 1.3547e-04, 1.3571e-04, 1.3594e-04, 1.3618e-04, 1.3642e-04, 1.3666e-04, 1.3690e-04, 1.3714e-04, 1.3737e-04, 1.3761e-04, 1.3785e-04, 1.3809e-04, 1.3833e-04, 1.3856e-04, 1.3880e-04, 1.3904e-04, 1.3928e-04, 1.3952e-04, 1.3976e-04, 1.3999e-04, 1.4023e-04, 1.4047e-04, 1.4071e-04, 1.4095e-04, 1.4118e-04, 1.4142e-04, 1.4166e-04, 1.4190e-04, 1.4214e-04, 1.4238e-04, 1.4261e-04, 1.4285e-04, 1.4309e-04, 1.4333e-04, 1.4357e-04, 1.4380e-04, 1.4404e-04, 1.4428e-04, 1.4452e-04, 1.4476e-04, 1.4500e-04, 1.4523e-04, 1.4547e-04, 1.4571e-04, 1.4595e-04, 1.4619e-04, 1.4642e-04, 1.4666e-04, 1.4690e-04, 1.4714e-04, 1.4738e-04, 1.4762e-04, 1.4785e-04, 1.4809e-04, 1.4833e-04, 1.4857e-04, 1.4881e-04, 1.4904e-04, 1.4928e-04, 1.4952e-04, 1.4976e-04, 1.5000e-04, 1.5024e-04, 1.5047e-04, 1.5071e-04, 1.5095e-04, 1.5119e-04, 1.5143e-04, 1.5166e-04, 1.5190e-04, 1.5214e-04, 1.5238e-04, 1.5262e-04, 1.5286e-04, 1.5309e-04, 1.5333e-04, 1.5357e-04, 1.5381e-04, 1.5405e-04, 1.5428e-04, 1.5452e-04, 1.5476e-04, 1.5500e-04, 1.5524e-04, 1.5548e-04, 1.5571e-04, 1.5595e-04, 1.5619e-04, 1.5643e-04, 1.5667e-04, 1.5690e-04, 1.5714e-04, 1.5738e-04, 1.5762e-04, 1.5786e-04, 1.5810e-04, 1.5833e-04, 1.5857e-04, 1.5881e-04, 1.5905e-04, 1.5929e-04, 1.5952e-04, 1.5976e-04, 1.6000e-04, 1.6024e-04, 1.6048e-04, 1.6072e-04, 1.6095e-04, 1.6119e-04, 1.6143e-04, 1.6167e-04, 1.6191e-04, 1.6214e-04, 1.6238e-04, 1.6262e-04, 1.6286e-04, 1.6310e-04, 1.6334e-04, 1.6357e-04, 1.6381e-04, 1.6405e-04, 1.6429e-04, 1.6453e-04, 1.6476e-04, 1.6500e-04, 1.6524e-04, 1.6548e-04, 1.6572e-04, 1.6596e-04, 1.6619e-04, 1.6643e-04, 1.6667e-04, 1.6691e-04, 1.6715e-04, 1.6738e-04, 1.6762e-04, 1.6786e-04, 1.6810e-04, 1.6834e-04, 1.6858e-04, 1.6881e-04, 1.6905e-04, 1.6929e-04, 1.6953e-04, 1.6977e-04, 1.7001e-04, 1.7024e-04, 1.7048e-04, 1.7072e-04, 1.7096e-04, 1.7120e-04, 1.7143e-04, 1.7167e-04, 1.7191e-04, 1.7215e-04, 1.7239e-04, 1.7263e-04, 1.7286e-04, 1.7310e-04, 1.7334e-04, 1.7358e-04, 1.7382e-04, 1.7405e-04, 1.7429e-04, 1.7453e-04, 1.7477e-04, 1.7501e-04, 1.7525e-04, 1.7548e-04, 1.7572e-04, 1.7596e-04, 1.7620e-04, 1.7644e-04, 1.7667e-04, 1.7691e-04, 1.7715e-04, 1.7739e-04, 1.7763e-04, 1.7787e-04, 1.7810e-04, 1.7834e-04, 1.7858e-04, 1.7882e-04, 1.7906e-04, 1.7929e-04, 1.7953e-04, 1.7977e-04, 1.8001e-04, 1.8025e-04, 1.8049e-04, 1.8072e-04, 1.8096e-04, 1.8120e-04, 1.8144e-04, 1.8168e-04, 1.8191e-04, 1.8215e-04, 1.8239e-04, 1.8263e-04, 1.8287e-04, // NOLINT - 1.8311e-04, 1.8334e-04, 1.8358e-04, 1.8382e-04, 1.8406e-04, 1.8430e-04, 1.8453e-04, 1.8477e-04, 1.8501e-04, 1.8525e-04, 1.8549e-04, 1.8573e-04, 1.8596e-04, 1.8620e-04, 1.8644e-04, 1.8668e-04, 1.8692e-04, 1.8715e-04, 1.8739e-04, 1.8763e-04, 1.8787e-04, 1.8811e-04, 1.8835e-04, 1.8858e-04, 1.8882e-04, 1.8906e-04, 1.8930e-04, 1.8954e-04, 1.8977e-04, 1.9001e-04, 1.9025e-04, 1.9049e-04, 1.9073e-04, 1.9097e-04, 1.9120e-04, 1.9144e-04, 1.9168e-04, 1.9192e-04, 1.9216e-04, 1.9239e-04, 1.9263e-04, 1.9287e-04, 1.9311e-04, 1.9335e-04, 1.9359e-04, 1.9382e-04, 1.9406e-04, 1.9430e-04, 1.9454e-04, 1.9478e-04, 1.9501e-04, 1.9525e-04, 1.9549e-04, 1.9573e-04, 1.9597e-04, 1.9621e-04, 1.9644e-04, 1.9668e-04, 1.9692e-04, 1.9716e-04, 1.9740e-04, 1.9763e-04, 1.9787e-04, 1.9811e-04, 1.9835e-04, 1.9859e-04, 1.9883e-04, 1.9906e-04, 1.9930e-04, 1.9954e-04, 1.9978e-04, 2.0002e-04, 2.0025e-04, 2.0049e-04, 2.0073e-04, 2.0097e-04, 2.0121e-04, 2.0145e-04, 2.0168e-04, 2.0192e-04, 2.0216e-04, 2.0240e-04, 2.0264e-04, 2.0287e-04, 2.0311e-04, 2.0335e-04, 2.0359e-04, 2.0383e-04, 2.0407e-04, 2.0430e-04, 2.0454e-04, 2.0478e-04, 2.0502e-04, 2.0526e-04, 2.0549e-04, 2.0573e-04, 2.0597e-04, 2.0621e-04, 2.0645e-04, 2.0669e-04, 2.0692e-04, 2.0716e-04, 2.0740e-04, 2.0764e-04, 2.0788e-04, 2.0811e-04, 2.0835e-04, 2.0859e-04, 2.0883e-04, 2.0907e-04, 2.0931e-04, 2.0954e-04, 2.0978e-04, 2.1002e-04, 2.1026e-04, 2.1050e-04, 2.1073e-04, 2.1097e-04, 2.1121e-04, 2.1145e-04, 2.1169e-04, 2.1193e-04, 2.1216e-04, 2.1240e-04, 2.1264e-04, 2.1288e-04, 2.1312e-04, 2.1335e-04, 2.1359e-04, 2.1383e-04, 2.1407e-04, 2.1431e-04, 2.1455e-04, 2.1478e-04, 2.1502e-04, 2.1526e-04, 2.1550e-04, 2.1574e-04, 2.1597e-04, 2.1621e-04, 2.1645e-04, 2.1669e-04, 2.1693e-04, 2.1717e-04, 2.1740e-04, 2.1764e-04, 2.1788e-04, 2.1812e-04, 2.1836e-04, 2.1859e-04, 2.1883e-04, 2.1907e-04, 2.1931e-04, 2.1955e-04, 2.1979e-04, 2.2002e-04, 2.2026e-04, 2.2050e-04, 2.2074e-04, 2.2098e-04, 2.2121e-04, 2.2145e-04, 2.2169e-04, 2.2193e-04, 2.2217e-04, 2.2241e-04, 2.2264e-04, 2.2288e-04, 2.2312e-04, 2.2336e-04, 2.2360e-04, 2.2383e-04, 2.2407e-04, 2.2431e-04, 2.2455e-04, 2.2479e-04, 2.2503e-04, 2.2526e-04, 2.2550e-04, 2.2574e-04, 2.2598e-04, 2.2622e-04, 2.2646e-04, 2.2669e-04, 2.2693e-04, 2.2717e-04, 2.2741e-04, 2.2765e-04, 2.2788e-04, 2.2812e-04, 2.2836e-04, 2.2860e-04, 2.2884e-04, 2.2908e-04, 2.2931e-04, 2.2955e-04, 2.2979e-04, 2.3003e-04, 2.3027e-04, 2.3050e-04, 2.3074e-04, 2.3098e-04, 2.3122e-04, 2.3146e-04, 2.3170e-04, 2.3193e-04, 2.3217e-04, 2.3241e-04, 2.3265e-04, 2.3289e-04, 2.3312e-04, 2.3336e-04, 2.3360e-04, 2.3384e-04, 2.3408e-04, 2.3432e-04, 2.3455e-04, 2.3479e-04, 2.3503e-04, 2.3527e-04, 2.3551e-04, 2.3574e-04, 2.3598e-04, 2.3622e-04, 2.3646e-04, 2.3670e-04, 2.3694e-04, 2.3717e-04, 2.3741e-04, 2.3765e-04, 2.3789e-04, 2.3813e-04, 2.3836e-04, 2.3860e-04, 2.3884e-04, 2.3908e-04, 2.3932e-04, 2.3956e-04, 2.3979e-04, 2.4003e-04, 2.4027e-04, 2.4051e-04, 2.4075e-04, 2.4098e-04, 2.4122e-04, 2.4146e-04, 2.4170e-04, 2.4194e-04, 2.4218e-04, 2.4241e-04, 2.4265e-04, 2.4289e-04, 2.4313e-04, 2.4337e-04, 2.4360e-04, 2.4384e-04, // NOLINT - 2.4480e-04, 2.4575e-04, 2.4670e-04, 2.4766e-04, 2.4861e-04, 2.4956e-04, 2.5052e-04, 2.5147e-04, 2.5242e-04, 2.5337e-04, 2.5433e-04, 2.5528e-04, 2.5623e-04, 2.5719e-04, 2.5814e-04, 2.5909e-04, 2.6005e-04, 2.6100e-04, 2.6195e-04, 2.6291e-04, 2.6386e-04, 2.6481e-04, 2.6577e-04, 2.6672e-04, 2.6767e-04, 2.6863e-04, 2.6958e-04, 2.7053e-04, 2.7149e-04, 2.7244e-04, 2.7339e-04, 2.7435e-04, 2.7530e-04, 2.7625e-04, 2.7720e-04, 2.7816e-04, 2.7911e-04, 2.8006e-04, 2.8102e-04, 2.8197e-04, 2.8292e-04, 2.8388e-04, 2.8483e-04, 2.8578e-04, 2.8674e-04, 2.8769e-04, 2.8864e-04, 2.8960e-04, 2.9055e-04, 2.9150e-04, 2.9246e-04, 2.9341e-04, 2.9436e-04, 2.9532e-04, 2.9627e-04, 2.9722e-04, 2.9818e-04, 2.9913e-04, 3.0008e-04, 3.0104e-04, 3.0199e-04, 3.0294e-04, 3.0389e-04, 3.0485e-04, 3.0580e-04, 3.0675e-04, 3.0771e-04, 3.0866e-04, 3.0961e-04, 3.1057e-04, 3.1152e-04, 3.1247e-04, 3.1343e-04, 3.1438e-04, 3.1533e-04, 3.1629e-04, 3.1724e-04, 3.1819e-04, 3.1915e-04, 3.2010e-04, 3.2105e-04, 3.2201e-04, 3.2296e-04, 3.2391e-04, 3.2487e-04, 3.2582e-04, 3.2677e-04, 3.2772e-04, 3.2868e-04, 3.2963e-04, 3.3058e-04, 3.3154e-04, 3.3249e-04, 3.3344e-04, 3.3440e-04, 3.3535e-04, 3.3630e-04, 3.3726e-04, 3.3821e-04, 3.3916e-04, 3.4012e-04, 3.4107e-04, 3.4202e-04, 3.4298e-04, 3.4393e-04, 3.4488e-04, 3.4584e-04, 3.4679e-04, 3.4774e-04, 3.4870e-04, 3.4965e-04, 3.5060e-04, 3.5156e-04, 3.5251e-04, 3.5346e-04, 3.5441e-04, 3.5537e-04, 3.5632e-04, 3.5727e-04, 3.5823e-04, 3.5918e-04, 3.6013e-04, 3.6109e-04, 3.6204e-04, 3.6299e-04, 3.6395e-04, 3.6490e-04, 3.6585e-04, 3.6681e-04, 3.6776e-04, 3.6871e-04, 3.6967e-04, 3.7062e-04, 3.7157e-04, 3.7253e-04, 3.7348e-04, 3.7443e-04, 3.7539e-04, 3.7634e-04, 3.7729e-04, 3.7825e-04, 3.7920e-04, 3.8015e-04, 3.8110e-04, 3.8206e-04, 3.8301e-04, 3.8396e-04, 3.8492e-04, 3.8587e-04, 3.8682e-04, 3.8778e-04, 3.8873e-04, 3.8968e-04, 3.9064e-04, 3.9159e-04, 3.9254e-04, 3.9350e-04, 3.9445e-04, 3.9540e-04, 3.9636e-04, 3.9731e-04, 3.9826e-04, 3.9922e-04, 4.0017e-04, 4.0112e-04, 4.0208e-04, 4.0303e-04, 4.0398e-04, 4.0493e-04, 4.0589e-04, 4.0684e-04, 4.0779e-04, 4.0875e-04, 4.0970e-04, 4.1065e-04, 4.1161e-04, 4.1256e-04, 4.1351e-04, 4.1447e-04, 4.1542e-04, 4.1637e-04, 4.1733e-04, 4.1828e-04, 4.1923e-04, 4.2019e-04, 4.2114e-04, 4.2209e-04, 4.2305e-04, 4.2400e-04, 4.2495e-04, 4.2591e-04, 4.2686e-04, 4.2781e-04, 4.2877e-04, 4.2972e-04, 4.3067e-04, 4.3162e-04, 4.3258e-04, 4.3353e-04, 4.3448e-04, 4.3544e-04, 4.3639e-04, 4.3734e-04, 4.3830e-04, 4.3925e-04, 4.4020e-04, 4.4116e-04, 4.4211e-04, 4.4306e-04, 4.4402e-04, 4.4497e-04, 4.4592e-04, 4.4688e-04, 4.4783e-04, 4.4878e-04, 4.4974e-04, 4.5069e-04, 4.5164e-04, 4.5260e-04, 4.5355e-04, 4.5450e-04, 4.5545e-04, 4.5641e-04, 4.5736e-04, 4.5831e-04, 4.5927e-04, 4.6022e-04, 4.6117e-04, 4.6213e-04, 4.6308e-04, 4.6403e-04, 4.6499e-04, 4.6594e-04, 4.6689e-04, 4.6785e-04, 4.6880e-04, 4.6975e-04, 4.7071e-04, 4.7166e-04, 4.7261e-04, 4.7357e-04, 4.7452e-04, 4.7547e-04, 4.7643e-04, 4.7738e-04, 4.7833e-04, 4.7929e-04, 4.8024e-04, 4.8119e-04, 4.8214e-04, 4.8310e-04, 4.8405e-04, 4.8500e-04, 4.8596e-04, 4.8691e-04, 4.8786e-04, // NOLINT - 4.8977e-04, 4.9168e-04, 4.9358e-04, 4.9549e-04, 4.9740e-04, 4.9931e-04, 5.0121e-04, 5.0312e-04, 5.0503e-04, 5.0693e-04, 5.0884e-04, 5.1075e-04, 5.1265e-04, 5.1456e-04, 5.1647e-04, 5.1837e-04, 5.2028e-04, 5.2219e-04, 5.2409e-04, 5.2600e-04, 5.2791e-04, 5.2982e-04, 5.3172e-04, 5.3363e-04, 5.3554e-04, 5.3744e-04, 5.3935e-04, 5.4126e-04, 5.4316e-04, 5.4507e-04, 5.4698e-04, 5.4888e-04, 5.5079e-04, 5.5270e-04, 5.5460e-04, 5.5651e-04, 5.5842e-04, 5.6033e-04, 5.6223e-04, 5.6414e-04, 5.6605e-04, 5.6795e-04, 5.6986e-04, 5.7177e-04, 5.7367e-04, 5.7558e-04, 5.7749e-04, 5.7939e-04, 5.8130e-04, 5.8321e-04, 5.8512e-04, 5.8702e-04, 5.8893e-04, 5.9084e-04, 5.9274e-04, 5.9465e-04, 5.9656e-04, 5.9846e-04, 6.0037e-04, 6.0228e-04, 6.0418e-04, 6.0609e-04, 6.0800e-04, 6.0990e-04, 6.1181e-04, 6.1372e-04, 6.1563e-04, 6.1753e-04, 6.1944e-04, 6.2135e-04, 6.2325e-04, 6.2516e-04, 6.2707e-04, 6.2897e-04, 6.3088e-04, 6.3279e-04, 6.3469e-04, 6.3660e-04, 6.3851e-04, 6.4041e-04, 6.4232e-04, 6.4423e-04, 6.4614e-04, 6.4804e-04, 6.4995e-04, 6.5186e-04, 6.5376e-04, 6.5567e-04, 6.5758e-04, 6.5948e-04, 6.6139e-04, 6.6330e-04, 6.6520e-04, 6.6711e-04, 6.6902e-04, 6.7092e-04, 6.7283e-04, 6.7474e-04, 6.7665e-04, 6.7855e-04, 6.8046e-04, 6.8237e-04, 6.8427e-04, 6.8618e-04, 6.8809e-04, 6.8999e-04, 6.9190e-04, 6.9381e-04, 6.9571e-04, 6.9762e-04, 6.9953e-04, 7.0143e-04, 7.0334e-04, 7.0525e-04, 7.0716e-04, 7.0906e-04, 7.1097e-04, 7.1288e-04, 7.1478e-04, 7.1669e-04, 7.1860e-04, 7.2050e-04, 7.2241e-04, 7.2432e-04, 7.2622e-04, 7.2813e-04, 7.3004e-04, 7.3195e-04, 7.3385e-04, 7.3576e-04, 7.3767e-04, 7.3957e-04, 7.4148e-04, 7.4339e-04, 7.4529e-04, 7.4720e-04, 7.4911e-04, 7.5101e-04, 7.5292e-04, 7.5483e-04, 7.5673e-04, 7.5864e-04, 7.6055e-04, 7.6246e-04, 7.6436e-04, 7.6627e-04, 7.6818e-04, 7.7008e-04, 7.7199e-04, 7.7390e-04, 7.7580e-04, 7.7771e-04, 7.7962e-04, 7.8152e-04, 7.8343e-04, 7.8534e-04, 7.8724e-04, 7.8915e-04, 7.9106e-04, 7.9297e-04, 7.9487e-04, 7.9678e-04, 7.9869e-04, 8.0059e-04, 8.0250e-04, 8.0441e-04, 8.0631e-04, 8.0822e-04, 8.1013e-04, 8.1203e-04, 8.1394e-04, 8.1585e-04, 8.1775e-04, 8.1966e-04, 8.2157e-04, 8.2348e-04, 8.2538e-04, 8.2729e-04, 8.2920e-04, 8.3110e-04, 8.3301e-04, 8.3492e-04, 8.3682e-04, 8.3873e-04, 8.4064e-04, 8.4254e-04, 8.4445e-04, 8.4636e-04, 8.4826e-04, 8.5017e-04, 8.5208e-04, 8.5399e-04, 8.5589e-04, 8.5780e-04, 8.5971e-04, 8.6161e-04, 8.6352e-04, 8.6543e-04, 8.6733e-04, 8.6924e-04, 8.7115e-04, 8.7305e-04, 8.7496e-04, 8.7687e-04, 8.7878e-04, 8.8068e-04, 8.8259e-04, 8.8450e-04, 8.8640e-04, 8.8831e-04, 8.9022e-04, 8.9212e-04, 8.9403e-04, 8.9594e-04, 8.9784e-04, 8.9975e-04, 9.0166e-04, 9.0356e-04, 9.0547e-04, 9.0738e-04, 9.0929e-04, 9.1119e-04, 9.1310e-04, 9.1501e-04, 9.1691e-04, 9.1882e-04, 9.2073e-04, 9.2263e-04, 9.2454e-04, 9.2645e-04, 9.2835e-04, 9.3026e-04, 9.3217e-04, 9.3407e-04, 9.3598e-04, 9.3789e-04, 9.3980e-04, 9.4170e-04, 9.4361e-04, 9.4552e-04, 9.4742e-04, 9.4933e-04, 9.5124e-04, 9.5314e-04, 9.5505e-04, 9.5696e-04, 9.5886e-04, 9.6077e-04, 9.6268e-04, 9.6458e-04, 9.6649e-04, 9.6840e-04, 9.7031e-04, 9.7221e-04, 9.7412e-04, 9.7603e-04, // NOLINT - 9.7984e-04, 9.8365e-04, 9.8747e-04, 9.9128e-04, 9.9510e-04, 9.9891e-04, 1.0027e-03, 1.0065e-03, 1.0104e-03, 1.0142e-03, 1.0180e-03, 1.0218e-03, 1.0256e-03, 1.0294e-03, 1.0332e-03, 1.0371e-03, 1.0409e-03, 1.0447e-03, 1.0485e-03, 1.0523e-03, 1.0561e-03, 1.0599e-03, 1.0638e-03, 1.0676e-03, 1.0714e-03, 1.0752e-03, 1.0790e-03, 1.0828e-03, 1.0866e-03, 1.0905e-03, 1.0943e-03, 1.0981e-03, 1.1019e-03, 1.1057e-03, 1.1095e-03, 1.1133e-03, 1.1172e-03, 1.1210e-03, 1.1248e-03, 1.1286e-03, 1.1324e-03, 1.1362e-03, 1.1400e-03, 1.1439e-03, 1.1477e-03, 1.1515e-03, 1.1553e-03, 1.1591e-03, 1.1629e-03, 1.1667e-03, 1.1706e-03, 1.1744e-03, 1.1782e-03, 1.1820e-03, 1.1858e-03, 1.1896e-03, 1.1934e-03, 1.1973e-03, 1.2011e-03, 1.2049e-03, 1.2087e-03, 1.2125e-03, 1.2163e-03, 1.2201e-03, 1.2240e-03, 1.2278e-03, 1.2316e-03, 1.2354e-03, 1.2392e-03, 1.2430e-03, 1.2468e-03, 1.2507e-03, 1.2545e-03, 1.2583e-03, 1.2621e-03, 1.2659e-03, 1.2697e-03, 1.2735e-03, 1.2774e-03, 1.2812e-03, 1.2850e-03, 1.2888e-03, 1.2926e-03, 1.2964e-03, 1.3002e-03, 1.3040e-03, 1.3079e-03, 1.3117e-03, 1.3155e-03, 1.3193e-03, 1.3231e-03, 1.3269e-03, 1.3307e-03, 1.3346e-03, 1.3384e-03, 1.3422e-03, 1.3460e-03, 1.3498e-03, 1.3536e-03, 1.3574e-03, 1.3613e-03, 1.3651e-03, 1.3689e-03, 1.3727e-03, 1.3765e-03, 1.3803e-03, 1.3841e-03, 1.3880e-03, 1.3918e-03, 1.3956e-03, 1.3994e-03, 1.4032e-03, 1.4070e-03, 1.4108e-03, 1.4147e-03, 1.4185e-03, 1.4223e-03, 1.4261e-03, 1.4299e-03, 1.4337e-03, 1.4375e-03, 1.4414e-03, 1.4452e-03, 1.4490e-03, 1.4528e-03, 1.4566e-03, 1.4604e-03, 1.4642e-03, 1.4681e-03, 1.4719e-03, 1.4757e-03, 1.4795e-03, 1.4833e-03, 1.4871e-03, 1.4909e-03, 1.4948e-03, 1.4986e-03, 1.5024e-03, 1.5062e-03, 1.5100e-03, 1.5138e-03, 1.5176e-03, 1.5215e-03, 1.5253e-03, 1.5291e-03, 1.5329e-03, 1.5367e-03, 1.5405e-03, 1.5443e-03, 1.5482e-03, 1.5520e-03, 1.5558e-03, 1.5596e-03, 1.5634e-03, 1.5672e-03, 1.5710e-03, 1.5749e-03, 1.5787e-03, 1.5825e-03, 1.5863e-03, 1.5901e-03, 1.5939e-03, 1.5977e-03, 1.6016e-03, 1.6054e-03, 1.6092e-03, 1.6130e-03, 1.6168e-03, 1.6206e-03, 1.6244e-03, 1.6283e-03, 1.6321e-03, 1.6359e-03, 1.6397e-03, 1.6435e-03, 1.6473e-03, 1.6511e-03, 1.6550e-03, 1.6588e-03, 1.6626e-03, 1.6664e-03, 1.6702e-03, 1.6740e-03, 1.6778e-03, 1.6817e-03, 1.6855e-03, 1.6893e-03, 1.6931e-03, 1.6969e-03, 1.7007e-03, 1.7045e-03, 1.7084e-03, 1.7122e-03, 1.7160e-03, 1.7198e-03, 1.7236e-03, 1.7274e-03, 1.7312e-03, 1.7351e-03, 1.7389e-03, 1.7427e-03, 1.7465e-03, 1.7503e-03, 1.7541e-03, 1.7579e-03, 1.7618e-03, 1.7656e-03, 1.7694e-03, 1.7732e-03, 1.7770e-03, 1.7808e-03, 1.7846e-03, 1.7885e-03, 1.7923e-03, 1.7961e-03, 1.7999e-03, 1.8037e-03, 1.8075e-03, 1.8113e-03, 1.8152e-03, 1.8190e-03, 1.8228e-03, 1.8266e-03, 1.8304e-03, 1.8342e-03, 1.8380e-03, 1.8419e-03, 1.8457e-03, 1.8495e-03, 1.8533e-03, 1.8571e-03, 1.8609e-03, 1.8647e-03, 1.8686e-03, 1.8724e-03, 1.8762e-03, 1.8800e-03, 1.8838e-03, 1.8876e-03, 1.8914e-03, 1.8953e-03, 1.8991e-03, 1.9029e-03, 1.9067e-03, 1.9105e-03, 1.9143e-03, 1.9181e-03, 1.9220e-03, 1.9258e-03, 1.9296e-03, 1.9334e-03, 1.9372e-03, 1.9410e-03, 1.9448e-03, 1.9487e-03, 1.9525e-03, // NOLINT - 1.9601e-03, 1.9677e-03, 1.9754e-03, 1.9830e-03, 1.9906e-03, 1.9982e-03, 2.0059e-03, 2.0135e-03, 2.0211e-03, 2.0288e-03, 2.0364e-03, 2.0440e-03, 2.0516e-03, 2.0593e-03, 2.0669e-03, 2.0745e-03, 2.0822e-03, 2.0898e-03, 2.0974e-03, 2.1050e-03, 2.1127e-03, 2.1203e-03, 2.1279e-03, 2.1356e-03, 2.1432e-03, 2.1508e-03, 2.1585e-03, 2.1661e-03, 2.1737e-03, 2.1813e-03, 2.1890e-03, 2.1966e-03, 2.2042e-03, 2.2119e-03, 2.2195e-03, 2.2271e-03, 2.2347e-03, 2.2424e-03, 2.2500e-03, 2.2576e-03, 2.2653e-03, 2.2729e-03, 2.2805e-03, 2.2881e-03, 2.2958e-03, 2.3034e-03, 2.3110e-03, 2.3187e-03, 2.3263e-03, 2.3339e-03, 2.3415e-03, 2.3492e-03, 2.3568e-03, 2.3644e-03, 2.3721e-03, 2.3797e-03, 2.3873e-03, 2.3949e-03, 2.4026e-03, 2.4102e-03, 2.4178e-03, 2.4255e-03, 2.4331e-03, 2.4407e-03, 2.4483e-03, 2.4560e-03, 2.4636e-03, 2.4712e-03, 2.4789e-03, 2.4865e-03, 2.4941e-03, 2.5018e-03, 2.5094e-03, 2.5170e-03, 2.5246e-03, 2.5323e-03, 2.5399e-03, 2.5475e-03, 2.5552e-03, 2.5628e-03, 2.5704e-03, 2.5780e-03, 2.5857e-03, 2.5933e-03, 2.6009e-03, 2.6086e-03, 2.6162e-03, 2.6238e-03, 2.6314e-03, 2.6391e-03, 2.6467e-03, 2.6543e-03, 2.6620e-03, 2.6696e-03, 2.6772e-03, 2.6848e-03, 2.6925e-03, 2.7001e-03, 2.7077e-03, 2.7154e-03, 2.7230e-03, 2.7306e-03, 2.7382e-03, 2.7459e-03, 2.7535e-03, 2.7611e-03, 2.7688e-03, 2.7764e-03, 2.7840e-03, 2.7917e-03, 2.7993e-03, 2.8069e-03, 2.8145e-03, 2.8222e-03, 2.8298e-03, 2.8374e-03, 2.8451e-03, 2.8527e-03, 2.8603e-03, 2.8679e-03, 2.8756e-03, 2.8832e-03, 2.8908e-03, 2.8985e-03, 2.9061e-03, 2.9137e-03, 2.9213e-03, 2.9290e-03, 2.9366e-03, 2.9442e-03, 2.9519e-03, 2.9595e-03, 2.9671e-03, 2.9747e-03, 2.9824e-03, 2.9900e-03, 2.9976e-03, 3.0053e-03, 3.0129e-03, 3.0205e-03, 3.0281e-03, 3.0358e-03, 3.0434e-03, 3.0510e-03, 3.0587e-03, 3.0663e-03, 3.0739e-03, 3.0816e-03, 3.0892e-03, 3.0968e-03, 3.1044e-03, 3.1121e-03, 3.1197e-03, 3.1273e-03, 3.1350e-03, 3.1426e-03, 3.1502e-03, 3.1578e-03, 3.1655e-03, 3.1731e-03, 3.1807e-03, 3.1884e-03, 3.1960e-03, 3.2036e-03, 3.2112e-03, 3.2189e-03, 3.2265e-03, 3.2341e-03, 3.2418e-03, 3.2494e-03, 3.2570e-03, 3.2646e-03, 3.2723e-03, 3.2799e-03, 3.2875e-03, 3.2952e-03, 3.3028e-03, 3.3104e-03, 3.3180e-03, 3.3257e-03, 3.3333e-03, 3.3409e-03, 3.3486e-03, 3.3562e-03, 3.3638e-03, 3.3715e-03, 3.3791e-03, 3.3867e-03, 3.3943e-03, 3.4020e-03, 3.4096e-03, 3.4172e-03, 3.4249e-03, 3.4325e-03, 3.4401e-03, 3.4477e-03, 3.4554e-03, 3.4630e-03, 3.4706e-03, 3.4783e-03, 3.4859e-03, 3.4935e-03, 3.5011e-03, 3.5088e-03, 3.5164e-03, 3.5240e-03, 3.5317e-03, 3.5393e-03, 3.5469e-03, 3.5545e-03, 3.5622e-03, 3.5698e-03, 3.5774e-03, 3.5851e-03, 3.5927e-03, 3.6003e-03, 3.6079e-03, 3.6156e-03, 3.6232e-03, 3.6308e-03, 3.6385e-03, 3.6461e-03, 3.6537e-03, 3.6613e-03, 3.6690e-03, 3.6766e-03, 3.6842e-03, 3.6919e-03, 3.6995e-03, 3.7071e-03, 3.7148e-03, 3.7224e-03, 3.7300e-03, 3.7376e-03, 3.7453e-03, 3.7529e-03, 3.7605e-03, 3.7682e-03, 3.7758e-03, 3.7834e-03, 3.7910e-03, 3.7987e-03, 3.8063e-03, 3.8139e-03, 3.8216e-03, 3.8292e-03, 3.8368e-03, 3.8444e-03, 3.8521e-03, 3.8597e-03, 3.8673e-03, 3.8750e-03, 3.8826e-03, 3.8902e-03, 3.8978e-03, 3.9055e-03, // NOLINT - 3.9207e-03, 3.9360e-03, 3.9513e-03, 3.9665e-03, 3.9818e-03, 3.9970e-03, 4.0123e-03, 4.0275e-03, 4.0428e-03, 4.0581e-03, 4.0733e-03, 4.0886e-03, 4.1038e-03, 4.1191e-03, 4.1343e-03, 4.1496e-03, 4.1649e-03, 4.1801e-03, 4.1954e-03, 4.2106e-03, 4.2259e-03, 4.2412e-03, 4.2564e-03, 4.2717e-03, 4.2869e-03, 4.3022e-03, 4.3174e-03, 4.3327e-03, 4.3480e-03, 4.3632e-03, 4.3785e-03, 4.3937e-03, 4.4090e-03, 4.4243e-03, 4.4395e-03, 4.4548e-03, 4.4700e-03, 4.4853e-03, 4.5005e-03, 4.5158e-03, 4.5311e-03, 4.5463e-03, 4.5616e-03, 4.5768e-03, 4.5921e-03, 4.6074e-03, 4.6226e-03, 4.6379e-03, 4.6531e-03, 4.6684e-03, 4.6836e-03, 4.6989e-03, 4.7142e-03, 4.7294e-03, 4.7447e-03, 4.7599e-03, 4.7752e-03, 4.7905e-03, 4.8057e-03, 4.8210e-03, 4.8362e-03, 4.8515e-03, 4.8667e-03, 4.8820e-03, 4.8973e-03, 4.9125e-03, 4.9278e-03, 4.9430e-03, 4.9583e-03, 4.9736e-03, 4.9888e-03, 5.0041e-03, 5.0193e-03, 5.0346e-03, 5.0498e-03, 5.0651e-03, 5.0804e-03, 5.0956e-03, 5.1109e-03, 5.1261e-03, 5.1414e-03, 5.1567e-03, 5.1719e-03, 5.1872e-03, 5.2024e-03, 5.2177e-03, 5.2329e-03, 5.2482e-03, 5.2635e-03, 5.2787e-03, 5.2940e-03, 5.3092e-03, 5.3245e-03, 5.3398e-03, 5.3550e-03, 5.3703e-03, 5.3855e-03, 5.4008e-03, 5.4160e-03, 5.4313e-03, 5.4466e-03, 5.4618e-03, 5.4771e-03, 5.4923e-03, 5.5076e-03, 5.5229e-03, 5.5381e-03, 5.5534e-03, 5.5686e-03, 5.5839e-03, 5.5991e-03, 5.6144e-03, 5.6297e-03, 5.6449e-03, 5.6602e-03, 5.6754e-03, 5.6907e-03, 5.7060e-03, 5.7212e-03, 5.7365e-03, 5.7517e-03, 5.7670e-03, 5.7822e-03, 5.7975e-03, 5.8128e-03, 5.8280e-03, 5.8433e-03, 5.8585e-03, 5.8738e-03, 5.8891e-03, 5.9043e-03, 5.9196e-03, 5.9348e-03, 5.9501e-03, 5.9653e-03, 5.9806e-03, 5.9959e-03, 6.0111e-03, 6.0264e-03, 6.0416e-03, 6.0569e-03, 6.0722e-03, 6.0874e-03, 6.1027e-03, 6.1179e-03, 6.1332e-03, 6.1484e-03, 6.1637e-03, 6.1790e-03, 6.1942e-03, 6.2095e-03, 6.2247e-03, 6.2400e-03, 6.2553e-03, 6.2705e-03, 6.2858e-03, 6.3010e-03, 6.3163e-03, 6.3315e-03, 6.3468e-03, 6.3621e-03, 6.3773e-03, 6.3926e-03, 6.4078e-03, 6.4231e-03, 6.4384e-03, 6.4536e-03, 6.4689e-03, 6.4841e-03, 6.4994e-03, 6.5146e-03, 6.5299e-03, 6.5452e-03, 6.5604e-03, 6.5757e-03, 6.5909e-03, 6.6062e-03, 6.6215e-03, 6.6367e-03, 6.6520e-03, 6.6672e-03, 6.6825e-03, 6.6977e-03, 6.7130e-03, 6.7283e-03, 6.7435e-03, 6.7588e-03, 6.7740e-03, 6.7893e-03, 6.8046e-03, 6.8198e-03, 6.8351e-03, 6.8503e-03, 6.8656e-03, 6.8808e-03, 6.8961e-03, 6.9114e-03, 6.9266e-03, 6.9419e-03, 6.9571e-03, 6.9724e-03, 6.9877e-03, 7.0029e-03, 7.0182e-03, 7.0334e-03, 7.0487e-03, 7.0639e-03, 7.0792e-03, 7.0945e-03, 7.1097e-03, 7.1250e-03, 7.1402e-03, 7.1555e-03, 7.1708e-03, 7.1860e-03, 7.2013e-03, 7.2165e-03, 7.2318e-03, 7.2470e-03, 7.2623e-03, 7.2776e-03, 7.2928e-03, 7.3081e-03, 7.3233e-03, 7.3386e-03, 7.3539e-03, 7.3691e-03, 7.3844e-03, 7.3996e-03, 7.4149e-03, 7.4301e-03, 7.4454e-03, 7.4607e-03, 7.4759e-03, 7.4912e-03, 7.5064e-03, 7.5217e-03, 7.5370e-03, 7.5522e-03, 7.5675e-03, 7.5827e-03, 7.5980e-03, 7.6132e-03, 7.6285e-03, 7.6438e-03, 7.6590e-03, 7.6743e-03, 7.6895e-03, 7.7048e-03, 7.7201e-03, 7.7353e-03, 7.7506e-03, 7.7658e-03, 7.7811e-03, 7.7963e-03, 7.8116e-03, // NOLINT - 7.8421e-03, 7.8726e-03, 7.9032e-03, 7.9337e-03, 7.9642e-03, 7.9947e-03, 8.0252e-03, 8.0557e-03, 8.0863e-03, 8.1168e-03, 8.1473e-03, 8.1778e-03, 8.2083e-03, 8.2388e-03, 8.2694e-03, 8.2999e-03, 8.3304e-03, 8.3609e-03, 8.3914e-03, 8.4219e-03, 8.4525e-03, 8.4830e-03, 8.5135e-03, 8.5440e-03, 8.5745e-03, 8.6051e-03, 8.6356e-03, 8.6661e-03, 8.6966e-03, 8.7271e-03, 8.7576e-03, 8.7882e-03, 8.8187e-03, 8.8492e-03, 8.8797e-03, 8.9102e-03, 8.9407e-03, 8.9713e-03, 9.0018e-03, 9.0323e-03, 9.0628e-03, 9.0933e-03, 9.1238e-03, 9.1544e-03, 9.1849e-03, 9.2154e-03, 9.2459e-03, 9.2764e-03, 9.3069e-03, 9.3375e-03, 9.3680e-03, 9.3985e-03, 9.4290e-03, 9.4595e-03, 9.4900e-03, 9.5206e-03, 9.5511e-03, 9.5816e-03, 9.6121e-03, 9.6426e-03, 9.6731e-03, 9.7037e-03, 9.7342e-03, 9.7647e-03, 9.7952e-03, 9.8257e-03, 9.8563e-03, 9.8868e-03, 9.9173e-03, 9.9478e-03, 9.9783e-03, 1.0009e-02, 1.0039e-02, 1.0070e-02, 1.0100e-02, 1.0131e-02, 1.0161e-02, 1.0192e-02, 1.0222e-02, 1.0253e-02, 1.0283e-02, 1.0314e-02, 1.0345e-02, 1.0375e-02, 1.0406e-02, 1.0436e-02, 1.0467e-02, 1.0497e-02, 1.0528e-02, 1.0558e-02, 1.0589e-02, 1.0619e-02, 1.0650e-02, 1.0680e-02, 1.0711e-02, 1.0741e-02, 1.0772e-02, 1.0802e-02, 1.0833e-02, 1.0863e-02, 1.0894e-02, 1.0924e-02, 1.0955e-02, 1.0985e-02, 1.1016e-02, 1.1046e-02, 1.1077e-02, 1.1107e-02, 1.1138e-02, 1.1168e-02, 1.1199e-02, 1.1230e-02, 1.1260e-02, 1.1291e-02, 1.1321e-02, 1.1352e-02, 1.1382e-02, 1.1413e-02, 1.1443e-02, 1.1474e-02, 1.1504e-02, 1.1535e-02, 1.1565e-02, 1.1596e-02, 1.1626e-02, 1.1657e-02, 1.1687e-02, 1.1718e-02, 1.1748e-02, 1.1779e-02, 1.1809e-02, 1.1840e-02, 1.1870e-02, 1.1901e-02, 1.1931e-02, 1.1962e-02, 1.1992e-02, 1.2023e-02, 1.2053e-02, 1.2084e-02, 1.2115e-02, 1.2145e-02, 1.2176e-02, 1.2206e-02, 1.2237e-02, 1.2267e-02, 1.2298e-02, 1.2328e-02, 1.2359e-02, 1.2389e-02, 1.2420e-02, 1.2450e-02, 1.2481e-02, 1.2511e-02, 1.2542e-02, 1.2572e-02, 1.2603e-02, 1.2633e-02, 1.2664e-02, 1.2694e-02, 1.2725e-02, 1.2755e-02, 1.2786e-02, 1.2816e-02, 1.2847e-02, 1.2877e-02, 1.2908e-02, 1.2938e-02, 1.2969e-02, 1.3000e-02, 1.3030e-02, 1.3061e-02, 1.3091e-02, 1.3122e-02, 1.3152e-02, 1.3183e-02, 1.3213e-02, 1.3244e-02, 1.3274e-02, 1.3305e-02, 1.3335e-02, 1.3366e-02, 1.3396e-02, 1.3427e-02, 1.3457e-02, 1.3488e-02, 1.3518e-02, 1.3549e-02, 1.3579e-02, 1.3610e-02, 1.3640e-02, 1.3671e-02, 1.3701e-02, 1.3732e-02, 1.3762e-02, 1.3793e-02, 1.3823e-02, 1.3854e-02, 1.3885e-02, 1.3915e-02, 1.3946e-02, 1.3976e-02, 1.4007e-02, 1.4037e-02, 1.4068e-02, 1.4098e-02, 1.4129e-02, 1.4159e-02, 1.4190e-02, 1.4220e-02, 1.4251e-02, 1.4281e-02, 1.4312e-02, 1.4342e-02, 1.4373e-02, 1.4403e-02, 1.4434e-02, 1.4464e-02, 1.4495e-02, 1.4525e-02, 1.4556e-02, 1.4586e-02, 1.4617e-02, 1.4647e-02, 1.4678e-02, 1.4708e-02, 1.4739e-02, 1.4770e-02, 1.4800e-02, 1.4831e-02, 1.4861e-02, 1.4892e-02, 1.4922e-02, 1.4953e-02, 1.4983e-02, 1.5014e-02, 1.5044e-02, 1.5075e-02, 1.5105e-02, 1.5136e-02, 1.5166e-02, 1.5197e-02, 1.5227e-02, 1.5258e-02, 1.5288e-02, 1.5319e-02, 1.5349e-02, 1.5380e-02, 1.5410e-02, 1.5441e-02, 1.5471e-02, 1.5502e-02, 1.5532e-02, 1.5563e-02, 1.5593e-02, 1.5624e-02, // NOLINT - 1.5746e-02, 1.5868e-02, 1.5990e-02, 1.6112e-02, 1.6234e-02, 1.6356e-02, 1.6478e-02, 1.6601e-02, 1.6723e-02, 1.6845e-02, 1.6967e-02, 1.7089e-02, 1.7211e-02, 1.7333e-02, 1.7455e-02, 1.7577e-02, 1.7699e-02, 1.7821e-02, 1.7943e-02, 1.8065e-02, 1.8187e-02, 1.8310e-02, 1.8432e-02, 1.8554e-02, 1.8676e-02, 1.8798e-02, 1.8920e-02, 1.9042e-02, 1.9164e-02, 1.9286e-02, 1.9408e-02, 1.9530e-02, 1.9652e-02, 1.9774e-02, 1.9896e-02, 2.0018e-02, 2.0141e-02, 2.0263e-02, 2.0385e-02, 2.0507e-02, 2.0629e-02, 2.0751e-02, 2.0873e-02, 2.0995e-02, 2.1117e-02, 2.1239e-02, 2.1361e-02, 2.1483e-02, 2.1605e-02, 2.1727e-02, 2.1850e-02, 2.1972e-02, 2.2094e-02, 2.2216e-02, 2.2338e-02, 2.2460e-02, 2.2582e-02, 2.2704e-02, 2.2826e-02, 2.2948e-02, 2.3070e-02, 2.3192e-02, 2.3314e-02, 2.3436e-02, 2.3558e-02, 2.3681e-02, 2.3803e-02, 2.3925e-02, 2.4047e-02, 2.4169e-02, 2.4291e-02, 2.4413e-02, 2.4535e-02, 2.4657e-02, 2.4779e-02, 2.4901e-02, 2.5023e-02, 2.5145e-02, 2.5267e-02, 2.5390e-02, 2.5512e-02, 2.5634e-02, 2.5756e-02, 2.5878e-02, 2.6000e-02, 2.6122e-02, 2.6244e-02, 2.6366e-02, 2.6488e-02, 2.6610e-02, 2.6732e-02, 2.6854e-02, 2.6976e-02, 2.7099e-02, 2.7221e-02, 2.7343e-02, 2.7465e-02, 2.7587e-02, 2.7709e-02, 2.7831e-02, 2.7953e-02, 2.8075e-02, 2.8197e-02, 2.8319e-02, 2.8441e-02, 2.8563e-02, 2.8685e-02, 2.8807e-02, 2.8930e-02, 2.9052e-02, 2.9174e-02, 2.9296e-02, 2.9418e-02, 2.9540e-02, 2.9662e-02, 2.9784e-02, 2.9906e-02, 3.0028e-02, 3.0150e-02, 3.0272e-02, 3.0394e-02, 3.0516e-02, 3.0639e-02, 3.0761e-02, 3.0883e-02, 3.1005e-02, 3.1127e-02, 3.1249e-02, 3.1493e-02, 3.1737e-02, 3.1981e-02, 3.2225e-02, 3.2470e-02, 3.2714e-02, 3.2958e-02, 3.3202e-02, 3.3446e-02, 3.3690e-02, 3.3934e-02, 3.4179e-02, 3.4423e-02, 3.4667e-02, 3.4911e-02, 3.5155e-02, 3.5399e-02, 3.5643e-02, 3.5888e-02, 3.6132e-02, 3.6376e-02, 3.6620e-02, 3.6864e-02, 3.7108e-02, 3.7352e-02, 3.7596e-02, 3.7841e-02, 3.8085e-02, 3.8329e-02, 3.8573e-02, 3.8817e-02, 3.9061e-02, 3.9305e-02, 3.9550e-02, 3.9794e-02, 4.0038e-02, 4.0282e-02, 4.0526e-02, 4.0770e-02, 4.1014e-02, 4.1259e-02, 4.1503e-02, 4.1747e-02, 4.1991e-02, 4.2235e-02, 4.2479e-02, 4.2723e-02, 4.2968e-02, 4.3212e-02, 4.3456e-02, 4.3700e-02, 4.3944e-02, 4.4188e-02, 4.4432e-02, 4.4677e-02, 4.4921e-02, 4.5165e-02, 4.5409e-02, 4.5653e-02, 4.5897e-02, 4.6141e-02, 4.6386e-02, 4.6630e-02, 4.6874e-02, 4.7118e-02, 4.7362e-02, 4.7606e-02, 4.7850e-02, 4.8095e-02, 4.8339e-02, 4.8583e-02, 4.8827e-02, 4.9071e-02, 4.9315e-02, 4.9559e-02, 4.9803e-02, 5.0048e-02, 5.0292e-02, 5.0536e-02, 5.0780e-02, 5.1024e-02, 5.1268e-02, 5.1512e-02, 5.1757e-02, 5.2001e-02, 5.2245e-02, 5.2489e-02, 5.2733e-02, 5.2977e-02, 5.3221e-02, 5.3466e-02, 5.3710e-02, 5.3954e-02, 5.4198e-02, 5.4442e-02, 5.4686e-02, 5.4930e-02, 5.5175e-02, 5.5419e-02, 5.5663e-02, 5.5907e-02, 5.6151e-02, 5.6395e-02, 5.6639e-02, 5.6884e-02, 5.7128e-02, 5.7372e-02, 5.7616e-02, 5.7860e-02, 5.8104e-02, 5.8348e-02, 5.8593e-02, 5.8837e-02, 5.9081e-02, 5.9325e-02, 5.9569e-02, 5.9813e-02, 6.0057e-02, 6.0301e-02, 6.0546e-02, 6.0790e-02, 6.1034e-02, 6.1278e-02, 6.1522e-02, 6.1766e-02, 6.2010e-02, 6.2255e-02, 6.2499e-02, // NOLINT - 6.2743e-02, 6.2987e-02, 6.3231e-02, 6.3475e-02, 6.3719e-02, 6.3964e-02, 6.4208e-02, 6.4452e-02, 6.4696e-02, 6.4940e-02, 6.5184e-02, 6.5428e-02, 6.5673e-02, 6.5917e-02, 6.6161e-02, 6.6405e-02, 6.6649e-02, 6.6893e-02, 6.7137e-02, 6.7382e-02, 6.7626e-02, 6.7870e-02, 6.8114e-02, 6.8358e-02, 6.8602e-02, 6.8846e-02, 6.9091e-02, 6.9335e-02, 6.9579e-02, 6.9823e-02, 7.0067e-02, 7.0311e-02, 7.0555e-02, 7.0799e-02, 7.1044e-02, 7.1288e-02, 7.1532e-02, 7.1776e-02, 7.2020e-02, 7.2264e-02, 7.2508e-02, 7.2753e-02, 7.2997e-02, 7.3241e-02, 7.3485e-02, 7.3729e-02, 7.3973e-02, 7.4217e-02, 7.4462e-02, 7.4706e-02, 7.4950e-02, 7.5194e-02, 7.5438e-02, 7.5682e-02, 7.5926e-02, 7.6171e-02, 7.6415e-02, 7.6659e-02, 7.6903e-02, 7.7147e-02, 7.7391e-02, 7.7635e-02, 7.7880e-02, 7.8124e-02, 7.8368e-02, 7.8612e-02, 7.8856e-02, 7.9100e-02, 7.9344e-02, 7.9589e-02, 7.9833e-02, 8.0077e-02, 8.0321e-02, 8.0565e-02, 8.0809e-02, 8.1053e-02, 8.1298e-02, 8.1542e-02, 8.1786e-02, 8.2030e-02, 8.2274e-02, 8.2518e-02, 8.2762e-02, 8.3006e-02, 8.3251e-02, 8.3495e-02, 8.3739e-02, 8.3983e-02, 8.4227e-02, 8.4471e-02, 8.4715e-02, 8.4960e-02, 8.5204e-02, 8.5448e-02, 8.5692e-02, 8.5936e-02, 8.6180e-02, 8.6424e-02, 8.6669e-02, 8.6913e-02, 8.7157e-02, 8.7401e-02, 8.7645e-02, 8.7889e-02, 8.8133e-02, 8.8378e-02, 8.8622e-02, 8.8866e-02, 8.9110e-02, 8.9354e-02, 8.9598e-02, 8.9842e-02, 9.0087e-02, 9.0331e-02, 9.0575e-02, 9.0819e-02, 9.1063e-02, 9.1307e-02, 9.1551e-02, 9.1796e-02, 9.2040e-02, 9.2284e-02, 9.2528e-02, 9.2772e-02, 9.3016e-02, 9.3260e-02, 9.3504e-02, 9.3749e-02, 9.4237e-02, 9.4725e-02, 9.5213e-02, 9.5702e-02, 9.6190e-02, 9.6678e-02, 9.7167e-02, 9.7655e-02, 9.8143e-02, 9.8631e-02, 9.9120e-02, 9.9608e-02, 1.0010e-01, 1.0058e-01, 1.0107e-01, 1.0156e-01, 1.0205e-01, 1.0254e-01, 1.0303e-01, 1.0351e-01, 1.0400e-01, 1.0449e-01, 1.0498e-01, 1.0547e-01, 1.0596e-01, 1.0644e-01, 1.0693e-01, 1.0742e-01, 1.0791e-01, 1.0840e-01, 1.0889e-01, 1.0937e-01, 1.0986e-01, 1.1035e-01, 1.1084e-01, 1.1133e-01, 1.1182e-01, 1.1230e-01, 1.1279e-01, 1.1328e-01, 1.1377e-01, 1.1426e-01, 1.1474e-01, 1.1523e-01, 1.1572e-01, 1.1621e-01, 1.1670e-01, 1.1719e-01, 1.1767e-01, 1.1816e-01, 1.1865e-01, 1.1914e-01, 1.1963e-01, 1.2012e-01, 1.2060e-01, 1.2109e-01, 1.2158e-01, 1.2207e-01, 1.2256e-01, 1.2305e-01, 1.2353e-01, 1.2402e-01, 1.2451e-01, 1.2500e-01, 1.2549e-01, 1.2598e-01, 1.2646e-01, 1.2695e-01, 1.2744e-01, 1.2793e-01, 1.2842e-01, 1.2890e-01, 1.2939e-01, 1.2988e-01, 1.3037e-01, 1.3086e-01, 1.3135e-01, 1.3183e-01, 1.3232e-01, 1.3281e-01, 1.3330e-01, 1.3379e-01, 1.3428e-01, 1.3476e-01, 1.3525e-01, 1.3574e-01, 1.3623e-01, 1.3672e-01, 1.3721e-01, 1.3769e-01, 1.3818e-01, 1.3867e-01, 1.3916e-01, 1.3965e-01, 1.4014e-01, 1.4062e-01, 1.4111e-01, 1.4160e-01, 1.4209e-01, 1.4258e-01, 1.4306e-01, 1.4355e-01, 1.4404e-01, 1.4453e-01, 1.4502e-01, 1.4551e-01, 1.4599e-01, 1.4648e-01, 1.4697e-01, 1.4746e-01, 1.4795e-01, 1.4844e-01, 1.4892e-01, 1.4941e-01, 1.4990e-01, 1.5039e-01, 1.5088e-01, 1.5137e-01, 1.5185e-01, 1.5234e-01, 1.5283e-01, 1.5332e-01, 1.5381e-01, 1.5430e-01, 1.5478e-01, 1.5527e-01, 1.5576e-01, 1.5625e-01, // NOLINT - 1.5674e-01, 1.5723e-01, 1.5771e-01, 1.5820e-01, 1.5869e-01, 1.5918e-01, 1.5967e-01, 1.6015e-01, 1.6064e-01, 1.6113e-01, 1.6162e-01, 1.6211e-01, 1.6260e-01, 1.6308e-01, 1.6357e-01, 1.6406e-01, 1.6455e-01, 1.6504e-01, 1.6553e-01, 1.6601e-01, 1.6650e-01, 1.6699e-01, 1.6748e-01, 1.6797e-01, 1.6846e-01, 1.6894e-01, 1.6943e-01, 1.6992e-01, 1.7041e-01, 1.7090e-01, 1.7139e-01, 1.7187e-01, 1.7236e-01, 1.7285e-01, 1.7334e-01, 1.7383e-01, 1.7431e-01, 1.7480e-01, 1.7529e-01, 1.7578e-01, 1.7627e-01, 1.7676e-01, 1.7724e-01, 1.7773e-01, 1.7822e-01, 1.7871e-01, 1.7920e-01, 1.7969e-01, 1.8017e-01, 1.8066e-01, 1.8115e-01, 1.8164e-01, 1.8213e-01, 1.8262e-01, 1.8310e-01, 1.8359e-01, 1.8408e-01, 1.8457e-01, 1.8506e-01, 1.8555e-01, 1.8603e-01, 1.8652e-01, 1.8701e-01, 1.8750e-01, 1.8848e-01, 1.8945e-01, 1.9043e-01, 1.9140e-01, 1.9238e-01, 1.9336e-01, 1.9433e-01, 1.9531e-01, 1.9629e-01, 1.9726e-01, 1.9824e-01, 1.9922e-01, 2.0019e-01, 2.0117e-01, 2.0215e-01, 2.0312e-01, 2.0410e-01, 2.0508e-01, 2.0605e-01, 2.0703e-01, 2.0801e-01, 2.0898e-01, 2.0996e-01, 2.1094e-01, 2.1191e-01, 2.1289e-01, 2.1387e-01, 2.1484e-01, 2.1582e-01, 2.1680e-01, 2.1777e-01, 2.1875e-01, 2.1972e-01, 2.2070e-01, 2.2168e-01, 2.2265e-01, 2.2363e-01, 2.2461e-01, 2.2558e-01, 2.2656e-01, 2.2754e-01, 2.2851e-01, 2.2949e-01, 2.3047e-01, 2.3144e-01, 2.3242e-01, 2.3340e-01, 2.3437e-01, 2.3535e-01, 2.3633e-01, 2.3730e-01, 2.3828e-01, 2.3926e-01, 2.4023e-01, 2.4121e-01, 2.4219e-01, 2.4316e-01, 2.4414e-01, 2.4512e-01, 2.4609e-01, 2.4707e-01, 2.4805e-01, 2.4902e-01, 2.5000e-01, 2.5097e-01, 2.5195e-01, 2.5293e-01, 2.5390e-01, 2.5488e-01, 2.5586e-01, 2.5683e-01, 2.5781e-01, 2.5879e-01, 2.5976e-01, 2.6074e-01, 2.6172e-01, 2.6269e-01, 2.6367e-01, 2.6465e-01, 2.6562e-01, 2.6660e-01, 2.6758e-01, 2.6855e-01, 2.6953e-01, 2.7051e-01, 2.7148e-01, 2.7246e-01, 2.7344e-01, 2.7441e-01, 2.7539e-01, 2.7637e-01, 2.7734e-01, 2.7832e-01, 2.7930e-01, 2.8027e-01, 2.8125e-01, 2.8222e-01, 2.8320e-01, 2.8418e-01, 2.8515e-01, 2.8613e-01, 2.8711e-01, 2.8808e-01, 2.8906e-01, 2.9004e-01, 2.9101e-01, 2.9199e-01, 2.9297e-01, 2.9394e-01, 2.9492e-01, 2.9590e-01, 2.9687e-01, 2.9785e-01, 2.9883e-01, 2.9980e-01, 3.0078e-01, 3.0176e-01, 3.0273e-01, 3.0371e-01, 3.0469e-01, 3.0566e-01, 3.0664e-01, 3.0762e-01, 3.0859e-01, 3.0957e-01, 3.1055e-01, 3.1152e-01, 3.1250e-01, 3.1347e-01, 3.1445e-01, 3.1543e-01, 3.1640e-01, 3.1738e-01, 3.1836e-01, 3.1933e-01, 3.2031e-01, 3.2129e-01, 3.2226e-01, 3.2324e-01, 3.2422e-01, 3.2519e-01, 3.2617e-01, 3.2715e-01, 3.2812e-01, 3.2910e-01, 3.3008e-01, 3.3105e-01, 3.3203e-01, 3.3301e-01, 3.3398e-01, 3.3496e-01, 3.3594e-01, 3.3691e-01, 3.3789e-01, 3.3887e-01, 3.3984e-01, 3.4082e-01, 3.4180e-01, 3.4277e-01, 3.4375e-01, 3.4472e-01, 3.4570e-01, 3.4668e-01, 3.4765e-01, 3.4863e-01, 3.4961e-01, 3.5058e-01, 3.5156e-01, 3.5254e-01, 3.5351e-01, 3.5449e-01, 3.5547e-01, 3.5644e-01, 3.5742e-01, 3.5840e-01, 3.5937e-01, 3.6035e-01, 3.6133e-01, 3.6230e-01, 3.6328e-01, 3.6426e-01, 3.6523e-01, 3.6621e-01, 3.6719e-01, 3.6816e-01, 3.6914e-01, 3.7012e-01, 3.7109e-01, 3.7207e-01, 3.7305e-01, 3.7402e-01, 3.7500e-01, // NOLINT - 3.7695e-01, 3.7890e-01, 3.8086e-01, 3.8281e-01, 3.8476e-01, 3.8672e-01, 3.8867e-01, 3.9062e-01, 3.9258e-01, 3.9453e-01, 3.9648e-01, 3.9844e-01, 4.0039e-01, 4.0234e-01, 4.0430e-01, 4.0625e-01, 4.0820e-01, 4.1015e-01, 4.1211e-01, 4.1406e-01, 4.1601e-01, 4.1797e-01, 4.1992e-01, 4.2187e-01, 4.2383e-01, 4.2578e-01, 4.2773e-01, 4.2969e-01, 4.3164e-01, 4.3359e-01, 4.3555e-01, 4.3750e-01, 4.3945e-01, 4.4140e-01, 4.4336e-01, 4.4531e-01, 4.4726e-01, 4.4922e-01, 4.5117e-01, 4.5312e-01, 4.5508e-01, 4.5703e-01, 4.5898e-01, 4.6094e-01, 4.6289e-01, 4.6484e-01, 4.6680e-01, 4.6875e-01, 4.7070e-01, 4.7265e-01, 4.7461e-01, 4.7656e-01, 4.7851e-01, 4.8047e-01, 4.8242e-01, 4.8437e-01, 4.8633e-01, 4.8828e-01, 4.9023e-01, 4.9219e-01, 4.9414e-01, 4.9609e-01, 4.9805e-01, 5.0000e-01, 5.0195e-01, 5.0390e-01, 5.0586e-01, 5.0781e-01, 5.0976e-01, 5.1172e-01, 5.1367e-01, 5.1562e-01, 5.1758e-01, 5.1953e-01, 5.2148e-01, 5.2344e-01, 5.2539e-01, 5.2734e-01, 5.2930e-01, 5.3125e-01, 5.3320e-01, 5.3515e-01, 5.3711e-01, 5.3906e-01, 5.4101e-01, 5.4297e-01, 5.4492e-01, 5.4687e-01, 5.4883e-01, 5.5078e-01, 5.5273e-01, 5.5469e-01, 5.5664e-01, 5.5859e-01, 5.6055e-01, 5.6250e-01, 5.6445e-01, 5.6640e-01, 5.6836e-01, 5.7031e-01, 5.7226e-01, 5.7422e-01, 5.7617e-01, 5.7812e-01, 5.8008e-01, 5.8203e-01, 5.8398e-01, 5.8594e-01, 5.8789e-01, 5.8984e-01, 5.9180e-01, 5.9375e-01, 5.9570e-01, 5.9765e-01, 5.9961e-01, 6.0156e-01, 6.0351e-01, 6.0547e-01, 6.0742e-01, 6.0937e-01, 6.1133e-01, 6.1328e-01, 6.1523e-01, 6.1719e-01, 6.1914e-01, 6.2109e-01, 6.2305e-01, 6.2500e-01, 6.2695e-01, 6.2890e-01, 6.3086e-01, 6.3281e-01, 6.3476e-01, 6.3672e-01, 6.3867e-01, 6.4062e-01, 6.4258e-01, 6.4453e-01, 6.4648e-01, 6.4844e-01, 6.5039e-01, 6.5234e-01, 6.5430e-01, 6.5625e-01, 6.5820e-01, 6.6015e-01, 6.6211e-01, 6.6406e-01, 6.6601e-01, 6.6797e-01, 6.6992e-01, 6.7187e-01, 6.7383e-01, 6.7578e-01, 6.7773e-01, 6.7969e-01, 6.8164e-01, 6.8359e-01, 6.8554e-01, 6.8750e-01, 6.8945e-01, 6.9140e-01, 6.9336e-01, 6.9531e-01, 6.9726e-01, 6.9922e-01, 7.0117e-01, 7.0312e-01, 7.0508e-01, 7.0703e-01, 7.0898e-01, 7.1094e-01, 7.1289e-01, 7.1484e-01, 7.1679e-01, 7.1875e-01, 7.2070e-01, 7.2265e-01, 7.2461e-01, 7.2656e-01, 7.2851e-01, 7.3047e-01, 7.3242e-01, 7.3437e-01, 7.3633e-01, 7.3828e-01, 7.4023e-01, 7.4219e-01, 7.4414e-01, 7.4609e-01, 7.4804e-01, 7.5000e-01, 7.5390e-01, 7.5781e-01, 7.6172e-01, 7.6562e-01, 7.6953e-01, 7.7344e-01, 7.7734e-01, 7.8125e-01, 7.8515e-01, 7.8906e-01, 7.9297e-01, 7.9687e-01, 8.0078e-01, 8.0469e-01, 8.0859e-01, 8.1250e-01, 8.1640e-01, 8.2031e-01, 8.2422e-01, 8.2812e-01, 8.3203e-01, 8.3594e-01, 8.3984e-01, 8.4375e-01, 8.4765e-01, 8.5156e-01, 8.5547e-01, 8.5937e-01, 8.6328e-01, 8.6719e-01, 8.7109e-01, 8.7500e-01, 8.7890e-01, 8.8281e-01, 8.8672e-01, 8.9062e-01, 8.9453e-01, 8.9844e-01, 9.0234e-01, 9.0625e-01, 9.1015e-01, 9.1406e-01, 9.1797e-01, 9.2187e-01, 9.2578e-01, 9.2969e-01, 9.3359e-01, 9.3750e-01, 9.4140e-01, 9.4531e-01, 9.4922e-01, 9.5312e-01, 9.5703e-01, 9.6094e-01, 9.6484e-01, 9.6875e-01, 9.7265e-01, 9.7656e-01, 9.8047e-01, 9.8437e-01, 9.8828e-01, 9.9219e-01, 9.9609e-01, 1.0000e+00 // NOLINT -}; +float ox_lut_func(int x) { + if (x < 512) { + return x * 5.94873e-8; + } else if (512 <= x < 768) { + return 3.0458e-05 + (x-512) * 1.19913e-7; + } else if (768 <= x < 1536) { + return 6.1154e-05 + (x-768) * 2.38493e-7; + } else if (1536 <= x < 1792) { + return 0.0002448 + (x-1536) * 9.56930e-7; + } else if (1792 <= x < 2048) { + return 0.00048977 + (x-1792) * 1.91441e-6; + } else if (2048 <= x < 2304) { + return 0.00097984 + (x-2048) * 3.82937e-6; + } else if (2304 <= x < 2560) { + return 0.0019601 + (x-2304) * 7.659055e-6; + } else if (2560 <= x < 2816) { + return 0.0039207 + (x-2560) * 1.525e-5; + } else { + return 0.0078421 + (exp((x-2816)/273.0) - 1) * 0.0092421; + } +} float4 normalize_pv(int4 parsed, float vignette_factor) { // PWL - float4 pv = {ox03c10_lut[parsed.s0], ox03c10_lut[parsed.s1], ox03c10_lut[parsed.s2], ox03c10_lut[parsed.s3]}; + float4 pv = {ox_lut_func(parsed.s0), ox_lut_func(parsed.s1), ox_lut_func(parsed.s2), ox_lut_func(parsed.s3)}; return clamp(pv*vignette_factor*256.0, 0.0, 1.0); } @@ -40,4 +43,4 @@ float3 apply_gamma(float3 rgb, int expo_time) { return -0.507089*exp(-12.54124638*rgb) + 0.9655*powr(rgb, 0.5) - 0.472597*rgb + 0.507089; } -#endif \ No newline at end of file +#endif From 36a9687d5d60c0cf26387f8edcf5f6ccc9214d0d Mon Sep 17 00:00:00 2001 From: YassineYousfi Date: Thu, 26 Sep 2024 11:01:56 -0700 Subject: [PATCH 144/214] long planner: use temporalPose for v_model_error calibration (#33655) * long planner: add flag to disable v_model_error calibration * use temporal pose instead of flag * udpate model replay ref --- selfdrive/controls/lib/drive_helpers.py | 4 ++-- selfdrive/modeld/fill_model_msg.py | 7 +++++++ selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 3 files changed, 10 insertions(+), 3 deletions(-) diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 369aeaf984..64cbf473d6 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -22,7 +22,7 @@ def clip_curvature(v_ego, prev_curvature, new_curvature): def get_speed_error(modelV2: log.ModelDataV2, v_ego: float) -> float: # ToDo: Try relative error, and absolute speed - if len(modelV2.velocity.x): - vel_err = clip(modelV2.velocity.x[0] - v_ego, -MAX_VEL_ERR, MAX_VEL_ERR) + if len(modelV2.temporalPose.trans): + vel_err = clip(modelV2.temporalPose.trans[0] - v_ego, -MAX_VEL_ERR, MAX_VEL_ERR) return float(vel_err) return 0.0 diff --git a/selfdrive/modeld/fill_model_msg.py b/selfdrive/modeld/fill_model_msg.py index 18dd9c7bac..10a1860b58 100644 --- a/selfdrive/modeld/fill_model_msg.py +++ b/selfdrive/modeld/fill_model_msg.py @@ -87,6 +87,13 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D orientation_rate = modelV2.orientationRate fill_xyzt(orientation_rate, ModelConstants.T_IDXS, *net_output_data['plan'][0,:,Plan.ORIENTATION_RATE].T) + # temporal pose + temporal_pose = modelV2.temporalPose + temporal_pose.trans = net_output_data['plan'][0,0,Plan.VELOCITY].tolist() + temporal_pose.transStd = net_output_data['plan_stds'][0,0,Plan.VELOCITY].tolist() + temporal_pose.rot = net_output_data['plan'][0,0,Plan.ORIENTATION_RATE].tolist() + temporal_pose.rotStd = net_output_data['plan_stds'][0,0,Plan.ORIENTATION_RATE].tolist() + # poly path poly_path = driving_model_data.path fill_xyz_poly(poly_path, ModelConstants.POLY_PATH_DEGREE, *net_output_data['plan'][0,:,Plan.POSITION].T) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index de6f6027c4..7d588b26fa 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -9d4d653d8cc361fe2ba53f74fd8fcfe1f1d559ed +666448fce191e196aac68d06e29a0745e6620db9 From e2f99426334dda3542760f8dacec124ffc85c980 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Thu, 26 Sep 2024 12:10:06 -0700 Subject: [PATCH 145/214] HKG: CAN-FD EV refactor, support for Genesis GV70 Electrified (#33657) * bump opendbc * regen CARS.md * bump opendbc to master --- docs/CARS.md | 3 ++- opendbc_repo | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index e94df79787..eea3eef1fc 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,7 +4,7 @@ A supported vehicle is one that just works when you install a comma device. All supported cars provide a better experience than any stock system. Supported vehicles reference the US market unless otherwise specified. -# 287 Supported Cars +# 288 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Hardware Needed
 |Video| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:| @@ -55,6 +55,7 @@ A supported vehicle is one that just works when you install a comma device. All |Genesis|GV60 (Performance Trim) 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|GV70 (2.5T Trim, without HDA II) 2022-23[5](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|GV70 (3.5T Trim, without HDA II) 2022-23[5](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Genesis|GV70 Electrified (with HDA II) 2023[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|GV80 2023[5](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |GMC|Sierra 1500 2020-21|Driver Alert Package II|openpilot available[1](#footnotes)|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Honda|Accord 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| diff --git a/opendbc_repo b/opendbc_repo index bda4ad475a..b11c159d87 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit bda4ad475aaf7a92f677ac2d50b6b7af0ffdf5fc +Subproject commit b11c159d87635ce698ec79d55516f202afa86f91 From 876f1921124059aa0395ed5131d7943ca10364f8 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Thu, 26 Sep 2024 16:40:44 -0700 Subject: [PATCH 146/214] exec DM model with gpu (#33609) * half old-commit-hash: 9f72eca003d4637ca7fe847ebaf925c694fc2e84 * optimed old-commit-hash: 6e36e2a12e09275ec21d1590012a92b05ca52ff5 * thneed old-commit-hash: 419a06c09c0c767d828bcd1e118bc575898c343a * exec old-commit-hash: 0059c27ec11b076a37f65d604ed135ea6541b1a6 * runner old-commit-hash: 34232ada94450ce541eaef546197fa219810a891 * runs but old-commit-hash: 3db37c00b6a64908293b4de8d8b56e80308cd8f2 * it is 01 old-commit-hash: a160d81eb1a7e77abbef959b44f602610f68f665 * np old-commit-hash: c1caff6ba648cc2c0094c71b2ea074f01c3c2dc8 * module url old-commit-hash: 6f4902c4d384263a53e2c1d14d93b5ff864b6a5f * new old-commit-hash: 779ae79b1bc3df6374fb6663ac8592e107a6e504 * ds fast * is this work * corcention * real timing * no reg * interim gather * 0e4a9c7b * fa69be01, and halve * list * cleanup * slighly faster * setprotlt * expected * replay ref * more powar * reluctantly * bump tg * 8 * less * less * bump tg * better than exp * closer * cc * see diff * commits * was right * to 32 cast * remove dlc file * support both * dspExecutionTime -> gpuExecutionTime * ignore * time ref * ref commit * last --------- Co-authored-by: Comma Device --- .gitattributes | 1 - cereal/log.capnp | 3 +- selfdrive/modeld/SConscript | 4 ++ selfdrive/modeld/dmonitoringmodeld | 10 +++++ selfdrive/modeld/dmonitoringmodeld.py | 37 +++++++++++-------- .../modeld/models/dmonitoring_model.current | 4 +- .../modeld/models/dmonitoring_model.onnx | 4 +- .../modeld/models/dmonitoring_model_q.dlc | 3 -- selfdrive/modeld/runners/onnxmodel.py | 3 +- selfdrive/monitoring/helpers.py | 4 +- selfdrive/test/process_replay/model_replay.py | 2 +- .../process_replay/model_replay_ref_commit | 2 +- .../test/process_replay/process_replay.py | 2 +- selfdrive/test/test_onroad.py | 3 +- system/hardware/tici/tests/test_power_draw.py | 2 +- system/manager/process_config.py | 2 +- tinygrad_repo | 2 +- 17 files changed, 53 insertions(+), 35 deletions(-) create mode 100755 selfdrive/modeld/dmonitoringmodeld delete mode 100644 selfdrive/modeld/models/dmonitoring_model_q.dlc diff --git a/.gitattributes b/.gitattributes index 8781a7371f..eda2505d0e 100644 --- a/.gitattributes +++ b/.gitattributes @@ -2,7 +2,6 @@ # to move existing files into LFS: # git add --renormalize . -*.dlc filter=lfs diff=lfs merge=lfs -text *.onnx filter=lfs diff=lfs merge=lfs -text *.svg filter=lfs diff=lfs merge=lfs -text *.png filter=lfs diff=lfs merge=lfs -text diff --git a/cereal/log.capnp b/cereal/log.capnp index c955cbf154..3d5f7d9d7f 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -2012,7 +2012,8 @@ struct Joystick { struct DriverStateV2 { frameId @0 :UInt32; modelExecutionTime @1 :Float32; - dspExecutionTime @2 :Float32; + dspExecutionTimeDEPRECATED @2 :Float32; + gpuExecutionTime @8 :Float32; rawPredictions @3 :Data; poorVisionProb @4 :Float32; diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index d572915c72..d472998416 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -69,6 +69,10 @@ if arch == "larch64" or GetOption('pc_thneed'): lenv.Command(fn + ".thneed", [fn + ".onnx"] + tinygrad_files, cmd) + fn_dm = File("models/dmonitoring_model").abspath + cmd = f"cd {Dir('#').abspath}/tinygrad_repo && " + ' '.join(tinygrad_opts) + f" python3 openpilot/compile2.py {fn_dm}.onnx {fn_dm}.thneed" + lenv.Command(fn_dm + ".thneed", [fn_dm + ".onnx"] + tinygrad_files, cmd) + thneed_lib = env.SharedLibrary('thneed', thneed_src, LIBS=[gpucommon, common, 'OpenCL', 'dl']) thneedmodel_lib = env.Library('thneedmodel', ['runners/thneedmodel.cc']) lenvCython.Program('runners/thneedmodel_pyx.so', 'runners/thneedmodel_pyx.pyx', LIBS=envCython["LIBS"]+[thneedmodel_lib, thneed_lib, gpucommon, common, 'dl', 'OpenCL']) diff --git a/selfdrive/modeld/dmonitoringmodeld b/selfdrive/modeld/dmonitoringmodeld new file mode 100755 index 0000000000..80157e1751 --- /dev/null +++ b/selfdrive/modeld/dmonitoringmodeld @@ -0,0 +1,10 @@ +#!/usr/bin/env bash + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd "$DIR/../../" + +if [ -f "$DIR/libthneed.so" ]; then + export LD_PRELOAD="$DIR/libthneed.so" +fi + +exec "$DIR/dmonitoringmodeld.py" "$@" diff --git a/selfdrive/modeld/dmonitoringmodeld.py b/selfdrive/modeld/dmonitoringmodeld.py index 0187184a7a..3030b31a0c 100755 --- a/selfdrive/modeld/dmonitoringmodeld.py +++ b/selfdrive/modeld/dmonitoringmodeld.py @@ -6,6 +6,7 @@ import time import ctypes import numpy as np from pathlib import Path +from setproctitle import setproctitle from cereal import messaging from cereal.messaging import PubMaster, SubMaster @@ -14,16 +15,19 @@ from openpilot.common.swaglog import cloudlog from openpilot.common.params import Params from openpilot.common.realtime import set_realtime_priority from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime +from openpilot.selfdrive.modeld.models.commonmodel_pyx import CLContext from openpilot.selfdrive.modeld.parse_model_outputs import sigmoid CALIB_LEN = 3 -REG_SCALE = 0.25 MODEL_WIDTH = 1440 MODEL_HEIGHT = 960 -OUTPUT_SIZE = 84 +FEATURE_LEN = 512 +OUTPUT_SIZE = 84 + FEATURE_LEN + +PROCESS_NAME = "selfdrive.modeld.dmonitoringmodeld" SEND_RAW_PRED = os.getenv('SEND_RAW_PRED') MODEL_PATHS = { - ModelRunner.SNPE: Path(__file__).parent / 'models/dmonitoring_model_q.dlc', + ModelRunner.THNEED: Path(__file__).parent / 'models/dmonitoring_model.thneed', ModelRunner.ONNX: Path(__file__).parent / 'models/dmonitoring_model.onnx'} class DriverStateResult(ctypes.Structure): @@ -49,21 +53,22 @@ class DMonitoringModelResult(ctypes.Structure): ("driver_state_lhd", DriverStateResult), ("driver_state_rhd", DriverStateResult), ("poor_vision_prob", ctypes.c_float), - ("wheel_on_right_prob", ctypes.c_float)] + ("wheel_on_right_prob", ctypes.c_float), + ("features", ctypes.c_float*FEATURE_LEN)] class ModelState: inputs: dict[str, np.ndarray] output: np.ndarray model: ModelRunner - def __init__(self): + def __init__(self, cl_ctx): assert ctypes.sizeof(DMonitoringModelResult) == OUTPUT_SIZE * ctypes.sizeof(ctypes.c_float) self.output = np.zeros(OUTPUT_SIZE, dtype=np.float32) self.inputs = { 'input_img': np.zeros(MODEL_HEIGHT * MODEL_WIDTH, dtype=np.uint8), 'calib': np.zeros(CALIB_LEN, dtype=np.float32)} - self.model = ModelRunner(MODEL_PATHS, self.output, Runtime.DSP, True, None) + self.model = ModelRunner(MODEL_PATHS, self.output, Runtime.GPU, False, cl_ctx) self.model.addInput("input_img", None) self.model.addInput("calib", self.inputs['calib']) @@ -76,17 +81,17 @@ class ModelState: input_data = self.inputs['input_img'].reshape(MODEL_HEIGHT, MODEL_WIDTH) input_data[:] = buf_data[v_offset:v_offset+MODEL_HEIGHT, h_offset:h_offset+MODEL_WIDTH] - t1 = time.perf_counter() self.model.setInputBuffer("input_img", self.inputs['input_img'].view(np.float32)) + t1 = time.perf_counter() self.model.execute() t2 = time.perf_counter() return self.output, t2 - t1 def fill_driver_state(msg, ds_result: DriverStateResult): - msg.faceOrientation = [x * REG_SCALE for x in ds_result.face_orientation] + msg.faceOrientation = list(ds_result.face_orientation) msg.faceOrientationStd = [math.exp(x) for x in ds_result.face_orientation_std] - msg.facePosition = [x * REG_SCALE for x in ds_result.face_position[:2]] + msg.facePosition = list(ds_result.face_position[:2]) msg.facePositionStd = [math.exp(x) for x in ds_result.face_position_std[:2]] msg.faceProb = float(sigmoid(ds_result.face_prob)) msg.leftEyeProb = float(sigmoid(ds_result.left_eye_prob)) @@ -98,13 +103,13 @@ def fill_driver_state(msg, ds_result: DriverStateResult): msg.readyProb = [float(sigmoid(x)) for x in ds_result.ready_prob] msg.notReadyProb = [float(sigmoid(x)) for x in ds_result.not_ready_prob] -def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: int, execution_time: float, dsp_execution_time: float): +def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: int, execution_time: float, gpu_execution_time: float): model_result = ctypes.cast(model_output.ctypes.data, ctypes.POINTER(DMonitoringModelResult)).contents msg = messaging.new_message('driverStateV2', valid=True) ds = msg.driverStateV2 ds.frameId = frame_id ds.modelExecutionTime = execution_time - ds.dspExecutionTime = dsp_execution_time + ds.gpuExecutionTime = gpu_execution_time ds.poorVisionProb = float(sigmoid(model_result.poor_vision_prob)) ds.wheelOnRightProb = float(sigmoid(model_result.wheel_on_right_prob)) ds.rawPredictions = model_output.tobytes() if SEND_RAW_PRED else b'' @@ -115,14 +120,16 @@ def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: def main(): gc.disable() + setproctitle(PROCESS_NAME) set_realtime_priority(1) - model = ModelState() + cl_context = CLContext() + model = ModelState(cl_context) cloudlog.warning("models loaded, dmonitoringmodeld starting") Params().put_bool("DmModelInitialized", True) cloudlog.warning("connecting to driver stream") - vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_DRIVER, True) + vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_DRIVER, True, cl_context) while not vipc_client.connect(False): time.sleep(0.1) assert vipc_client.is_connected() @@ -144,10 +151,10 @@ def main(): calib[:] = np.array(sm["liveCalibration"].rpyCalib) t1 = time.perf_counter() - model_output, dsp_execution_time = model.run(buf, calib) + model_output, gpu_execution_time = model.run(buf, calib) t2 = time.perf_counter() - pm.send("driverStateV2", get_driverstate_packet(model_output, vipc_client.frame_id, vipc_client.timestamp_sof, t2 - t1, dsp_execution_time)) + pm.send("driverStateV2", get_driverstate_packet(model_output, vipc_client.frame_id, vipc_client.timestamp_sof, t2 - t1, gpu_execution_time)) # print("dmonitoring process: %.2fms, from last %.2fms\n" % (t2 - t1, t1 - last)) # last = t1 diff --git a/selfdrive/modeld/models/dmonitoring_model.current b/selfdrive/modeld/models/dmonitoring_model.current index f935ab06b3..121871ef2b 100644 --- a/selfdrive/modeld/models/dmonitoring_model.current +++ b/selfdrive/modeld/models/dmonitoring_model.current @@ -1,2 +1,2 @@ -5ec97a39-0095-4cea-adfa-6d72b1966cc1 -26cac7a9757a27c783a365403040a1bd27ccdaea \ No newline at end of file +fa69be01-b430-4504-9d72-7dcb058eb6dd +d9fb22d1c4fa3ca3d201dbc8edf1d0f0918e53e6 diff --git a/selfdrive/modeld/models/dmonitoring_model.onnx b/selfdrive/modeld/models/dmonitoring_model.onnx index dd3a6aba2e..dcc727510e 100644 --- a/selfdrive/modeld/models/dmonitoring_model.onnx +++ b/selfdrive/modeld/models/dmonitoring_model.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3dd3982940d823c4fbb0429b733a0b78b0688d7d67aa76ff7b754a3e2f3d8683 -size 16132780 +oid sha256:50efe6451a3fb3fa04b6bb0e846544533329bd46ecefe9e657e91214dee2aaeb +size 7196502 diff --git a/selfdrive/modeld/models/dmonitoring_model_q.dlc b/selfdrive/modeld/models/dmonitoring_model_q.dlc deleted file mode 100644 index fc285954d4..0000000000 --- a/selfdrive/modeld/models/dmonitoring_model_q.dlc +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:7c26f13816b143f5bb29ac2980f8557bd5687a75729e4d895313fb9a5a1f0f46 -size 4488449 diff --git a/selfdrive/modeld/runners/onnxmodel.py b/selfdrive/modeld/runners/onnxmodel.py index a570e34305..2b17422740 100644 --- a/selfdrive/modeld/runners/onnxmodel.py +++ b/selfdrive/modeld/runners/onnxmodel.py @@ -67,7 +67,6 @@ class ONNXModel(RunModel): def __init__(self, path, output, runtime, use_tf8, cl_context): self.inputs = {} self.output = output - self.use_tf8 = use_tf8 self.session = create_ort_session(path, fp16_to_fp32=True) self.input_names = [x.name for x in self.session.get_inputs()] @@ -91,7 +90,7 @@ class ONNXModel(RunModel): return None def execute(self): - inputs = {k: (v.view(np.uint8) / 255. if self.use_tf8 and k == 'input_img' else v) for k,v in self.inputs.items()} + inputs = {k: v.view(self.input_dtypes[k]) for k,v in self.inputs.items()} inputs = {k: v.reshape(self.input_shapes[k]).astype(self.input_dtypes[k]) for k,v in inputs.items()} outputs = self.session.run(None, inputs) assert len(outputs) == 1, "Only single model outputs are supported" diff --git a/selfdrive/monitoring/helpers.py b/selfdrive/monitoring/helpers.py index 54c81daeab..72df724532 100644 --- a/selfdrive/monitoring/helpers.py +++ b/selfdrive/monitoring/helpers.py @@ -33,8 +33,8 @@ class DRIVER_MONITOR_SETTINGS: self._SG_THRESHOLD = 0.9 self._BLINK_THRESHOLD = 0.865 - self._EE_THRESH11 = 0.25 - self._EE_THRESH12 = 7.5 + self._EE_THRESH11 = 0.4 + self._EE_THRESH12 = 15.0 self._EE_MAX_OFFSET1 = 0.06 self._EE_MIN_OFFSET1 = 0.025 self._EE_THRESH21 = 0.01 diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index 269cf464a3..ead3a3b4b5 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -109,7 +109,7 @@ if __name__ == "__main__": 'modelV2.frameDropPerc', 'modelV2.modelExecutionTime', 'driverStateV2.modelExecutionTime', - 'driverStateV2.dspExecutionTime' + 'driverStateV2.gpuExecutionTime' ] if PC: # TODO We ignore whole bunch so we can compare important stuff diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 7d588b26fa..3e4f435964 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -666448fce191e196aac68d06e29a0745e6620db9 +7cd64f431b814adfa11118643efe3822c496922b diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 59f6c6cc53..af33b0458b 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -585,7 +585,7 @@ CONFIGS = [ proc_name="dmonitoringmodeld", pubs=["liveCalibration", "driverCameraState"], subs=["driverStateV2"], - ignore=["logMonoTime", "driverStateV2.modelExecutionTime", "driverStateV2.dspExecutionTime"], + ignore=["logMonoTime", "driverStateV2.modelExecutionTime", "driverStateV2.gpuExecutionTime"], should_recv_callback=dmonitoringmodeld_rcv_callback, tolerance=NUMPY_TOLERANCE, processing_time=0.020, diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 5bc6bff1c2..964848e3d3 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -32,6 +32,7 @@ CPU usage budget * total CPU usage of openpilot (sum(PROCS.values()) should not exceed MAX_TOTAL_CPU """ + MAX_TOTAL_CPU = 265. # total for all 8 cores PROCS = { # Baseline CPU usage by process @@ -312,7 +313,7 @@ class TestOnroad: assert max(mems) - min(mems) <= 3.0 def test_gpu_usage(self): - assert self.gpu_procs == {"weston", "ui", "camerad", "selfdrive.modeld.modeld"} + assert self.gpu_procs == {"weston", "ui", "camerad", "selfdrive.modeld.modeld", "selfdrive.modeld.dmonitoringmodeld"} def test_camera_processing_time(self): result = "\n" diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index eb3a515b76..3b9d65b85a 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -34,7 +34,7 @@ class Proc: PROCS = [ Proc(['camerad'], 2.1, msgs=['roadCameraState', 'wideRoadCameraState', 'driverCameraState']), Proc(['modeld'], 1.12, atol=0.2, msgs=['modelV2']), - Proc(['dmonitoringmodeld'], 0.4, msgs=['driverStateV2']), + Proc(['dmonitoringmodeld'], 0.5, msgs=['driverStateV2']), Proc(['encoderd'], 0.23, msgs=[]), ] diff --git a/system/manager/process_config.py b/system/manager/process_config.py index bdb549fa41..eca5184c92 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -70,7 +70,7 @@ procs = [ PythonProcess("micd", "system.micd", iscar), PythonProcess("timed", "system.timed", always_run, enabled=not PC), - PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(not PC or WEBCAM)), + NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], driverview, enabled=(not PC or WEBCAM)), NativeProcess("encoderd", "system/loggerd", ["./encoderd"], only_onroad), NativeProcess("stream_encoderd", "system/loggerd", ["./encoderd", "--stream"], notcar), NativeProcess("loggerd", "system/loggerd", ["./loggerd"], logging), diff --git a/tinygrad_repo b/tinygrad_repo index f51aa0fc7c..3e15fa0dae 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit f51aa0fc7cdbac710e640172db280cfb747d2718 +Subproject commit 3e15fa0daefae75e2ddef98f82be5b5d37820631 From 1d5b2079742e43c77fe81c6535e5e3fa7a74cb3e Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Thu, 26 Sep 2024 17:32:06 -0700 Subject: [PATCH 147/214] Revert "camerad: Replace ox LUT with function" (#33658) Revert "camerad: Replace ox LUT with function (#33653)" This reverts commit 4851dacd063a742983446224b7ea84bced7a4943. --- system/camerad/sensors/ox03c10_cl.h | 43 ++++++++++++++--------------- 1 file changed, 20 insertions(+), 23 deletions(-) diff --git a/system/camerad/sensors/ox03c10_cl.h b/system/camerad/sensors/ox03c10_cl.h index b8d331f50d..21441902fc 100644 --- a/system/camerad/sensors/ox03c10_cl.h +++ b/system/camerad/sensors/ox03c10_cl.h @@ -4,31 +4,28 @@ #define BLACK_LVL 64 #define VIGNETTE_RSZ 1.0f -float ox_lut_func(int x) { - if (x < 512) { - return x * 5.94873e-8; - } else if (512 <= x < 768) { - return 3.0458e-05 + (x-512) * 1.19913e-7; - } else if (768 <= x < 1536) { - return 6.1154e-05 + (x-768) * 2.38493e-7; - } else if (1536 <= x < 1792) { - return 0.0002448 + (x-1536) * 9.56930e-7; - } else if (1792 <= x < 2048) { - return 0.00048977 + (x-1792) * 1.91441e-6; - } else if (2048 <= x < 2304) { - return 0.00097984 + (x-2048) * 3.82937e-6; - } else if (2304 <= x < 2560) { - return 0.0019601 + (x-2304) * 7.659055e-6; - } else if (2560 <= x < 2816) { - return 0.0039207 + (x-2560) * 1.525e-5; - } else { - return 0.0078421 + (exp((x-2816)/273.0) - 1) * 0.0092421; - } -} +constant float ox03c10_lut[] = { + 0.0000e+00, 5.9488e-08, 1.1898e-07, 1.7846e-07, 2.3795e-07, 2.9744e-07, 3.5693e-07, 4.1642e-07, 4.7591e-07, 5.3539e-07, 5.9488e-07, 6.5437e-07, 7.1386e-07, 7.7335e-07, 8.3284e-07, 8.9232e-07, 9.5181e-07, 1.0113e-06, 1.0708e-06, 1.1303e-06, 1.1898e-06, 1.2493e-06, 1.3087e-06, 1.3682e-06, 1.4277e-06, 1.4872e-06, 1.5467e-06, 1.6062e-06, 1.6657e-06, 1.7252e-06, 1.7846e-06, 1.8441e-06, 1.9036e-06, 1.9631e-06, 2.0226e-06, 2.0821e-06, 2.1416e-06, 2.2011e-06, 2.2606e-06, 2.3200e-06, 2.3795e-06, 2.4390e-06, 2.4985e-06, 2.5580e-06, 2.6175e-06, 2.6770e-06, 2.7365e-06, 2.7959e-06, 2.8554e-06, 2.9149e-06, 2.9744e-06, 3.0339e-06, 3.0934e-06, 3.1529e-06, 3.2124e-06, 3.2719e-06, 3.3313e-06, 3.3908e-06, 3.4503e-06, 3.5098e-06, 3.5693e-06, 3.6288e-06, 3.6883e-06, 3.7478e-06, 3.8072e-06, 3.8667e-06, 3.9262e-06, 3.9857e-06, 4.0452e-06, 4.1047e-06, 4.1642e-06, 4.2237e-06, 4.2832e-06, 4.3426e-06, 4.4021e-06, 4.4616e-06, 4.5211e-06, 4.5806e-06, 4.6401e-06, 4.6996e-06, 4.7591e-06, 4.8185e-06, 4.8780e-06, 4.9375e-06, 4.9970e-06, 5.0565e-06, 5.1160e-06, 5.1755e-06, 5.2350e-06, 5.2945e-06, 5.3539e-06, 5.4134e-06, 5.4729e-06, 5.5324e-06, 5.5919e-06, 5.6514e-06, 5.7109e-06, 5.7704e-06, 5.8298e-06, 5.8893e-06, 5.9488e-06, 6.0083e-06, 6.0678e-06, 6.1273e-06, 6.1868e-06, 6.2463e-06, 6.3058e-06, 6.3652e-06, 6.4247e-06, 6.4842e-06, 6.5437e-06, 6.6032e-06, 6.6627e-06, 6.7222e-06, 6.7817e-06, 6.8411e-06, 6.9006e-06, 6.9601e-06, 7.0196e-06, 7.0791e-06, 7.1386e-06, 7.1981e-06, 7.2576e-06, 7.3171e-06, 7.3765e-06, 7.4360e-06, 7.4955e-06, 7.5550e-06, 7.6145e-06, 7.6740e-06, 7.7335e-06, 7.7930e-06, 7.8524e-06, 7.9119e-06, 7.9714e-06, 8.0309e-06, 8.0904e-06, 8.1499e-06, 8.2094e-06, 8.2689e-06, 8.3284e-06, 8.3878e-06, 8.4473e-06, 8.5068e-06, 8.5663e-06, 8.6258e-06, 8.6853e-06, 8.7448e-06, 8.8043e-06, 8.8637e-06, 8.9232e-06, 8.9827e-06, 9.0422e-06, 9.1017e-06, 9.1612e-06, 9.2207e-06, 9.2802e-06, 9.3397e-06, 9.3991e-06, 9.4586e-06, 9.5181e-06, 9.5776e-06, 9.6371e-06, 9.6966e-06, 9.7561e-06, 9.8156e-06, 9.8750e-06, 9.9345e-06, 9.9940e-06, 1.0054e-05, 1.0113e-05, 1.0172e-05, 1.0232e-05, 1.0291e-05, 1.0351e-05, 1.0410e-05, 1.0470e-05, 1.0529e-05, 1.0589e-05, 1.0648e-05, 1.0708e-05, 1.0767e-05, 1.0827e-05, 1.0886e-05, 1.0946e-05, 1.1005e-05, 1.1065e-05, 1.1124e-05, 1.1184e-05, 1.1243e-05, 1.1303e-05, 1.1362e-05, 1.1422e-05, 1.1481e-05, 1.1541e-05, 1.1600e-05, 1.1660e-05, 1.1719e-05, 1.1779e-05, 1.1838e-05, 1.1898e-05, 1.1957e-05, 1.2017e-05, 1.2076e-05, 1.2136e-05, 1.2195e-05, 1.2255e-05, 1.2314e-05, 1.2374e-05, 1.2433e-05, 1.2493e-05, 1.2552e-05, 1.2612e-05, 1.2671e-05, 1.2730e-05, 1.2790e-05, 1.2849e-05, 1.2909e-05, 1.2968e-05, 1.3028e-05, 1.3087e-05, 1.3147e-05, 1.3206e-05, 1.3266e-05, 1.3325e-05, 1.3385e-05, 1.3444e-05, 1.3504e-05, 1.3563e-05, 1.3623e-05, 1.3682e-05, 1.3742e-05, 1.3801e-05, 1.3861e-05, 1.3920e-05, 1.3980e-05, 1.4039e-05, 1.4099e-05, 1.4158e-05, 1.4218e-05, 1.4277e-05, 1.4337e-05, 1.4396e-05, 1.4456e-05, 1.4515e-05, 1.4575e-05, 1.4634e-05, 1.4694e-05, 1.4753e-05, 1.4813e-05, 1.4872e-05, 1.4932e-05, 1.4991e-05, 1.5051e-05, 1.5110e-05, 1.5169e-05, // NOLINT + 1.5229e-05, 1.5288e-05, 1.5348e-05, 1.5407e-05, 1.5467e-05, 1.5526e-05, 1.5586e-05, 1.5645e-05, 1.5705e-05, 1.5764e-05, 1.5824e-05, 1.5883e-05, 1.5943e-05, 1.6002e-05, 1.6062e-05, 1.6121e-05, 1.6181e-05, 1.6240e-05, 1.6300e-05, 1.6359e-05, 1.6419e-05, 1.6478e-05, 1.6538e-05, 1.6597e-05, 1.6657e-05, 1.6716e-05, 1.6776e-05, 1.6835e-05, 1.6895e-05, 1.6954e-05, 1.7014e-05, 1.7073e-05, 1.7133e-05, 1.7192e-05, 1.7252e-05, 1.7311e-05, 1.7371e-05, 1.7430e-05, 1.7490e-05, 1.7549e-05, 1.7609e-05, 1.7668e-05, 1.7727e-05, 1.7787e-05, 1.7846e-05, 1.7906e-05, 1.7965e-05, 1.8025e-05, 1.8084e-05, 1.8144e-05, 1.8203e-05, 1.8263e-05, 1.8322e-05, 1.8382e-05, 1.8441e-05, 1.8501e-05, 1.8560e-05, 1.8620e-05, 1.8679e-05, 1.8739e-05, 1.8798e-05, 1.8858e-05, 1.8917e-05, 1.8977e-05, 1.9036e-05, 1.9096e-05, 1.9155e-05, 1.9215e-05, 1.9274e-05, 1.9334e-05, 1.9393e-05, 1.9453e-05, 1.9512e-05, 1.9572e-05, 1.9631e-05, 1.9691e-05, 1.9750e-05, 1.9810e-05, 1.9869e-05, 1.9929e-05, 1.9988e-05, 2.0048e-05, 2.0107e-05, 2.0167e-05, 2.0226e-05, 2.0285e-05, 2.0345e-05, 2.0404e-05, 2.0464e-05, 2.0523e-05, 2.0583e-05, 2.0642e-05, 2.0702e-05, 2.0761e-05, 2.0821e-05, 2.0880e-05, 2.0940e-05, 2.0999e-05, 2.1059e-05, 2.1118e-05, 2.1178e-05, 2.1237e-05, 2.1297e-05, 2.1356e-05, 2.1416e-05, 2.1475e-05, 2.1535e-05, 2.1594e-05, 2.1654e-05, 2.1713e-05, 2.1773e-05, 2.1832e-05, 2.1892e-05, 2.1951e-05, 2.2011e-05, 2.2070e-05, 2.2130e-05, 2.2189e-05, 2.2249e-05, 2.2308e-05, 2.2368e-05, 2.2427e-05, 2.2487e-05, 2.2546e-05, 2.2606e-05, 2.2665e-05, 2.2725e-05, 2.2784e-05, 2.2843e-05, 2.2903e-05, 2.2962e-05, 2.3022e-05, 2.3081e-05, 2.3141e-05, 2.3200e-05, 2.3260e-05, 2.3319e-05, 2.3379e-05, 2.3438e-05, 2.3498e-05, 2.3557e-05, 2.3617e-05, 2.3676e-05, 2.3736e-05, 2.3795e-05, 2.3855e-05, 2.3914e-05, 2.3974e-05, 2.4033e-05, 2.4093e-05, 2.4152e-05, 2.4212e-05, 2.4271e-05, 2.4331e-05, 2.4390e-05, 2.4450e-05, 2.4509e-05, 2.4569e-05, 2.4628e-05, 2.4688e-05, 2.4747e-05, 2.4807e-05, 2.4866e-05, 2.4926e-05, 2.4985e-05, 2.5045e-05, 2.5104e-05, 2.5164e-05, 2.5223e-05, 2.5282e-05, 2.5342e-05, 2.5401e-05, 2.5461e-05, 2.5520e-05, 2.5580e-05, 2.5639e-05, 2.5699e-05, 2.5758e-05, 2.5818e-05, 2.5877e-05, 2.5937e-05, 2.5996e-05, 2.6056e-05, 2.6115e-05, 2.6175e-05, 2.6234e-05, 2.6294e-05, 2.6353e-05, 2.6413e-05, 2.6472e-05, 2.6532e-05, 2.6591e-05, 2.6651e-05, 2.6710e-05, 2.6770e-05, 2.6829e-05, 2.6889e-05, 2.6948e-05, 2.7008e-05, 2.7067e-05, 2.7127e-05, 2.7186e-05, 2.7246e-05, 2.7305e-05, 2.7365e-05, 2.7424e-05, 2.7484e-05, 2.7543e-05, 2.7603e-05, 2.7662e-05, 2.7722e-05, 2.7781e-05, 2.7840e-05, 2.7900e-05, 2.7959e-05, 2.8019e-05, 2.8078e-05, 2.8138e-05, 2.8197e-05, 2.8257e-05, 2.8316e-05, 2.8376e-05, 2.8435e-05, 2.8495e-05, 2.8554e-05, 2.8614e-05, 2.8673e-05, 2.8733e-05, 2.8792e-05, 2.8852e-05, 2.8911e-05, 2.8971e-05, 2.9030e-05, 2.9090e-05, 2.9149e-05, 2.9209e-05, 2.9268e-05, 2.9328e-05, 2.9387e-05, 2.9447e-05, 2.9506e-05, 2.9566e-05, 2.9625e-05, 2.9685e-05, 2.9744e-05, 2.9804e-05, 2.9863e-05, 2.9923e-05, 2.9982e-05, 3.0042e-05, 3.0101e-05, 3.0161e-05, 3.0220e-05, 3.0280e-05, 3.0339e-05, 3.0398e-05, // NOLINT + 3.0458e-05, 3.0577e-05, 3.0697e-05, 3.0816e-05, 3.0936e-05, 3.1055e-05, 3.1175e-05, 3.1294e-05, 3.1414e-05, 3.1533e-05, 3.1652e-05, 3.1772e-05, 3.1891e-05, 3.2011e-05, 3.2130e-05, 3.2250e-05, 3.2369e-05, 3.2489e-05, 3.2608e-05, 3.2727e-05, 3.2847e-05, 3.2966e-05, 3.3086e-05, 3.3205e-05, 3.3325e-05, 3.3444e-05, 3.3563e-05, 3.3683e-05, 3.3802e-05, 3.3922e-05, 3.4041e-05, 3.4161e-05, 3.4280e-05, 3.4400e-05, 3.4519e-05, 3.4638e-05, 3.4758e-05, 3.4877e-05, 3.4997e-05, 3.5116e-05, 3.5236e-05, 3.5355e-05, 3.5475e-05, 3.5594e-05, 3.5713e-05, 3.5833e-05, 3.5952e-05, 3.6072e-05, 3.6191e-05, 3.6311e-05, 3.6430e-05, 3.6550e-05, 3.6669e-05, 3.6788e-05, 3.6908e-05, 3.7027e-05, 3.7147e-05, 3.7266e-05, 3.7386e-05, 3.7505e-05, 3.7625e-05, 3.7744e-05, 3.7863e-05, 3.7983e-05, 3.8102e-05, 3.8222e-05, 3.8341e-05, 3.8461e-05, 3.8580e-05, 3.8700e-05, 3.8819e-05, 3.8938e-05, 3.9058e-05, 3.9177e-05, 3.9297e-05, 3.9416e-05, 3.9536e-05, 3.9655e-05, 3.9775e-05, 3.9894e-05, 4.0013e-05, 4.0133e-05, 4.0252e-05, 4.0372e-05, 4.0491e-05, 4.0611e-05, 4.0730e-05, 4.0850e-05, 4.0969e-05, 4.1088e-05, 4.1208e-05, 4.1327e-05, 4.1447e-05, 4.1566e-05, 4.1686e-05, 4.1805e-05, 4.1925e-05, 4.2044e-05, 4.2163e-05, 4.2283e-05, 4.2402e-05, 4.2522e-05, 4.2641e-05, 4.2761e-05, 4.2880e-05, 4.2999e-05, 4.3119e-05, 4.3238e-05, 4.3358e-05, 4.3477e-05, 4.3597e-05, 4.3716e-05, 4.3836e-05, 4.3955e-05, 4.4074e-05, 4.4194e-05, 4.4313e-05, 4.4433e-05, 4.4552e-05, 4.4672e-05, 4.4791e-05, 4.4911e-05, 4.5030e-05, 4.5149e-05, 4.5269e-05, 4.5388e-05, 4.5508e-05, 4.5627e-05, 4.5747e-05, 4.5866e-05, 4.5986e-05, 4.6105e-05, 4.6224e-05, 4.6344e-05, 4.6463e-05, 4.6583e-05, 4.6702e-05, 4.6822e-05, 4.6941e-05, 4.7061e-05, 4.7180e-05, 4.7299e-05, 4.7419e-05, 4.7538e-05, 4.7658e-05, 4.7777e-05, 4.7897e-05, 4.8016e-05, 4.8136e-05, 4.8255e-05, 4.8374e-05, 4.8494e-05, 4.8613e-05, 4.8733e-05, 4.8852e-05, 4.8972e-05, 4.9091e-05, 4.9211e-05, 4.9330e-05, 4.9449e-05, 4.9569e-05, 4.9688e-05, 4.9808e-05, 4.9927e-05, 5.0047e-05, 5.0166e-05, 5.0286e-05, 5.0405e-05, 5.0524e-05, 5.0644e-05, 5.0763e-05, 5.0883e-05, 5.1002e-05, 5.1122e-05, 5.1241e-05, 5.1361e-05, 5.1480e-05, 5.1599e-05, 5.1719e-05, 5.1838e-05, 5.1958e-05, 5.2077e-05, 5.2197e-05, 5.2316e-05, 5.2435e-05, 5.2555e-05, 5.2674e-05, 5.2794e-05, 5.2913e-05, 5.3033e-05, 5.3152e-05, 5.3272e-05, 5.3391e-05, 5.3510e-05, 5.3630e-05, 5.3749e-05, 5.3869e-05, 5.3988e-05, 5.4108e-05, 5.4227e-05, 5.4347e-05, 5.4466e-05, 5.4585e-05, 5.4705e-05, 5.4824e-05, 5.4944e-05, 5.5063e-05, 5.5183e-05, 5.5302e-05, 5.5422e-05, 5.5541e-05, 5.5660e-05, 5.5780e-05, 5.5899e-05, 5.6019e-05, 5.6138e-05, 5.6258e-05, 5.6377e-05, 5.6497e-05, 5.6616e-05, 5.6735e-05, 5.6855e-05, 5.6974e-05, 5.7094e-05, 5.7213e-05, 5.7333e-05, 5.7452e-05, 5.7572e-05, 5.7691e-05, 5.7810e-05, 5.7930e-05, 5.8049e-05, 5.8169e-05, 5.8288e-05, 5.8408e-05, 5.8527e-05, 5.8647e-05, 5.8766e-05, 5.8885e-05, 5.9005e-05, 5.9124e-05, 5.9244e-05, 5.9363e-05, 5.9483e-05, 5.9602e-05, 5.9722e-05, 5.9841e-05, 5.9960e-05, 6.0080e-05, 6.0199e-05, 6.0319e-05, 6.0438e-05, 6.0558e-05, 6.0677e-05, 6.0797e-05, 6.0916e-05, // NOLINT + 6.1154e-05, 6.1392e-05, 6.1631e-05, 6.1869e-05, 6.2107e-05, 6.2345e-05, 6.2583e-05, 6.2821e-05, 6.3060e-05, 6.3298e-05, 6.3536e-05, 6.3774e-05, 6.4012e-05, 6.4251e-05, 6.4489e-05, 6.4727e-05, 6.4965e-05, 6.5203e-05, 6.5441e-05, 6.5680e-05, 6.5918e-05, 6.6156e-05, 6.6394e-05, 6.6632e-05, 6.6871e-05, 6.7109e-05, 6.7347e-05, 6.7585e-05, 6.7823e-05, 6.8062e-05, 6.8300e-05, 6.8538e-05, 6.8776e-05, 6.9014e-05, 6.9252e-05, 6.9491e-05, 6.9729e-05, 6.9967e-05, 7.0205e-05, 7.0443e-05, 7.0682e-05, 7.0920e-05, 7.1158e-05, 7.1396e-05, 7.1634e-05, 7.1872e-05, 7.2111e-05, 7.2349e-05, 7.2587e-05, 7.2825e-05, 7.3063e-05, 7.3302e-05, 7.3540e-05, 7.3778e-05, 7.4016e-05, 7.4254e-05, 7.4493e-05, 7.4731e-05, 7.4969e-05, 7.5207e-05, 7.5445e-05, 7.5683e-05, 7.5922e-05, 7.6160e-05, 7.6398e-05, 7.6636e-05, 7.6874e-05, 7.7113e-05, 7.7351e-05, 7.7589e-05, 7.7827e-05, 7.8065e-05, 7.8304e-05, 7.8542e-05, 7.8780e-05, 7.9018e-05, 7.9256e-05, 7.9494e-05, 7.9733e-05, 7.9971e-05, 8.0209e-05, 8.0447e-05, 8.0685e-05, 8.0924e-05, 8.1162e-05, 8.1400e-05, 8.1638e-05, 8.1876e-05, 8.2114e-05, 8.2353e-05, 8.2591e-05, 8.2829e-05, 8.3067e-05, 8.3305e-05, 8.3544e-05, 8.3782e-05, 8.4020e-05, 8.4258e-05, 8.4496e-05, 8.4735e-05, 8.4973e-05, 8.5211e-05, 8.5449e-05, 8.5687e-05, 8.5925e-05, 8.6164e-05, 8.6402e-05, 8.6640e-05, 8.6878e-05, 8.7116e-05, 8.7355e-05, 8.7593e-05, 8.7831e-05, 8.8069e-05, 8.8307e-05, 8.8545e-05, 8.8784e-05, 8.9022e-05, 8.9260e-05, 8.9498e-05, 8.9736e-05, 8.9975e-05, 9.0213e-05, 9.0451e-05, 9.0689e-05, 9.0927e-05, 9.1166e-05, 9.1404e-05, 9.1642e-05, 9.1880e-05, 9.2118e-05, 9.2356e-05, 9.2595e-05, 9.2833e-05, 9.3071e-05, 9.3309e-05, 9.3547e-05, 9.3786e-05, 9.4024e-05, 9.4262e-05, 9.4500e-05, 9.4738e-05, 9.4977e-05, 9.5215e-05, 9.5453e-05, 9.5691e-05, 9.5929e-05, 9.6167e-05, 9.6406e-05, 9.6644e-05, 9.6882e-05, 9.7120e-05, 9.7358e-05, 9.7597e-05, 9.7835e-05, 9.8073e-05, 9.8311e-05, 9.8549e-05, 9.8787e-05, 9.9026e-05, 9.9264e-05, 9.9502e-05, 9.9740e-05, 9.9978e-05, 1.0022e-04, 1.0045e-04, 1.0069e-04, 1.0093e-04, 1.0117e-04, 1.0141e-04, 1.0165e-04, 1.0188e-04, 1.0212e-04, 1.0236e-04, 1.0260e-04, 1.0284e-04, 1.0307e-04, 1.0331e-04, 1.0355e-04, 1.0379e-04, 1.0403e-04, 1.0427e-04, 1.0450e-04, 1.0474e-04, 1.0498e-04, 1.0522e-04, 1.0546e-04, 1.0569e-04, 1.0593e-04, 1.0617e-04, 1.0641e-04, 1.0665e-04, 1.0689e-04, 1.0712e-04, 1.0736e-04, 1.0760e-04, 1.0784e-04, 1.0808e-04, 1.0831e-04, 1.0855e-04, 1.0879e-04, 1.0903e-04, 1.0927e-04, 1.0951e-04, 1.0974e-04, 1.0998e-04, 1.1022e-04, 1.1046e-04, 1.1070e-04, 1.1093e-04, 1.1117e-04, 1.1141e-04, 1.1165e-04, 1.1189e-04, 1.1213e-04, 1.1236e-04, 1.1260e-04, 1.1284e-04, 1.1308e-04, 1.1332e-04, 1.1355e-04, 1.1379e-04, 1.1403e-04, 1.1427e-04, 1.1451e-04, 1.1475e-04, 1.1498e-04, 1.1522e-04, 1.1546e-04, 1.1570e-04, 1.1594e-04, 1.1618e-04, 1.1641e-04, 1.1665e-04, 1.1689e-04, 1.1713e-04, 1.1737e-04, 1.1760e-04, 1.1784e-04, 1.1808e-04, 1.1832e-04, 1.1856e-04, 1.1880e-04, 1.1903e-04, 1.1927e-04, 1.1951e-04, 1.1975e-04, 1.1999e-04, 1.2022e-04, 1.2046e-04, 1.2070e-04, 1.2094e-04, 1.2118e-04, 1.2142e-04, 1.2165e-04, 1.2189e-04, // NOLINT + 1.2213e-04, 1.2237e-04, 1.2261e-04, 1.2284e-04, 1.2308e-04, 1.2332e-04, 1.2356e-04, 1.2380e-04, 1.2404e-04, 1.2427e-04, 1.2451e-04, 1.2475e-04, 1.2499e-04, 1.2523e-04, 1.2546e-04, 1.2570e-04, 1.2594e-04, 1.2618e-04, 1.2642e-04, 1.2666e-04, 1.2689e-04, 1.2713e-04, 1.2737e-04, 1.2761e-04, 1.2785e-04, 1.2808e-04, 1.2832e-04, 1.2856e-04, 1.2880e-04, 1.2904e-04, 1.2928e-04, 1.2951e-04, 1.2975e-04, 1.2999e-04, 1.3023e-04, 1.3047e-04, 1.3070e-04, 1.3094e-04, 1.3118e-04, 1.3142e-04, 1.3166e-04, 1.3190e-04, 1.3213e-04, 1.3237e-04, 1.3261e-04, 1.3285e-04, 1.3309e-04, 1.3332e-04, 1.3356e-04, 1.3380e-04, 1.3404e-04, 1.3428e-04, 1.3452e-04, 1.3475e-04, 1.3499e-04, 1.3523e-04, 1.3547e-04, 1.3571e-04, 1.3594e-04, 1.3618e-04, 1.3642e-04, 1.3666e-04, 1.3690e-04, 1.3714e-04, 1.3737e-04, 1.3761e-04, 1.3785e-04, 1.3809e-04, 1.3833e-04, 1.3856e-04, 1.3880e-04, 1.3904e-04, 1.3928e-04, 1.3952e-04, 1.3976e-04, 1.3999e-04, 1.4023e-04, 1.4047e-04, 1.4071e-04, 1.4095e-04, 1.4118e-04, 1.4142e-04, 1.4166e-04, 1.4190e-04, 1.4214e-04, 1.4238e-04, 1.4261e-04, 1.4285e-04, 1.4309e-04, 1.4333e-04, 1.4357e-04, 1.4380e-04, 1.4404e-04, 1.4428e-04, 1.4452e-04, 1.4476e-04, 1.4500e-04, 1.4523e-04, 1.4547e-04, 1.4571e-04, 1.4595e-04, 1.4619e-04, 1.4642e-04, 1.4666e-04, 1.4690e-04, 1.4714e-04, 1.4738e-04, 1.4762e-04, 1.4785e-04, 1.4809e-04, 1.4833e-04, 1.4857e-04, 1.4881e-04, 1.4904e-04, 1.4928e-04, 1.4952e-04, 1.4976e-04, 1.5000e-04, 1.5024e-04, 1.5047e-04, 1.5071e-04, 1.5095e-04, 1.5119e-04, 1.5143e-04, 1.5166e-04, 1.5190e-04, 1.5214e-04, 1.5238e-04, 1.5262e-04, 1.5286e-04, 1.5309e-04, 1.5333e-04, 1.5357e-04, 1.5381e-04, 1.5405e-04, 1.5428e-04, 1.5452e-04, 1.5476e-04, 1.5500e-04, 1.5524e-04, 1.5548e-04, 1.5571e-04, 1.5595e-04, 1.5619e-04, 1.5643e-04, 1.5667e-04, 1.5690e-04, 1.5714e-04, 1.5738e-04, 1.5762e-04, 1.5786e-04, 1.5810e-04, 1.5833e-04, 1.5857e-04, 1.5881e-04, 1.5905e-04, 1.5929e-04, 1.5952e-04, 1.5976e-04, 1.6000e-04, 1.6024e-04, 1.6048e-04, 1.6072e-04, 1.6095e-04, 1.6119e-04, 1.6143e-04, 1.6167e-04, 1.6191e-04, 1.6214e-04, 1.6238e-04, 1.6262e-04, 1.6286e-04, 1.6310e-04, 1.6334e-04, 1.6357e-04, 1.6381e-04, 1.6405e-04, 1.6429e-04, 1.6453e-04, 1.6476e-04, 1.6500e-04, 1.6524e-04, 1.6548e-04, 1.6572e-04, 1.6596e-04, 1.6619e-04, 1.6643e-04, 1.6667e-04, 1.6691e-04, 1.6715e-04, 1.6738e-04, 1.6762e-04, 1.6786e-04, 1.6810e-04, 1.6834e-04, 1.6858e-04, 1.6881e-04, 1.6905e-04, 1.6929e-04, 1.6953e-04, 1.6977e-04, 1.7001e-04, 1.7024e-04, 1.7048e-04, 1.7072e-04, 1.7096e-04, 1.7120e-04, 1.7143e-04, 1.7167e-04, 1.7191e-04, 1.7215e-04, 1.7239e-04, 1.7263e-04, 1.7286e-04, 1.7310e-04, 1.7334e-04, 1.7358e-04, 1.7382e-04, 1.7405e-04, 1.7429e-04, 1.7453e-04, 1.7477e-04, 1.7501e-04, 1.7525e-04, 1.7548e-04, 1.7572e-04, 1.7596e-04, 1.7620e-04, 1.7644e-04, 1.7667e-04, 1.7691e-04, 1.7715e-04, 1.7739e-04, 1.7763e-04, 1.7787e-04, 1.7810e-04, 1.7834e-04, 1.7858e-04, 1.7882e-04, 1.7906e-04, 1.7929e-04, 1.7953e-04, 1.7977e-04, 1.8001e-04, 1.8025e-04, 1.8049e-04, 1.8072e-04, 1.8096e-04, 1.8120e-04, 1.8144e-04, 1.8168e-04, 1.8191e-04, 1.8215e-04, 1.8239e-04, 1.8263e-04, 1.8287e-04, // NOLINT + 1.8311e-04, 1.8334e-04, 1.8358e-04, 1.8382e-04, 1.8406e-04, 1.8430e-04, 1.8453e-04, 1.8477e-04, 1.8501e-04, 1.8525e-04, 1.8549e-04, 1.8573e-04, 1.8596e-04, 1.8620e-04, 1.8644e-04, 1.8668e-04, 1.8692e-04, 1.8715e-04, 1.8739e-04, 1.8763e-04, 1.8787e-04, 1.8811e-04, 1.8835e-04, 1.8858e-04, 1.8882e-04, 1.8906e-04, 1.8930e-04, 1.8954e-04, 1.8977e-04, 1.9001e-04, 1.9025e-04, 1.9049e-04, 1.9073e-04, 1.9097e-04, 1.9120e-04, 1.9144e-04, 1.9168e-04, 1.9192e-04, 1.9216e-04, 1.9239e-04, 1.9263e-04, 1.9287e-04, 1.9311e-04, 1.9335e-04, 1.9359e-04, 1.9382e-04, 1.9406e-04, 1.9430e-04, 1.9454e-04, 1.9478e-04, 1.9501e-04, 1.9525e-04, 1.9549e-04, 1.9573e-04, 1.9597e-04, 1.9621e-04, 1.9644e-04, 1.9668e-04, 1.9692e-04, 1.9716e-04, 1.9740e-04, 1.9763e-04, 1.9787e-04, 1.9811e-04, 1.9835e-04, 1.9859e-04, 1.9883e-04, 1.9906e-04, 1.9930e-04, 1.9954e-04, 1.9978e-04, 2.0002e-04, 2.0025e-04, 2.0049e-04, 2.0073e-04, 2.0097e-04, 2.0121e-04, 2.0145e-04, 2.0168e-04, 2.0192e-04, 2.0216e-04, 2.0240e-04, 2.0264e-04, 2.0287e-04, 2.0311e-04, 2.0335e-04, 2.0359e-04, 2.0383e-04, 2.0407e-04, 2.0430e-04, 2.0454e-04, 2.0478e-04, 2.0502e-04, 2.0526e-04, 2.0549e-04, 2.0573e-04, 2.0597e-04, 2.0621e-04, 2.0645e-04, 2.0669e-04, 2.0692e-04, 2.0716e-04, 2.0740e-04, 2.0764e-04, 2.0788e-04, 2.0811e-04, 2.0835e-04, 2.0859e-04, 2.0883e-04, 2.0907e-04, 2.0931e-04, 2.0954e-04, 2.0978e-04, 2.1002e-04, 2.1026e-04, 2.1050e-04, 2.1073e-04, 2.1097e-04, 2.1121e-04, 2.1145e-04, 2.1169e-04, 2.1193e-04, 2.1216e-04, 2.1240e-04, 2.1264e-04, 2.1288e-04, 2.1312e-04, 2.1335e-04, 2.1359e-04, 2.1383e-04, 2.1407e-04, 2.1431e-04, 2.1455e-04, 2.1478e-04, 2.1502e-04, 2.1526e-04, 2.1550e-04, 2.1574e-04, 2.1597e-04, 2.1621e-04, 2.1645e-04, 2.1669e-04, 2.1693e-04, 2.1717e-04, 2.1740e-04, 2.1764e-04, 2.1788e-04, 2.1812e-04, 2.1836e-04, 2.1859e-04, 2.1883e-04, 2.1907e-04, 2.1931e-04, 2.1955e-04, 2.1979e-04, 2.2002e-04, 2.2026e-04, 2.2050e-04, 2.2074e-04, 2.2098e-04, 2.2121e-04, 2.2145e-04, 2.2169e-04, 2.2193e-04, 2.2217e-04, 2.2241e-04, 2.2264e-04, 2.2288e-04, 2.2312e-04, 2.2336e-04, 2.2360e-04, 2.2383e-04, 2.2407e-04, 2.2431e-04, 2.2455e-04, 2.2479e-04, 2.2503e-04, 2.2526e-04, 2.2550e-04, 2.2574e-04, 2.2598e-04, 2.2622e-04, 2.2646e-04, 2.2669e-04, 2.2693e-04, 2.2717e-04, 2.2741e-04, 2.2765e-04, 2.2788e-04, 2.2812e-04, 2.2836e-04, 2.2860e-04, 2.2884e-04, 2.2908e-04, 2.2931e-04, 2.2955e-04, 2.2979e-04, 2.3003e-04, 2.3027e-04, 2.3050e-04, 2.3074e-04, 2.3098e-04, 2.3122e-04, 2.3146e-04, 2.3170e-04, 2.3193e-04, 2.3217e-04, 2.3241e-04, 2.3265e-04, 2.3289e-04, 2.3312e-04, 2.3336e-04, 2.3360e-04, 2.3384e-04, 2.3408e-04, 2.3432e-04, 2.3455e-04, 2.3479e-04, 2.3503e-04, 2.3527e-04, 2.3551e-04, 2.3574e-04, 2.3598e-04, 2.3622e-04, 2.3646e-04, 2.3670e-04, 2.3694e-04, 2.3717e-04, 2.3741e-04, 2.3765e-04, 2.3789e-04, 2.3813e-04, 2.3836e-04, 2.3860e-04, 2.3884e-04, 2.3908e-04, 2.3932e-04, 2.3956e-04, 2.3979e-04, 2.4003e-04, 2.4027e-04, 2.4051e-04, 2.4075e-04, 2.4098e-04, 2.4122e-04, 2.4146e-04, 2.4170e-04, 2.4194e-04, 2.4218e-04, 2.4241e-04, 2.4265e-04, 2.4289e-04, 2.4313e-04, 2.4337e-04, 2.4360e-04, 2.4384e-04, // NOLINT + 2.4480e-04, 2.4575e-04, 2.4670e-04, 2.4766e-04, 2.4861e-04, 2.4956e-04, 2.5052e-04, 2.5147e-04, 2.5242e-04, 2.5337e-04, 2.5433e-04, 2.5528e-04, 2.5623e-04, 2.5719e-04, 2.5814e-04, 2.5909e-04, 2.6005e-04, 2.6100e-04, 2.6195e-04, 2.6291e-04, 2.6386e-04, 2.6481e-04, 2.6577e-04, 2.6672e-04, 2.6767e-04, 2.6863e-04, 2.6958e-04, 2.7053e-04, 2.7149e-04, 2.7244e-04, 2.7339e-04, 2.7435e-04, 2.7530e-04, 2.7625e-04, 2.7720e-04, 2.7816e-04, 2.7911e-04, 2.8006e-04, 2.8102e-04, 2.8197e-04, 2.8292e-04, 2.8388e-04, 2.8483e-04, 2.8578e-04, 2.8674e-04, 2.8769e-04, 2.8864e-04, 2.8960e-04, 2.9055e-04, 2.9150e-04, 2.9246e-04, 2.9341e-04, 2.9436e-04, 2.9532e-04, 2.9627e-04, 2.9722e-04, 2.9818e-04, 2.9913e-04, 3.0008e-04, 3.0104e-04, 3.0199e-04, 3.0294e-04, 3.0389e-04, 3.0485e-04, 3.0580e-04, 3.0675e-04, 3.0771e-04, 3.0866e-04, 3.0961e-04, 3.1057e-04, 3.1152e-04, 3.1247e-04, 3.1343e-04, 3.1438e-04, 3.1533e-04, 3.1629e-04, 3.1724e-04, 3.1819e-04, 3.1915e-04, 3.2010e-04, 3.2105e-04, 3.2201e-04, 3.2296e-04, 3.2391e-04, 3.2487e-04, 3.2582e-04, 3.2677e-04, 3.2772e-04, 3.2868e-04, 3.2963e-04, 3.3058e-04, 3.3154e-04, 3.3249e-04, 3.3344e-04, 3.3440e-04, 3.3535e-04, 3.3630e-04, 3.3726e-04, 3.3821e-04, 3.3916e-04, 3.4012e-04, 3.4107e-04, 3.4202e-04, 3.4298e-04, 3.4393e-04, 3.4488e-04, 3.4584e-04, 3.4679e-04, 3.4774e-04, 3.4870e-04, 3.4965e-04, 3.5060e-04, 3.5156e-04, 3.5251e-04, 3.5346e-04, 3.5441e-04, 3.5537e-04, 3.5632e-04, 3.5727e-04, 3.5823e-04, 3.5918e-04, 3.6013e-04, 3.6109e-04, 3.6204e-04, 3.6299e-04, 3.6395e-04, 3.6490e-04, 3.6585e-04, 3.6681e-04, 3.6776e-04, 3.6871e-04, 3.6967e-04, 3.7062e-04, 3.7157e-04, 3.7253e-04, 3.7348e-04, 3.7443e-04, 3.7539e-04, 3.7634e-04, 3.7729e-04, 3.7825e-04, 3.7920e-04, 3.8015e-04, 3.8110e-04, 3.8206e-04, 3.8301e-04, 3.8396e-04, 3.8492e-04, 3.8587e-04, 3.8682e-04, 3.8778e-04, 3.8873e-04, 3.8968e-04, 3.9064e-04, 3.9159e-04, 3.9254e-04, 3.9350e-04, 3.9445e-04, 3.9540e-04, 3.9636e-04, 3.9731e-04, 3.9826e-04, 3.9922e-04, 4.0017e-04, 4.0112e-04, 4.0208e-04, 4.0303e-04, 4.0398e-04, 4.0493e-04, 4.0589e-04, 4.0684e-04, 4.0779e-04, 4.0875e-04, 4.0970e-04, 4.1065e-04, 4.1161e-04, 4.1256e-04, 4.1351e-04, 4.1447e-04, 4.1542e-04, 4.1637e-04, 4.1733e-04, 4.1828e-04, 4.1923e-04, 4.2019e-04, 4.2114e-04, 4.2209e-04, 4.2305e-04, 4.2400e-04, 4.2495e-04, 4.2591e-04, 4.2686e-04, 4.2781e-04, 4.2877e-04, 4.2972e-04, 4.3067e-04, 4.3162e-04, 4.3258e-04, 4.3353e-04, 4.3448e-04, 4.3544e-04, 4.3639e-04, 4.3734e-04, 4.3830e-04, 4.3925e-04, 4.4020e-04, 4.4116e-04, 4.4211e-04, 4.4306e-04, 4.4402e-04, 4.4497e-04, 4.4592e-04, 4.4688e-04, 4.4783e-04, 4.4878e-04, 4.4974e-04, 4.5069e-04, 4.5164e-04, 4.5260e-04, 4.5355e-04, 4.5450e-04, 4.5545e-04, 4.5641e-04, 4.5736e-04, 4.5831e-04, 4.5927e-04, 4.6022e-04, 4.6117e-04, 4.6213e-04, 4.6308e-04, 4.6403e-04, 4.6499e-04, 4.6594e-04, 4.6689e-04, 4.6785e-04, 4.6880e-04, 4.6975e-04, 4.7071e-04, 4.7166e-04, 4.7261e-04, 4.7357e-04, 4.7452e-04, 4.7547e-04, 4.7643e-04, 4.7738e-04, 4.7833e-04, 4.7929e-04, 4.8024e-04, 4.8119e-04, 4.8214e-04, 4.8310e-04, 4.8405e-04, 4.8500e-04, 4.8596e-04, 4.8691e-04, 4.8786e-04, // NOLINT + 4.8977e-04, 4.9168e-04, 4.9358e-04, 4.9549e-04, 4.9740e-04, 4.9931e-04, 5.0121e-04, 5.0312e-04, 5.0503e-04, 5.0693e-04, 5.0884e-04, 5.1075e-04, 5.1265e-04, 5.1456e-04, 5.1647e-04, 5.1837e-04, 5.2028e-04, 5.2219e-04, 5.2409e-04, 5.2600e-04, 5.2791e-04, 5.2982e-04, 5.3172e-04, 5.3363e-04, 5.3554e-04, 5.3744e-04, 5.3935e-04, 5.4126e-04, 5.4316e-04, 5.4507e-04, 5.4698e-04, 5.4888e-04, 5.5079e-04, 5.5270e-04, 5.5460e-04, 5.5651e-04, 5.5842e-04, 5.6033e-04, 5.6223e-04, 5.6414e-04, 5.6605e-04, 5.6795e-04, 5.6986e-04, 5.7177e-04, 5.7367e-04, 5.7558e-04, 5.7749e-04, 5.7939e-04, 5.8130e-04, 5.8321e-04, 5.8512e-04, 5.8702e-04, 5.8893e-04, 5.9084e-04, 5.9274e-04, 5.9465e-04, 5.9656e-04, 5.9846e-04, 6.0037e-04, 6.0228e-04, 6.0418e-04, 6.0609e-04, 6.0800e-04, 6.0990e-04, 6.1181e-04, 6.1372e-04, 6.1563e-04, 6.1753e-04, 6.1944e-04, 6.2135e-04, 6.2325e-04, 6.2516e-04, 6.2707e-04, 6.2897e-04, 6.3088e-04, 6.3279e-04, 6.3469e-04, 6.3660e-04, 6.3851e-04, 6.4041e-04, 6.4232e-04, 6.4423e-04, 6.4614e-04, 6.4804e-04, 6.4995e-04, 6.5186e-04, 6.5376e-04, 6.5567e-04, 6.5758e-04, 6.5948e-04, 6.6139e-04, 6.6330e-04, 6.6520e-04, 6.6711e-04, 6.6902e-04, 6.7092e-04, 6.7283e-04, 6.7474e-04, 6.7665e-04, 6.7855e-04, 6.8046e-04, 6.8237e-04, 6.8427e-04, 6.8618e-04, 6.8809e-04, 6.8999e-04, 6.9190e-04, 6.9381e-04, 6.9571e-04, 6.9762e-04, 6.9953e-04, 7.0143e-04, 7.0334e-04, 7.0525e-04, 7.0716e-04, 7.0906e-04, 7.1097e-04, 7.1288e-04, 7.1478e-04, 7.1669e-04, 7.1860e-04, 7.2050e-04, 7.2241e-04, 7.2432e-04, 7.2622e-04, 7.2813e-04, 7.3004e-04, 7.3195e-04, 7.3385e-04, 7.3576e-04, 7.3767e-04, 7.3957e-04, 7.4148e-04, 7.4339e-04, 7.4529e-04, 7.4720e-04, 7.4911e-04, 7.5101e-04, 7.5292e-04, 7.5483e-04, 7.5673e-04, 7.5864e-04, 7.6055e-04, 7.6246e-04, 7.6436e-04, 7.6627e-04, 7.6818e-04, 7.7008e-04, 7.7199e-04, 7.7390e-04, 7.7580e-04, 7.7771e-04, 7.7962e-04, 7.8152e-04, 7.8343e-04, 7.8534e-04, 7.8724e-04, 7.8915e-04, 7.9106e-04, 7.9297e-04, 7.9487e-04, 7.9678e-04, 7.9869e-04, 8.0059e-04, 8.0250e-04, 8.0441e-04, 8.0631e-04, 8.0822e-04, 8.1013e-04, 8.1203e-04, 8.1394e-04, 8.1585e-04, 8.1775e-04, 8.1966e-04, 8.2157e-04, 8.2348e-04, 8.2538e-04, 8.2729e-04, 8.2920e-04, 8.3110e-04, 8.3301e-04, 8.3492e-04, 8.3682e-04, 8.3873e-04, 8.4064e-04, 8.4254e-04, 8.4445e-04, 8.4636e-04, 8.4826e-04, 8.5017e-04, 8.5208e-04, 8.5399e-04, 8.5589e-04, 8.5780e-04, 8.5971e-04, 8.6161e-04, 8.6352e-04, 8.6543e-04, 8.6733e-04, 8.6924e-04, 8.7115e-04, 8.7305e-04, 8.7496e-04, 8.7687e-04, 8.7878e-04, 8.8068e-04, 8.8259e-04, 8.8450e-04, 8.8640e-04, 8.8831e-04, 8.9022e-04, 8.9212e-04, 8.9403e-04, 8.9594e-04, 8.9784e-04, 8.9975e-04, 9.0166e-04, 9.0356e-04, 9.0547e-04, 9.0738e-04, 9.0929e-04, 9.1119e-04, 9.1310e-04, 9.1501e-04, 9.1691e-04, 9.1882e-04, 9.2073e-04, 9.2263e-04, 9.2454e-04, 9.2645e-04, 9.2835e-04, 9.3026e-04, 9.3217e-04, 9.3407e-04, 9.3598e-04, 9.3789e-04, 9.3980e-04, 9.4170e-04, 9.4361e-04, 9.4552e-04, 9.4742e-04, 9.4933e-04, 9.5124e-04, 9.5314e-04, 9.5505e-04, 9.5696e-04, 9.5886e-04, 9.6077e-04, 9.6268e-04, 9.6458e-04, 9.6649e-04, 9.6840e-04, 9.7031e-04, 9.7221e-04, 9.7412e-04, 9.7603e-04, // NOLINT + 9.7984e-04, 9.8365e-04, 9.8747e-04, 9.9128e-04, 9.9510e-04, 9.9891e-04, 1.0027e-03, 1.0065e-03, 1.0104e-03, 1.0142e-03, 1.0180e-03, 1.0218e-03, 1.0256e-03, 1.0294e-03, 1.0332e-03, 1.0371e-03, 1.0409e-03, 1.0447e-03, 1.0485e-03, 1.0523e-03, 1.0561e-03, 1.0599e-03, 1.0638e-03, 1.0676e-03, 1.0714e-03, 1.0752e-03, 1.0790e-03, 1.0828e-03, 1.0866e-03, 1.0905e-03, 1.0943e-03, 1.0981e-03, 1.1019e-03, 1.1057e-03, 1.1095e-03, 1.1133e-03, 1.1172e-03, 1.1210e-03, 1.1248e-03, 1.1286e-03, 1.1324e-03, 1.1362e-03, 1.1400e-03, 1.1439e-03, 1.1477e-03, 1.1515e-03, 1.1553e-03, 1.1591e-03, 1.1629e-03, 1.1667e-03, 1.1706e-03, 1.1744e-03, 1.1782e-03, 1.1820e-03, 1.1858e-03, 1.1896e-03, 1.1934e-03, 1.1973e-03, 1.2011e-03, 1.2049e-03, 1.2087e-03, 1.2125e-03, 1.2163e-03, 1.2201e-03, 1.2240e-03, 1.2278e-03, 1.2316e-03, 1.2354e-03, 1.2392e-03, 1.2430e-03, 1.2468e-03, 1.2507e-03, 1.2545e-03, 1.2583e-03, 1.2621e-03, 1.2659e-03, 1.2697e-03, 1.2735e-03, 1.2774e-03, 1.2812e-03, 1.2850e-03, 1.2888e-03, 1.2926e-03, 1.2964e-03, 1.3002e-03, 1.3040e-03, 1.3079e-03, 1.3117e-03, 1.3155e-03, 1.3193e-03, 1.3231e-03, 1.3269e-03, 1.3307e-03, 1.3346e-03, 1.3384e-03, 1.3422e-03, 1.3460e-03, 1.3498e-03, 1.3536e-03, 1.3574e-03, 1.3613e-03, 1.3651e-03, 1.3689e-03, 1.3727e-03, 1.3765e-03, 1.3803e-03, 1.3841e-03, 1.3880e-03, 1.3918e-03, 1.3956e-03, 1.3994e-03, 1.4032e-03, 1.4070e-03, 1.4108e-03, 1.4147e-03, 1.4185e-03, 1.4223e-03, 1.4261e-03, 1.4299e-03, 1.4337e-03, 1.4375e-03, 1.4414e-03, 1.4452e-03, 1.4490e-03, 1.4528e-03, 1.4566e-03, 1.4604e-03, 1.4642e-03, 1.4681e-03, 1.4719e-03, 1.4757e-03, 1.4795e-03, 1.4833e-03, 1.4871e-03, 1.4909e-03, 1.4948e-03, 1.4986e-03, 1.5024e-03, 1.5062e-03, 1.5100e-03, 1.5138e-03, 1.5176e-03, 1.5215e-03, 1.5253e-03, 1.5291e-03, 1.5329e-03, 1.5367e-03, 1.5405e-03, 1.5443e-03, 1.5482e-03, 1.5520e-03, 1.5558e-03, 1.5596e-03, 1.5634e-03, 1.5672e-03, 1.5710e-03, 1.5749e-03, 1.5787e-03, 1.5825e-03, 1.5863e-03, 1.5901e-03, 1.5939e-03, 1.5977e-03, 1.6016e-03, 1.6054e-03, 1.6092e-03, 1.6130e-03, 1.6168e-03, 1.6206e-03, 1.6244e-03, 1.6283e-03, 1.6321e-03, 1.6359e-03, 1.6397e-03, 1.6435e-03, 1.6473e-03, 1.6511e-03, 1.6550e-03, 1.6588e-03, 1.6626e-03, 1.6664e-03, 1.6702e-03, 1.6740e-03, 1.6778e-03, 1.6817e-03, 1.6855e-03, 1.6893e-03, 1.6931e-03, 1.6969e-03, 1.7007e-03, 1.7045e-03, 1.7084e-03, 1.7122e-03, 1.7160e-03, 1.7198e-03, 1.7236e-03, 1.7274e-03, 1.7312e-03, 1.7351e-03, 1.7389e-03, 1.7427e-03, 1.7465e-03, 1.7503e-03, 1.7541e-03, 1.7579e-03, 1.7618e-03, 1.7656e-03, 1.7694e-03, 1.7732e-03, 1.7770e-03, 1.7808e-03, 1.7846e-03, 1.7885e-03, 1.7923e-03, 1.7961e-03, 1.7999e-03, 1.8037e-03, 1.8075e-03, 1.8113e-03, 1.8152e-03, 1.8190e-03, 1.8228e-03, 1.8266e-03, 1.8304e-03, 1.8342e-03, 1.8380e-03, 1.8419e-03, 1.8457e-03, 1.8495e-03, 1.8533e-03, 1.8571e-03, 1.8609e-03, 1.8647e-03, 1.8686e-03, 1.8724e-03, 1.8762e-03, 1.8800e-03, 1.8838e-03, 1.8876e-03, 1.8914e-03, 1.8953e-03, 1.8991e-03, 1.9029e-03, 1.9067e-03, 1.9105e-03, 1.9143e-03, 1.9181e-03, 1.9220e-03, 1.9258e-03, 1.9296e-03, 1.9334e-03, 1.9372e-03, 1.9410e-03, 1.9448e-03, 1.9487e-03, 1.9525e-03, // NOLINT + 1.9601e-03, 1.9677e-03, 1.9754e-03, 1.9830e-03, 1.9906e-03, 1.9982e-03, 2.0059e-03, 2.0135e-03, 2.0211e-03, 2.0288e-03, 2.0364e-03, 2.0440e-03, 2.0516e-03, 2.0593e-03, 2.0669e-03, 2.0745e-03, 2.0822e-03, 2.0898e-03, 2.0974e-03, 2.1050e-03, 2.1127e-03, 2.1203e-03, 2.1279e-03, 2.1356e-03, 2.1432e-03, 2.1508e-03, 2.1585e-03, 2.1661e-03, 2.1737e-03, 2.1813e-03, 2.1890e-03, 2.1966e-03, 2.2042e-03, 2.2119e-03, 2.2195e-03, 2.2271e-03, 2.2347e-03, 2.2424e-03, 2.2500e-03, 2.2576e-03, 2.2653e-03, 2.2729e-03, 2.2805e-03, 2.2881e-03, 2.2958e-03, 2.3034e-03, 2.3110e-03, 2.3187e-03, 2.3263e-03, 2.3339e-03, 2.3415e-03, 2.3492e-03, 2.3568e-03, 2.3644e-03, 2.3721e-03, 2.3797e-03, 2.3873e-03, 2.3949e-03, 2.4026e-03, 2.4102e-03, 2.4178e-03, 2.4255e-03, 2.4331e-03, 2.4407e-03, 2.4483e-03, 2.4560e-03, 2.4636e-03, 2.4712e-03, 2.4789e-03, 2.4865e-03, 2.4941e-03, 2.5018e-03, 2.5094e-03, 2.5170e-03, 2.5246e-03, 2.5323e-03, 2.5399e-03, 2.5475e-03, 2.5552e-03, 2.5628e-03, 2.5704e-03, 2.5780e-03, 2.5857e-03, 2.5933e-03, 2.6009e-03, 2.6086e-03, 2.6162e-03, 2.6238e-03, 2.6314e-03, 2.6391e-03, 2.6467e-03, 2.6543e-03, 2.6620e-03, 2.6696e-03, 2.6772e-03, 2.6848e-03, 2.6925e-03, 2.7001e-03, 2.7077e-03, 2.7154e-03, 2.7230e-03, 2.7306e-03, 2.7382e-03, 2.7459e-03, 2.7535e-03, 2.7611e-03, 2.7688e-03, 2.7764e-03, 2.7840e-03, 2.7917e-03, 2.7993e-03, 2.8069e-03, 2.8145e-03, 2.8222e-03, 2.8298e-03, 2.8374e-03, 2.8451e-03, 2.8527e-03, 2.8603e-03, 2.8679e-03, 2.8756e-03, 2.8832e-03, 2.8908e-03, 2.8985e-03, 2.9061e-03, 2.9137e-03, 2.9213e-03, 2.9290e-03, 2.9366e-03, 2.9442e-03, 2.9519e-03, 2.9595e-03, 2.9671e-03, 2.9747e-03, 2.9824e-03, 2.9900e-03, 2.9976e-03, 3.0053e-03, 3.0129e-03, 3.0205e-03, 3.0281e-03, 3.0358e-03, 3.0434e-03, 3.0510e-03, 3.0587e-03, 3.0663e-03, 3.0739e-03, 3.0816e-03, 3.0892e-03, 3.0968e-03, 3.1044e-03, 3.1121e-03, 3.1197e-03, 3.1273e-03, 3.1350e-03, 3.1426e-03, 3.1502e-03, 3.1578e-03, 3.1655e-03, 3.1731e-03, 3.1807e-03, 3.1884e-03, 3.1960e-03, 3.2036e-03, 3.2112e-03, 3.2189e-03, 3.2265e-03, 3.2341e-03, 3.2418e-03, 3.2494e-03, 3.2570e-03, 3.2646e-03, 3.2723e-03, 3.2799e-03, 3.2875e-03, 3.2952e-03, 3.3028e-03, 3.3104e-03, 3.3180e-03, 3.3257e-03, 3.3333e-03, 3.3409e-03, 3.3486e-03, 3.3562e-03, 3.3638e-03, 3.3715e-03, 3.3791e-03, 3.3867e-03, 3.3943e-03, 3.4020e-03, 3.4096e-03, 3.4172e-03, 3.4249e-03, 3.4325e-03, 3.4401e-03, 3.4477e-03, 3.4554e-03, 3.4630e-03, 3.4706e-03, 3.4783e-03, 3.4859e-03, 3.4935e-03, 3.5011e-03, 3.5088e-03, 3.5164e-03, 3.5240e-03, 3.5317e-03, 3.5393e-03, 3.5469e-03, 3.5545e-03, 3.5622e-03, 3.5698e-03, 3.5774e-03, 3.5851e-03, 3.5927e-03, 3.6003e-03, 3.6079e-03, 3.6156e-03, 3.6232e-03, 3.6308e-03, 3.6385e-03, 3.6461e-03, 3.6537e-03, 3.6613e-03, 3.6690e-03, 3.6766e-03, 3.6842e-03, 3.6919e-03, 3.6995e-03, 3.7071e-03, 3.7148e-03, 3.7224e-03, 3.7300e-03, 3.7376e-03, 3.7453e-03, 3.7529e-03, 3.7605e-03, 3.7682e-03, 3.7758e-03, 3.7834e-03, 3.7910e-03, 3.7987e-03, 3.8063e-03, 3.8139e-03, 3.8216e-03, 3.8292e-03, 3.8368e-03, 3.8444e-03, 3.8521e-03, 3.8597e-03, 3.8673e-03, 3.8750e-03, 3.8826e-03, 3.8902e-03, 3.8978e-03, 3.9055e-03, // NOLINT + 3.9207e-03, 3.9360e-03, 3.9513e-03, 3.9665e-03, 3.9818e-03, 3.9970e-03, 4.0123e-03, 4.0275e-03, 4.0428e-03, 4.0581e-03, 4.0733e-03, 4.0886e-03, 4.1038e-03, 4.1191e-03, 4.1343e-03, 4.1496e-03, 4.1649e-03, 4.1801e-03, 4.1954e-03, 4.2106e-03, 4.2259e-03, 4.2412e-03, 4.2564e-03, 4.2717e-03, 4.2869e-03, 4.3022e-03, 4.3174e-03, 4.3327e-03, 4.3480e-03, 4.3632e-03, 4.3785e-03, 4.3937e-03, 4.4090e-03, 4.4243e-03, 4.4395e-03, 4.4548e-03, 4.4700e-03, 4.4853e-03, 4.5005e-03, 4.5158e-03, 4.5311e-03, 4.5463e-03, 4.5616e-03, 4.5768e-03, 4.5921e-03, 4.6074e-03, 4.6226e-03, 4.6379e-03, 4.6531e-03, 4.6684e-03, 4.6836e-03, 4.6989e-03, 4.7142e-03, 4.7294e-03, 4.7447e-03, 4.7599e-03, 4.7752e-03, 4.7905e-03, 4.8057e-03, 4.8210e-03, 4.8362e-03, 4.8515e-03, 4.8667e-03, 4.8820e-03, 4.8973e-03, 4.9125e-03, 4.9278e-03, 4.9430e-03, 4.9583e-03, 4.9736e-03, 4.9888e-03, 5.0041e-03, 5.0193e-03, 5.0346e-03, 5.0498e-03, 5.0651e-03, 5.0804e-03, 5.0956e-03, 5.1109e-03, 5.1261e-03, 5.1414e-03, 5.1567e-03, 5.1719e-03, 5.1872e-03, 5.2024e-03, 5.2177e-03, 5.2329e-03, 5.2482e-03, 5.2635e-03, 5.2787e-03, 5.2940e-03, 5.3092e-03, 5.3245e-03, 5.3398e-03, 5.3550e-03, 5.3703e-03, 5.3855e-03, 5.4008e-03, 5.4160e-03, 5.4313e-03, 5.4466e-03, 5.4618e-03, 5.4771e-03, 5.4923e-03, 5.5076e-03, 5.5229e-03, 5.5381e-03, 5.5534e-03, 5.5686e-03, 5.5839e-03, 5.5991e-03, 5.6144e-03, 5.6297e-03, 5.6449e-03, 5.6602e-03, 5.6754e-03, 5.6907e-03, 5.7060e-03, 5.7212e-03, 5.7365e-03, 5.7517e-03, 5.7670e-03, 5.7822e-03, 5.7975e-03, 5.8128e-03, 5.8280e-03, 5.8433e-03, 5.8585e-03, 5.8738e-03, 5.8891e-03, 5.9043e-03, 5.9196e-03, 5.9348e-03, 5.9501e-03, 5.9653e-03, 5.9806e-03, 5.9959e-03, 6.0111e-03, 6.0264e-03, 6.0416e-03, 6.0569e-03, 6.0722e-03, 6.0874e-03, 6.1027e-03, 6.1179e-03, 6.1332e-03, 6.1484e-03, 6.1637e-03, 6.1790e-03, 6.1942e-03, 6.2095e-03, 6.2247e-03, 6.2400e-03, 6.2553e-03, 6.2705e-03, 6.2858e-03, 6.3010e-03, 6.3163e-03, 6.3315e-03, 6.3468e-03, 6.3621e-03, 6.3773e-03, 6.3926e-03, 6.4078e-03, 6.4231e-03, 6.4384e-03, 6.4536e-03, 6.4689e-03, 6.4841e-03, 6.4994e-03, 6.5146e-03, 6.5299e-03, 6.5452e-03, 6.5604e-03, 6.5757e-03, 6.5909e-03, 6.6062e-03, 6.6215e-03, 6.6367e-03, 6.6520e-03, 6.6672e-03, 6.6825e-03, 6.6977e-03, 6.7130e-03, 6.7283e-03, 6.7435e-03, 6.7588e-03, 6.7740e-03, 6.7893e-03, 6.8046e-03, 6.8198e-03, 6.8351e-03, 6.8503e-03, 6.8656e-03, 6.8808e-03, 6.8961e-03, 6.9114e-03, 6.9266e-03, 6.9419e-03, 6.9571e-03, 6.9724e-03, 6.9877e-03, 7.0029e-03, 7.0182e-03, 7.0334e-03, 7.0487e-03, 7.0639e-03, 7.0792e-03, 7.0945e-03, 7.1097e-03, 7.1250e-03, 7.1402e-03, 7.1555e-03, 7.1708e-03, 7.1860e-03, 7.2013e-03, 7.2165e-03, 7.2318e-03, 7.2470e-03, 7.2623e-03, 7.2776e-03, 7.2928e-03, 7.3081e-03, 7.3233e-03, 7.3386e-03, 7.3539e-03, 7.3691e-03, 7.3844e-03, 7.3996e-03, 7.4149e-03, 7.4301e-03, 7.4454e-03, 7.4607e-03, 7.4759e-03, 7.4912e-03, 7.5064e-03, 7.5217e-03, 7.5370e-03, 7.5522e-03, 7.5675e-03, 7.5827e-03, 7.5980e-03, 7.6132e-03, 7.6285e-03, 7.6438e-03, 7.6590e-03, 7.6743e-03, 7.6895e-03, 7.7048e-03, 7.7201e-03, 7.7353e-03, 7.7506e-03, 7.7658e-03, 7.7811e-03, 7.7963e-03, 7.8116e-03, // NOLINT + 7.8421e-03, 7.8726e-03, 7.9032e-03, 7.9337e-03, 7.9642e-03, 7.9947e-03, 8.0252e-03, 8.0557e-03, 8.0863e-03, 8.1168e-03, 8.1473e-03, 8.1778e-03, 8.2083e-03, 8.2388e-03, 8.2694e-03, 8.2999e-03, 8.3304e-03, 8.3609e-03, 8.3914e-03, 8.4219e-03, 8.4525e-03, 8.4830e-03, 8.5135e-03, 8.5440e-03, 8.5745e-03, 8.6051e-03, 8.6356e-03, 8.6661e-03, 8.6966e-03, 8.7271e-03, 8.7576e-03, 8.7882e-03, 8.8187e-03, 8.8492e-03, 8.8797e-03, 8.9102e-03, 8.9407e-03, 8.9713e-03, 9.0018e-03, 9.0323e-03, 9.0628e-03, 9.0933e-03, 9.1238e-03, 9.1544e-03, 9.1849e-03, 9.2154e-03, 9.2459e-03, 9.2764e-03, 9.3069e-03, 9.3375e-03, 9.3680e-03, 9.3985e-03, 9.4290e-03, 9.4595e-03, 9.4900e-03, 9.5206e-03, 9.5511e-03, 9.5816e-03, 9.6121e-03, 9.6426e-03, 9.6731e-03, 9.7037e-03, 9.7342e-03, 9.7647e-03, 9.7952e-03, 9.8257e-03, 9.8563e-03, 9.8868e-03, 9.9173e-03, 9.9478e-03, 9.9783e-03, 1.0009e-02, 1.0039e-02, 1.0070e-02, 1.0100e-02, 1.0131e-02, 1.0161e-02, 1.0192e-02, 1.0222e-02, 1.0253e-02, 1.0283e-02, 1.0314e-02, 1.0345e-02, 1.0375e-02, 1.0406e-02, 1.0436e-02, 1.0467e-02, 1.0497e-02, 1.0528e-02, 1.0558e-02, 1.0589e-02, 1.0619e-02, 1.0650e-02, 1.0680e-02, 1.0711e-02, 1.0741e-02, 1.0772e-02, 1.0802e-02, 1.0833e-02, 1.0863e-02, 1.0894e-02, 1.0924e-02, 1.0955e-02, 1.0985e-02, 1.1016e-02, 1.1046e-02, 1.1077e-02, 1.1107e-02, 1.1138e-02, 1.1168e-02, 1.1199e-02, 1.1230e-02, 1.1260e-02, 1.1291e-02, 1.1321e-02, 1.1352e-02, 1.1382e-02, 1.1413e-02, 1.1443e-02, 1.1474e-02, 1.1504e-02, 1.1535e-02, 1.1565e-02, 1.1596e-02, 1.1626e-02, 1.1657e-02, 1.1687e-02, 1.1718e-02, 1.1748e-02, 1.1779e-02, 1.1809e-02, 1.1840e-02, 1.1870e-02, 1.1901e-02, 1.1931e-02, 1.1962e-02, 1.1992e-02, 1.2023e-02, 1.2053e-02, 1.2084e-02, 1.2115e-02, 1.2145e-02, 1.2176e-02, 1.2206e-02, 1.2237e-02, 1.2267e-02, 1.2298e-02, 1.2328e-02, 1.2359e-02, 1.2389e-02, 1.2420e-02, 1.2450e-02, 1.2481e-02, 1.2511e-02, 1.2542e-02, 1.2572e-02, 1.2603e-02, 1.2633e-02, 1.2664e-02, 1.2694e-02, 1.2725e-02, 1.2755e-02, 1.2786e-02, 1.2816e-02, 1.2847e-02, 1.2877e-02, 1.2908e-02, 1.2938e-02, 1.2969e-02, 1.3000e-02, 1.3030e-02, 1.3061e-02, 1.3091e-02, 1.3122e-02, 1.3152e-02, 1.3183e-02, 1.3213e-02, 1.3244e-02, 1.3274e-02, 1.3305e-02, 1.3335e-02, 1.3366e-02, 1.3396e-02, 1.3427e-02, 1.3457e-02, 1.3488e-02, 1.3518e-02, 1.3549e-02, 1.3579e-02, 1.3610e-02, 1.3640e-02, 1.3671e-02, 1.3701e-02, 1.3732e-02, 1.3762e-02, 1.3793e-02, 1.3823e-02, 1.3854e-02, 1.3885e-02, 1.3915e-02, 1.3946e-02, 1.3976e-02, 1.4007e-02, 1.4037e-02, 1.4068e-02, 1.4098e-02, 1.4129e-02, 1.4159e-02, 1.4190e-02, 1.4220e-02, 1.4251e-02, 1.4281e-02, 1.4312e-02, 1.4342e-02, 1.4373e-02, 1.4403e-02, 1.4434e-02, 1.4464e-02, 1.4495e-02, 1.4525e-02, 1.4556e-02, 1.4586e-02, 1.4617e-02, 1.4647e-02, 1.4678e-02, 1.4708e-02, 1.4739e-02, 1.4770e-02, 1.4800e-02, 1.4831e-02, 1.4861e-02, 1.4892e-02, 1.4922e-02, 1.4953e-02, 1.4983e-02, 1.5014e-02, 1.5044e-02, 1.5075e-02, 1.5105e-02, 1.5136e-02, 1.5166e-02, 1.5197e-02, 1.5227e-02, 1.5258e-02, 1.5288e-02, 1.5319e-02, 1.5349e-02, 1.5380e-02, 1.5410e-02, 1.5441e-02, 1.5471e-02, 1.5502e-02, 1.5532e-02, 1.5563e-02, 1.5593e-02, 1.5624e-02, // NOLINT + 1.5746e-02, 1.5868e-02, 1.5990e-02, 1.6112e-02, 1.6234e-02, 1.6356e-02, 1.6478e-02, 1.6601e-02, 1.6723e-02, 1.6845e-02, 1.6967e-02, 1.7089e-02, 1.7211e-02, 1.7333e-02, 1.7455e-02, 1.7577e-02, 1.7699e-02, 1.7821e-02, 1.7943e-02, 1.8065e-02, 1.8187e-02, 1.8310e-02, 1.8432e-02, 1.8554e-02, 1.8676e-02, 1.8798e-02, 1.8920e-02, 1.9042e-02, 1.9164e-02, 1.9286e-02, 1.9408e-02, 1.9530e-02, 1.9652e-02, 1.9774e-02, 1.9896e-02, 2.0018e-02, 2.0141e-02, 2.0263e-02, 2.0385e-02, 2.0507e-02, 2.0629e-02, 2.0751e-02, 2.0873e-02, 2.0995e-02, 2.1117e-02, 2.1239e-02, 2.1361e-02, 2.1483e-02, 2.1605e-02, 2.1727e-02, 2.1850e-02, 2.1972e-02, 2.2094e-02, 2.2216e-02, 2.2338e-02, 2.2460e-02, 2.2582e-02, 2.2704e-02, 2.2826e-02, 2.2948e-02, 2.3070e-02, 2.3192e-02, 2.3314e-02, 2.3436e-02, 2.3558e-02, 2.3681e-02, 2.3803e-02, 2.3925e-02, 2.4047e-02, 2.4169e-02, 2.4291e-02, 2.4413e-02, 2.4535e-02, 2.4657e-02, 2.4779e-02, 2.4901e-02, 2.5023e-02, 2.5145e-02, 2.5267e-02, 2.5390e-02, 2.5512e-02, 2.5634e-02, 2.5756e-02, 2.5878e-02, 2.6000e-02, 2.6122e-02, 2.6244e-02, 2.6366e-02, 2.6488e-02, 2.6610e-02, 2.6732e-02, 2.6854e-02, 2.6976e-02, 2.7099e-02, 2.7221e-02, 2.7343e-02, 2.7465e-02, 2.7587e-02, 2.7709e-02, 2.7831e-02, 2.7953e-02, 2.8075e-02, 2.8197e-02, 2.8319e-02, 2.8441e-02, 2.8563e-02, 2.8685e-02, 2.8807e-02, 2.8930e-02, 2.9052e-02, 2.9174e-02, 2.9296e-02, 2.9418e-02, 2.9540e-02, 2.9662e-02, 2.9784e-02, 2.9906e-02, 3.0028e-02, 3.0150e-02, 3.0272e-02, 3.0394e-02, 3.0516e-02, 3.0639e-02, 3.0761e-02, 3.0883e-02, 3.1005e-02, 3.1127e-02, 3.1249e-02, 3.1493e-02, 3.1737e-02, 3.1981e-02, 3.2225e-02, 3.2470e-02, 3.2714e-02, 3.2958e-02, 3.3202e-02, 3.3446e-02, 3.3690e-02, 3.3934e-02, 3.4179e-02, 3.4423e-02, 3.4667e-02, 3.4911e-02, 3.5155e-02, 3.5399e-02, 3.5643e-02, 3.5888e-02, 3.6132e-02, 3.6376e-02, 3.6620e-02, 3.6864e-02, 3.7108e-02, 3.7352e-02, 3.7596e-02, 3.7841e-02, 3.8085e-02, 3.8329e-02, 3.8573e-02, 3.8817e-02, 3.9061e-02, 3.9305e-02, 3.9550e-02, 3.9794e-02, 4.0038e-02, 4.0282e-02, 4.0526e-02, 4.0770e-02, 4.1014e-02, 4.1259e-02, 4.1503e-02, 4.1747e-02, 4.1991e-02, 4.2235e-02, 4.2479e-02, 4.2723e-02, 4.2968e-02, 4.3212e-02, 4.3456e-02, 4.3700e-02, 4.3944e-02, 4.4188e-02, 4.4432e-02, 4.4677e-02, 4.4921e-02, 4.5165e-02, 4.5409e-02, 4.5653e-02, 4.5897e-02, 4.6141e-02, 4.6386e-02, 4.6630e-02, 4.6874e-02, 4.7118e-02, 4.7362e-02, 4.7606e-02, 4.7850e-02, 4.8095e-02, 4.8339e-02, 4.8583e-02, 4.8827e-02, 4.9071e-02, 4.9315e-02, 4.9559e-02, 4.9803e-02, 5.0048e-02, 5.0292e-02, 5.0536e-02, 5.0780e-02, 5.1024e-02, 5.1268e-02, 5.1512e-02, 5.1757e-02, 5.2001e-02, 5.2245e-02, 5.2489e-02, 5.2733e-02, 5.2977e-02, 5.3221e-02, 5.3466e-02, 5.3710e-02, 5.3954e-02, 5.4198e-02, 5.4442e-02, 5.4686e-02, 5.4930e-02, 5.5175e-02, 5.5419e-02, 5.5663e-02, 5.5907e-02, 5.6151e-02, 5.6395e-02, 5.6639e-02, 5.6884e-02, 5.7128e-02, 5.7372e-02, 5.7616e-02, 5.7860e-02, 5.8104e-02, 5.8348e-02, 5.8593e-02, 5.8837e-02, 5.9081e-02, 5.9325e-02, 5.9569e-02, 5.9813e-02, 6.0057e-02, 6.0301e-02, 6.0546e-02, 6.0790e-02, 6.1034e-02, 6.1278e-02, 6.1522e-02, 6.1766e-02, 6.2010e-02, 6.2255e-02, 6.2499e-02, // NOLINT + 6.2743e-02, 6.2987e-02, 6.3231e-02, 6.3475e-02, 6.3719e-02, 6.3964e-02, 6.4208e-02, 6.4452e-02, 6.4696e-02, 6.4940e-02, 6.5184e-02, 6.5428e-02, 6.5673e-02, 6.5917e-02, 6.6161e-02, 6.6405e-02, 6.6649e-02, 6.6893e-02, 6.7137e-02, 6.7382e-02, 6.7626e-02, 6.7870e-02, 6.8114e-02, 6.8358e-02, 6.8602e-02, 6.8846e-02, 6.9091e-02, 6.9335e-02, 6.9579e-02, 6.9823e-02, 7.0067e-02, 7.0311e-02, 7.0555e-02, 7.0799e-02, 7.1044e-02, 7.1288e-02, 7.1532e-02, 7.1776e-02, 7.2020e-02, 7.2264e-02, 7.2508e-02, 7.2753e-02, 7.2997e-02, 7.3241e-02, 7.3485e-02, 7.3729e-02, 7.3973e-02, 7.4217e-02, 7.4462e-02, 7.4706e-02, 7.4950e-02, 7.5194e-02, 7.5438e-02, 7.5682e-02, 7.5926e-02, 7.6171e-02, 7.6415e-02, 7.6659e-02, 7.6903e-02, 7.7147e-02, 7.7391e-02, 7.7635e-02, 7.7880e-02, 7.8124e-02, 7.8368e-02, 7.8612e-02, 7.8856e-02, 7.9100e-02, 7.9344e-02, 7.9589e-02, 7.9833e-02, 8.0077e-02, 8.0321e-02, 8.0565e-02, 8.0809e-02, 8.1053e-02, 8.1298e-02, 8.1542e-02, 8.1786e-02, 8.2030e-02, 8.2274e-02, 8.2518e-02, 8.2762e-02, 8.3006e-02, 8.3251e-02, 8.3495e-02, 8.3739e-02, 8.3983e-02, 8.4227e-02, 8.4471e-02, 8.4715e-02, 8.4960e-02, 8.5204e-02, 8.5448e-02, 8.5692e-02, 8.5936e-02, 8.6180e-02, 8.6424e-02, 8.6669e-02, 8.6913e-02, 8.7157e-02, 8.7401e-02, 8.7645e-02, 8.7889e-02, 8.8133e-02, 8.8378e-02, 8.8622e-02, 8.8866e-02, 8.9110e-02, 8.9354e-02, 8.9598e-02, 8.9842e-02, 9.0087e-02, 9.0331e-02, 9.0575e-02, 9.0819e-02, 9.1063e-02, 9.1307e-02, 9.1551e-02, 9.1796e-02, 9.2040e-02, 9.2284e-02, 9.2528e-02, 9.2772e-02, 9.3016e-02, 9.3260e-02, 9.3504e-02, 9.3749e-02, 9.4237e-02, 9.4725e-02, 9.5213e-02, 9.5702e-02, 9.6190e-02, 9.6678e-02, 9.7167e-02, 9.7655e-02, 9.8143e-02, 9.8631e-02, 9.9120e-02, 9.9608e-02, 1.0010e-01, 1.0058e-01, 1.0107e-01, 1.0156e-01, 1.0205e-01, 1.0254e-01, 1.0303e-01, 1.0351e-01, 1.0400e-01, 1.0449e-01, 1.0498e-01, 1.0547e-01, 1.0596e-01, 1.0644e-01, 1.0693e-01, 1.0742e-01, 1.0791e-01, 1.0840e-01, 1.0889e-01, 1.0937e-01, 1.0986e-01, 1.1035e-01, 1.1084e-01, 1.1133e-01, 1.1182e-01, 1.1230e-01, 1.1279e-01, 1.1328e-01, 1.1377e-01, 1.1426e-01, 1.1474e-01, 1.1523e-01, 1.1572e-01, 1.1621e-01, 1.1670e-01, 1.1719e-01, 1.1767e-01, 1.1816e-01, 1.1865e-01, 1.1914e-01, 1.1963e-01, 1.2012e-01, 1.2060e-01, 1.2109e-01, 1.2158e-01, 1.2207e-01, 1.2256e-01, 1.2305e-01, 1.2353e-01, 1.2402e-01, 1.2451e-01, 1.2500e-01, 1.2549e-01, 1.2598e-01, 1.2646e-01, 1.2695e-01, 1.2744e-01, 1.2793e-01, 1.2842e-01, 1.2890e-01, 1.2939e-01, 1.2988e-01, 1.3037e-01, 1.3086e-01, 1.3135e-01, 1.3183e-01, 1.3232e-01, 1.3281e-01, 1.3330e-01, 1.3379e-01, 1.3428e-01, 1.3476e-01, 1.3525e-01, 1.3574e-01, 1.3623e-01, 1.3672e-01, 1.3721e-01, 1.3769e-01, 1.3818e-01, 1.3867e-01, 1.3916e-01, 1.3965e-01, 1.4014e-01, 1.4062e-01, 1.4111e-01, 1.4160e-01, 1.4209e-01, 1.4258e-01, 1.4306e-01, 1.4355e-01, 1.4404e-01, 1.4453e-01, 1.4502e-01, 1.4551e-01, 1.4599e-01, 1.4648e-01, 1.4697e-01, 1.4746e-01, 1.4795e-01, 1.4844e-01, 1.4892e-01, 1.4941e-01, 1.4990e-01, 1.5039e-01, 1.5088e-01, 1.5137e-01, 1.5185e-01, 1.5234e-01, 1.5283e-01, 1.5332e-01, 1.5381e-01, 1.5430e-01, 1.5478e-01, 1.5527e-01, 1.5576e-01, 1.5625e-01, // NOLINT + 1.5674e-01, 1.5723e-01, 1.5771e-01, 1.5820e-01, 1.5869e-01, 1.5918e-01, 1.5967e-01, 1.6015e-01, 1.6064e-01, 1.6113e-01, 1.6162e-01, 1.6211e-01, 1.6260e-01, 1.6308e-01, 1.6357e-01, 1.6406e-01, 1.6455e-01, 1.6504e-01, 1.6553e-01, 1.6601e-01, 1.6650e-01, 1.6699e-01, 1.6748e-01, 1.6797e-01, 1.6846e-01, 1.6894e-01, 1.6943e-01, 1.6992e-01, 1.7041e-01, 1.7090e-01, 1.7139e-01, 1.7187e-01, 1.7236e-01, 1.7285e-01, 1.7334e-01, 1.7383e-01, 1.7431e-01, 1.7480e-01, 1.7529e-01, 1.7578e-01, 1.7627e-01, 1.7676e-01, 1.7724e-01, 1.7773e-01, 1.7822e-01, 1.7871e-01, 1.7920e-01, 1.7969e-01, 1.8017e-01, 1.8066e-01, 1.8115e-01, 1.8164e-01, 1.8213e-01, 1.8262e-01, 1.8310e-01, 1.8359e-01, 1.8408e-01, 1.8457e-01, 1.8506e-01, 1.8555e-01, 1.8603e-01, 1.8652e-01, 1.8701e-01, 1.8750e-01, 1.8848e-01, 1.8945e-01, 1.9043e-01, 1.9140e-01, 1.9238e-01, 1.9336e-01, 1.9433e-01, 1.9531e-01, 1.9629e-01, 1.9726e-01, 1.9824e-01, 1.9922e-01, 2.0019e-01, 2.0117e-01, 2.0215e-01, 2.0312e-01, 2.0410e-01, 2.0508e-01, 2.0605e-01, 2.0703e-01, 2.0801e-01, 2.0898e-01, 2.0996e-01, 2.1094e-01, 2.1191e-01, 2.1289e-01, 2.1387e-01, 2.1484e-01, 2.1582e-01, 2.1680e-01, 2.1777e-01, 2.1875e-01, 2.1972e-01, 2.2070e-01, 2.2168e-01, 2.2265e-01, 2.2363e-01, 2.2461e-01, 2.2558e-01, 2.2656e-01, 2.2754e-01, 2.2851e-01, 2.2949e-01, 2.3047e-01, 2.3144e-01, 2.3242e-01, 2.3340e-01, 2.3437e-01, 2.3535e-01, 2.3633e-01, 2.3730e-01, 2.3828e-01, 2.3926e-01, 2.4023e-01, 2.4121e-01, 2.4219e-01, 2.4316e-01, 2.4414e-01, 2.4512e-01, 2.4609e-01, 2.4707e-01, 2.4805e-01, 2.4902e-01, 2.5000e-01, 2.5097e-01, 2.5195e-01, 2.5293e-01, 2.5390e-01, 2.5488e-01, 2.5586e-01, 2.5683e-01, 2.5781e-01, 2.5879e-01, 2.5976e-01, 2.6074e-01, 2.6172e-01, 2.6269e-01, 2.6367e-01, 2.6465e-01, 2.6562e-01, 2.6660e-01, 2.6758e-01, 2.6855e-01, 2.6953e-01, 2.7051e-01, 2.7148e-01, 2.7246e-01, 2.7344e-01, 2.7441e-01, 2.7539e-01, 2.7637e-01, 2.7734e-01, 2.7832e-01, 2.7930e-01, 2.8027e-01, 2.8125e-01, 2.8222e-01, 2.8320e-01, 2.8418e-01, 2.8515e-01, 2.8613e-01, 2.8711e-01, 2.8808e-01, 2.8906e-01, 2.9004e-01, 2.9101e-01, 2.9199e-01, 2.9297e-01, 2.9394e-01, 2.9492e-01, 2.9590e-01, 2.9687e-01, 2.9785e-01, 2.9883e-01, 2.9980e-01, 3.0078e-01, 3.0176e-01, 3.0273e-01, 3.0371e-01, 3.0469e-01, 3.0566e-01, 3.0664e-01, 3.0762e-01, 3.0859e-01, 3.0957e-01, 3.1055e-01, 3.1152e-01, 3.1250e-01, 3.1347e-01, 3.1445e-01, 3.1543e-01, 3.1640e-01, 3.1738e-01, 3.1836e-01, 3.1933e-01, 3.2031e-01, 3.2129e-01, 3.2226e-01, 3.2324e-01, 3.2422e-01, 3.2519e-01, 3.2617e-01, 3.2715e-01, 3.2812e-01, 3.2910e-01, 3.3008e-01, 3.3105e-01, 3.3203e-01, 3.3301e-01, 3.3398e-01, 3.3496e-01, 3.3594e-01, 3.3691e-01, 3.3789e-01, 3.3887e-01, 3.3984e-01, 3.4082e-01, 3.4180e-01, 3.4277e-01, 3.4375e-01, 3.4472e-01, 3.4570e-01, 3.4668e-01, 3.4765e-01, 3.4863e-01, 3.4961e-01, 3.5058e-01, 3.5156e-01, 3.5254e-01, 3.5351e-01, 3.5449e-01, 3.5547e-01, 3.5644e-01, 3.5742e-01, 3.5840e-01, 3.5937e-01, 3.6035e-01, 3.6133e-01, 3.6230e-01, 3.6328e-01, 3.6426e-01, 3.6523e-01, 3.6621e-01, 3.6719e-01, 3.6816e-01, 3.6914e-01, 3.7012e-01, 3.7109e-01, 3.7207e-01, 3.7305e-01, 3.7402e-01, 3.7500e-01, // NOLINT + 3.7695e-01, 3.7890e-01, 3.8086e-01, 3.8281e-01, 3.8476e-01, 3.8672e-01, 3.8867e-01, 3.9062e-01, 3.9258e-01, 3.9453e-01, 3.9648e-01, 3.9844e-01, 4.0039e-01, 4.0234e-01, 4.0430e-01, 4.0625e-01, 4.0820e-01, 4.1015e-01, 4.1211e-01, 4.1406e-01, 4.1601e-01, 4.1797e-01, 4.1992e-01, 4.2187e-01, 4.2383e-01, 4.2578e-01, 4.2773e-01, 4.2969e-01, 4.3164e-01, 4.3359e-01, 4.3555e-01, 4.3750e-01, 4.3945e-01, 4.4140e-01, 4.4336e-01, 4.4531e-01, 4.4726e-01, 4.4922e-01, 4.5117e-01, 4.5312e-01, 4.5508e-01, 4.5703e-01, 4.5898e-01, 4.6094e-01, 4.6289e-01, 4.6484e-01, 4.6680e-01, 4.6875e-01, 4.7070e-01, 4.7265e-01, 4.7461e-01, 4.7656e-01, 4.7851e-01, 4.8047e-01, 4.8242e-01, 4.8437e-01, 4.8633e-01, 4.8828e-01, 4.9023e-01, 4.9219e-01, 4.9414e-01, 4.9609e-01, 4.9805e-01, 5.0000e-01, 5.0195e-01, 5.0390e-01, 5.0586e-01, 5.0781e-01, 5.0976e-01, 5.1172e-01, 5.1367e-01, 5.1562e-01, 5.1758e-01, 5.1953e-01, 5.2148e-01, 5.2344e-01, 5.2539e-01, 5.2734e-01, 5.2930e-01, 5.3125e-01, 5.3320e-01, 5.3515e-01, 5.3711e-01, 5.3906e-01, 5.4101e-01, 5.4297e-01, 5.4492e-01, 5.4687e-01, 5.4883e-01, 5.5078e-01, 5.5273e-01, 5.5469e-01, 5.5664e-01, 5.5859e-01, 5.6055e-01, 5.6250e-01, 5.6445e-01, 5.6640e-01, 5.6836e-01, 5.7031e-01, 5.7226e-01, 5.7422e-01, 5.7617e-01, 5.7812e-01, 5.8008e-01, 5.8203e-01, 5.8398e-01, 5.8594e-01, 5.8789e-01, 5.8984e-01, 5.9180e-01, 5.9375e-01, 5.9570e-01, 5.9765e-01, 5.9961e-01, 6.0156e-01, 6.0351e-01, 6.0547e-01, 6.0742e-01, 6.0937e-01, 6.1133e-01, 6.1328e-01, 6.1523e-01, 6.1719e-01, 6.1914e-01, 6.2109e-01, 6.2305e-01, 6.2500e-01, 6.2695e-01, 6.2890e-01, 6.3086e-01, 6.3281e-01, 6.3476e-01, 6.3672e-01, 6.3867e-01, 6.4062e-01, 6.4258e-01, 6.4453e-01, 6.4648e-01, 6.4844e-01, 6.5039e-01, 6.5234e-01, 6.5430e-01, 6.5625e-01, 6.5820e-01, 6.6015e-01, 6.6211e-01, 6.6406e-01, 6.6601e-01, 6.6797e-01, 6.6992e-01, 6.7187e-01, 6.7383e-01, 6.7578e-01, 6.7773e-01, 6.7969e-01, 6.8164e-01, 6.8359e-01, 6.8554e-01, 6.8750e-01, 6.8945e-01, 6.9140e-01, 6.9336e-01, 6.9531e-01, 6.9726e-01, 6.9922e-01, 7.0117e-01, 7.0312e-01, 7.0508e-01, 7.0703e-01, 7.0898e-01, 7.1094e-01, 7.1289e-01, 7.1484e-01, 7.1679e-01, 7.1875e-01, 7.2070e-01, 7.2265e-01, 7.2461e-01, 7.2656e-01, 7.2851e-01, 7.3047e-01, 7.3242e-01, 7.3437e-01, 7.3633e-01, 7.3828e-01, 7.4023e-01, 7.4219e-01, 7.4414e-01, 7.4609e-01, 7.4804e-01, 7.5000e-01, 7.5390e-01, 7.5781e-01, 7.6172e-01, 7.6562e-01, 7.6953e-01, 7.7344e-01, 7.7734e-01, 7.8125e-01, 7.8515e-01, 7.8906e-01, 7.9297e-01, 7.9687e-01, 8.0078e-01, 8.0469e-01, 8.0859e-01, 8.1250e-01, 8.1640e-01, 8.2031e-01, 8.2422e-01, 8.2812e-01, 8.3203e-01, 8.3594e-01, 8.3984e-01, 8.4375e-01, 8.4765e-01, 8.5156e-01, 8.5547e-01, 8.5937e-01, 8.6328e-01, 8.6719e-01, 8.7109e-01, 8.7500e-01, 8.7890e-01, 8.8281e-01, 8.8672e-01, 8.9062e-01, 8.9453e-01, 8.9844e-01, 9.0234e-01, 9.0625e-01, 9.1015e-01, 9.1406e-01, 9.1797e-01, 9.2187e-01, 9.2578e-01, 9.2969e-01, 9.3359e-01, 9.3750e-01, 9.4140e-01, 9.4531e-01, 9.4922e-01, 9.5312e-01, 9.5703e-01, 9.6094e-01, 9.6484e-01, 9.6875e-01, 9.7265e-01, 9.7656e-01, 9.8047e-01, 9.8437e-01, 9.8828e-01, 9.9219e-01, 9.9609e-01, 1.0000e+00 // NOLINT +}; float4 normalize_pv(int4 parsed, float vignette_factor) { // PWL - float4 pv = {ox_lut_func(parsed.s0), ox_lut_func(parsed.s1), ox_lut_func(parsed.s2), ox_lut_func(parsed.s3)}; + float4 pv = {ox03c10_lut[parsed.s0], ox03c10_lut[parsed.s1], ox03c10_lut[parsed.s2], ox03c10_lut[parsed.s3]}; return clamp(pv*vignette_factor*256.0, 0.0, 1.0); } @@ -43,4 +40,4 @@ float3 apply_gamma(float3 rgb, int expo_time) { return -0.507089*exp(-12.54124638*rgb) + 0.9655*powr(rgb, 0.5) - 0.472597*rgb + 0.507089; } -#endif +#endif \ No newline at end of file From e5870dcf20a6088340db2ca43bec5645bb6171be Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Thu, 26 Sep 2024 19:48:31 -0700 Subject: [PATCH 148/214] camerad: Replace ox LUT with function (#33659) * fast eh * need * ; * no chained --------- Co-authored-by: Comma Device --- system/camerad/sensors/ox03c10_cl.h | 43 +++++++++++++++-------------- 1 file changed, 23 insertions(+), 20 deletions(-) diff --git a/system/camerad/sensors/ox03c10_cl.h b/system/camerad/sensors/ox03c10_cl.h index 21441902fc..f1fbd16ccb 100644 --- a/system/camerad/sensors/ox03c10_cl.h +++ b/system/camerad/sensors/ox03c10_cl.h @@ -4,28 +4,31 @@ #define BLACK_LVL 64 #define VIGNETTE_RSZ 1.0f -constant float ox03c10_lut[] = { - 0.0000e+00, 5.9488e-08, 1.1898e-07, 1.7846e-07, 2.3795e-07, 2.9744e-07, 3.5693e-07, 4.1642e-07, 4.7591e-07, 5.3539e-07, 5.9488e-07, 6.5437e-07, 7.1386e-07, 7.7335e-07, 8.3284e-07, 8.9232e-07, 9.5181e-07, 1.0113e-06, 1.0708e-06, 1.1303e-06, 1.1898e-06, 1.2493e-06, 1.3087e-06, 1.3682e-06, 1.4277e-06, 1.4872e-06, 1.5467e-06, 1.6062e-06, 1.6657e-06, 1.7252e-06, 1.7846e-06, 1.8441e-06, 1.9036e-06, 1.9631e-06, 2.0226e-06, 2.0821e-06, 2.1416e-06, 2.2011e-06, 2.2606e-06, 2.3200e-06, 2.3795e-06, 2.4390e-06, 2.4985e-06, 2.5580e-06, 2.6175e-06, 2.6770e-06, 2.7365e-06, 2.7959e-06, 2.8554e-06, 2.9149e-06, 2.9744e-06, 3.0339e-06, 3.0934e-06, 3.1529e-06, 3.2124e-06, 3.2719e-06, 3.3313e-06, 3.3908e-06, 3.4503e-06, 3.5098e-06, 3.5693e-06, 3.6288e-06, 3.6883e-06, 3.7478e-06, 3.8072e-06, 3.8667e-06, 3.9262e-06, 3.9857e-06, 4.0452e-06, 4.1047e-06, 4.1642e-06, 4.2237e-06, 4.2832e-06, 4.3426e-06, 4.4021e-06, 4.4616e-06, 4.5211e-06, 4.5806e-06, 4.6401e-06, 4.6996e-06, 4.7591e-06, 4.8185e-06, 4.8780e-06, 4.9375e-06, 4.9970e-06, 5.0565e-06, 5.1160e-06, 5.1755e-06, 5.2350e-06, 5.2945e-06, 5.3539e-06, 5.4134e-06, 5.4729e-06, 5.5324e-06, 5.5919e-06, 5.6514e-06, 5.7109e-06, 5.7704e-06, 5.8298e-06, 5.8893e-06, 5.9488e-06, 6.0083e-06, 6.0678e-06, 6.1273e-06, 6.1868e-06, 6.2463e-06, 6.3058e-06, 6.3652e-06, 6.4247e-06, 6.4842e-06, 6.5437e-06, 6.6032e-06, 6.6627e-06, 6.7222e-06, 6.7817e-06, 6.8411e-06, 6.9006e-06, 6.9601e-06, 7.0196e-06, 7.0791e-06, 7.1386e-06, 7.1981e-06, 7.2576e-06, 7.3171e-06, 7.3765e-06, 7.4360e-06, 7.4955e-06, 7.5550e-06, 7.6145e-06, 7.6740e-06, 7.7335e-06, 7.7930e-06, 7.8524e-06, 7.9119e-06, 7.9714e-06, 8.0309e-06, 8.0904e-06, 8.1499e-06, 8.2094e-06, 8.2689e-06, 8.3284e-06, 8.3878e-06, 8.4473e-06, 8.5068e-06, 8.5663e-06, 8.6258e-06, 8.6853e-06, 8.7448e-06, 8.8043e-06, 8.8637e-06, 8.9232e-06, 8.9827e-06, 9.0422e-06, 9.1017e-06, 9.1612e-06, 9.2207e-06, 9.2802e-06, 9.3397e-06, 9.3991e-06, 9.4586e-06, 9.5181e-06, 9.5776e-06, 9.6371e-06, 9.6966e-06, 9.7561e-06, 9.8156e-06, 9.8750e-06, 9.9345e-06, 9.9940e-06, 1.0054e-05, 1.0113e-05, 1.0172e-05, 1.0232e-05, 1.0291e-05, 1.0351e-05, 1.0410e-05, 1.0470e-05, 1.0529e-05, 1.0589e-05, 1.0648e-05, 1.0708e-05, 1.0767e-05, 1.0827e-05, 1.0886e-05, 1.0946e-05, 1.1005e-05, 1.1065e-05, 1.1124e-05, 1.1184e-05, 1.1243e-05, 1.1303e-05, 1.1362e-05, 1.1422e-05, 1.1481e-05, 1.1541e-05, 1.1600e-05, 1.1660e-05, 1.1719e-05, 1.1779e-05, 1.1838e-05, 1.1898e-05, 1.1957e-05, 1.2017e-05, 1.2076e-05, 1.2136e-05, 1.2195e-05, 1.2255e-05, 1.2314e-05, 1.2374e-05, 1.2433e-05, 1.2493e-05, 1.2552e-05, 1.2612e-05, 1.2671e-05, 1.2730e-05, 1.2790e-05, 1.2849e-05, 1.2909e-05, 1.2968e-05, 1.3028e-05, 1.3087e-05, 1.3147e-05, 1.3206e-05, 1.3266e-05, 1.3325e-05, 1.3385e-05, 1.3444e-05, 1.3504e-05, 1.3563e-05, 1.3623e-05, 1.3682e-05, 1.3742e-05, 1.3801e-05, 1.3861e-05, 1.3920e-05, 1.3980e-05, 1.4039e-05, 1.4099e-05, 1.4158e-05, 1.4218e-05, 1.4277e-05, 1.4337e-05, 1.4396e-05, 1.4456e-05, 1.4515e-05, 1.4575e-05, 1.4634e-05, 1.4694e-05, 1.4753e-05, 1.4813e-05, 1.4872e-05, 1.4932e-05, 1.4991e-05, 1.5051e-05, 1.5110e-05, 1.5169e-05, // NOLINT - 1.5229e-05, 1.5288e-05, 1.5348e-05, 1.5407e-05, 1.5467e-05, 1.5526e-05, 1.5586e-05, 1.5645e-05, 1.5705e-05, 1.5764e-05, 1.5824e-05, 1.5883e-05, 1.5943e-05, 1.6002e-05, 1.6062e-05, 1.6121e-05, 1.6181e-05, 1.6240e-05, 1.6300e-05, 1.6359e-05, 1.6419e-05, 1.6478e-05, 1.6538e-05, 1.6597e-05, 1.6657e-05, 1.6716e-05, 1.6776e-05, 1.6835e-05, 1.6895e-05, 1.6954e-05, 1.7014e-05, 1.7073e-05, 1.7133e-05, 1.7192e-05, 1.7252e-05, 1.7311e-05, 1.7371e-05, 1.7430e-05, 1.7490e-05, 1.7549e-05, 1.7609e-05, 1.7668e-05, 1.7727e-05, 1.7787e-05, 1.7846e-05, 1.7906e-05, 1.7965e-05, 1.8025e-05, 1.8084e-05, 1.8144e-05, 1.8203e-05, 1.8263e-05, 1.8322e-05, 1.8382e-05, 1.8441e-05, 1.8501e-05, 1.8560e-05, 1.8620e-05, 1.8679e-05, 1.8739e-05, 1.8798e-05, 1.8858e-05, 1.8917e-05, 1.8977e-05, 1.9036e-05, 1.9096e-05, 1.9155e-05, 1.9215e-05, 1.9274e-05, 1.9334e-05, 1.9393e-05, 1.9453e-05, 1.9512e-05, 1.9572e-05, 1.9631e-05, 1.9691e-05, 1.9750e-05, 1.9810e-05, 1.9869e-05, 1.9929e-05, 1.9988e-05, 2.0048e-05, 2.0107e-05, 2.0167e-05, 2.0226e-05, 2.0285e-05, 2.0345e-05, 2.0404e-05, 2.0464e-05, 2.0523e-05, 2.0583e-05, 2.0642e-05, 2.0702e-05, 2.0761e-05, 2.0821e-05, 2.0880e-05, 2.0940e-05, 2.0999e-05, 2.1059e-05, 2.1118e-05, 2.1178e-05, 2.1237e-05, 2.1297e-05, 2.1356e-05, 2.1416e-05, 2.1475e-05, 2.1535e-05, 2.1594e-05, 2.1654e-05, 2.1713e-05, 2.1773e-05, 2.1832e-05, 2.1892e-05, 2.1951e-05, 2.2011e-05, 2.2070e-05, 2.2130e-05, 2.2189e-05, 2.2249e-05, 2.2308e-05, 2.2368e-05, 2.2427e-05, 2.2487e-05, 2.2546e-05, 2.2606e-05, 2.2665e-05, 2.2725e-05, 2.2784e-05, 2.2843e-05, 2.2903e-05, 2.2962e-05, 2.3022e-05, 2.3081e-05, 2.3141e-05, 2.3200e-05, 2.3260e-05, 2.3319e-05, 2.3379e-05, 2.3438e-05, 2.3498e-05, 2.3557e-05, 2.3617e-05, 2.3676e-05, 2.3736e-05, 2.3795e-05, 2.3855e-05, 2.3914e-05, 2.3974e-05, 2.4033e-05, 2.4093e-05, 2.4152e-05, 2.4212e-05, 2.4271e-05, 2.4331e-05, 2.4390e-05, 2.4450e-05, 2.4509e-05, 2.4569e-05, 2.4628e-05, 2.4688e-05, 2.4747e-05, 2.4807e-05, 2.4866e-05, 2.4926e-05, 2.4985e-05, 2.5045e-05, 2.5104e-05, 2.5164e-05, 2.5223e-05, 2.5282e-05, 2.5342e-05, 2.5401e-05, 2.5461e-05, 2.5520e-05, 2.5580e-05, 2.5639e-05, 2.5699e-05, 2.5758e-05, 2.5818e-05, 2.5877e-05, 2.5937e-05, 2.5996e-05, 2.6056e-05, 2.6115e-05, 2.6175e-05, 2.6234e-05, 2.6294e-05, 2.6353e-05, 2.6413e-05, 2.6472e-05, 2.6532e-05, 2.6591e-05, 2.6651e-05, 2.6710e-05, 2.6770e-05, 2.6829e-05, 2.6889e-05, 2.6948e-05, 2.7008e-05, 2.7067e-05, 2.7127e-05, 2.7186e-05, 2.7246e-05, 2.7305e-05, 2.7365e-05, 2.7424e-05, 2.7484e-05, 2.7543e-05, 2.7603e-05, 2.7662e-05, 2.7722e-05, 2.7781e-05, 2.7840e-05, 2.7900e-05, 2.7959e-05, 2.8019e-05, 2.8078e-05, 2.8138e-05, 2.8197e-05, 2.8257e-05, 2.8316e-05, 2.8376e-05, 2.8435e-05, 2.8495e-05, 2.8554e-05, 2.8614e-05, 2.8673e-05, 2.8733e-05, 2.8792e-05, 2.8852e-05, 2.8911e-05, 2.8971e-05, 2.9030e-05, 2.9090e-05, 2.9149e-05, 2.9209e-05, 2.9268e-05, 2.9328e-05, 2.9387e-05, 2.9447e-05, 2.9506e-05, 2.9566e-05, 2.9625e-05, 2.9685e-05, 2.9744e-05, 2.9804e-05, 2.9863e-05, 2.9923e-05, 2.9982e-05, 3.0042e-05, 3.0101e-05, 3.0161e-05, 3.0220e-05, 3.0280e-05, 3.0339e-05, 3.0398e-05, // NOLINT - 3.0458e-05, 3.0577e-05, 3.0697e-05, 3.0816e-05, 3.0936e-05, 3.1055e-05, 3.1175e-05, 3.1294e-05, 3.1414e-05, 3.1533e-05, 3.1652e-05, 3.1772e-05, 3.1891e-05, 3.2011e-05, 3.2130e-05, 3.2250e-05, 3.2369e-05, 3.2489e-05, 3.2608e-05, 3.2727e-05, 3.2847e-05, 3.2966e-05, 3.3086e-05, 3.3205e-05, 3.3325e-05, 3.3444e-05, 3.3563e-05, 3.3683e-05, 3.3802e-05, 3.3922e-05, 3.4041e-05, 3.4161e-05, 3.4280e-05, 3.4400e-05, 3.4519e-05, 3.4638e-05, 3.4758e-05, 3.4877e-05, 3.4997e-05, 3.5116e-05, 3.5236e-05, 3.5355e-05, 3.5475e-05, 3.5594e-05, 3.5713e-05, 3.5833e-05, 3.5952e-05, 3.6072e-05, 3.6191e-05, 3.6311e-05, 3.6430e-05, 3.6550e-05, 3.6669e-05, 3.6788e-05, 3.6908e-05, 3.7027e-05, 3.7147e-05, 3.7266e-05, 3.7386e-05, 3.7505e-05, 3.7625e-05, 3.7744e-05, 3.7863e-05, 3.7983e-05, 3.8102e-05, 3.8222e-05, 3.8341e-05, 3.8461e-05, 3.8580e-05, 3.8700e-05, 3.8819e-05, 3.8938e-05, 3.9058e-05, 3.9177e-05, 3.9297e-05, 3.9416e-05, 3.9536e-05, 3.9655e-05, 3.9775e-05, 3.9894e-05, 4.0013e-05, 4.0133e-05, 4.0252e-05, 4.0372e-05, 4.0491e-05, 4.0611e-05, 4.0730e-05, 4.0850e-05, 4.0969e-05, 4.1088e-05, 4.1208e-05, 4.1327e-05, 4.1447e-05, 4.1566e-05, 4.1686e-05, 4.1805e-05, 4.1925e-05, 4.2044e-05, 4.2163e-05, 4.2283e-05, 4.2402e-05, 4.2522e-05, 4.2641e-05, 4.2761e-05, 4.2880e-05, 4.2999e-05, 4.3119e-05, 4.3238e-05, 4.3358e-05, 4.3477e-05, 4.3597e-05, 4.3716e-05, 4.3836e-05, 4.3955e-05, 4.4074e-05, 4.4194e-05, 4.4313e-05, 4.4433e-05, 4.4552e-05, 4.4672e-05, 4.4791e-05, 4.4911e-05, 4.5030e-05, 4.5149e-05, 4.5269e-05, 4.5388e-05, 4.5508e-05, 4.5627e-05, 4.5747e-05, 4.5866e-05, 4.5986e-05, 4.6105e-05, 4.6224e-05, 4.6344e-05, 4.6463e-05, 4.6583e-05, 4.6702e-05, 4.6822e-05, 4.6941e-05, 4.7061e-05, 4.7180e-05, 4.7299e-05, 4.7419e-05, 4.7538e-05, 4.7658e-05, 4.7777e-05, 4.7897e-05, 4.8016e-05, 4.8136e-05, 4.8255e-05, 4.8374e-05, 4.8494e-05, 4.8613e-05, 4.8733e-05, 4.8852e-05, 4.8972e-05, 4.9091e-05, 4.9211e-05, 4.9330e-05, 4.9449e-05, 4.9569e-05, 4.9688e-05, 4.9808e-05, 4.9927e-05, 5.0047e-05, 5.0166e-05, 5.0286e-05, 5.0405e-05, 5.0524e-05, 5.0644e-05, 5.0763e-05, 5.0883e-05, 5.1002e-05, 5.1122e-05, 5.1241e-05, 5.1361e-05, 5.1480e-05, 5.1599e-05, 5.1719e-05, 5.1838e-05, 5.1958e-05, 5.2077e-05, 5.2197e-05, 5.2316e-05, 5.2435e-05, 5.2555e-05, 5.2674e-05, 5.2794e-05, 5.2913e-05, 5.3033e-05, 5.3152e-05, 5.3272e-05, 5.3391e-05, 5.3510e-05, 5.3630e-05, 5.3749e-05, 5.3869e-05, 5.3988e-05, 5.4108e-05, 5.4227e-05, 5.4347e-05, 5.4466e-05, 5.4585e-05, 5.4705e-05, 5.4824e-05, 5.4944e-05, 5.5063e-05, 5.5183e-05, 5.5302e-05, 5.5422e-05, 5.5541e-05, 5.5660e-05, 5.5780e-05, 5.5899e-05, 5.6019e-05, 5.6138e-05, 5.6258e-05, 5.6377e-05, 5.6497e-05, 5.6616e-05, 5.6735e-05, 5.6855e-05, 5.6974e-05, 5.7094e-05, 5.7213e-05, 5.7333e-05, 5.7452e-05, 5.7572e-05, 5.7691e-05, 5.7810e-05, 5.7930e-05, 5.8049e-05, 5.8169e-05, 5.8288e-05, 5.8408e-05, 5.8527e-05, 5.8647e-05, 5.8766e-05, 5.8885e-05, 5.9005e-05, 5.9124e-05, 5.9244e-05, 5.9363e-05, 5.9483e-05, 5.9602e-05, 5.9722e-05, 5.9841e-05, 5.9960e-05, 6.0080e-05, 6.0199e-05, 6.0319e-05, 6.0438e-05, 6.0558e-05, 6.0677e-05, 6.0797e-05, 6.0916e-05, // NOLINT - 6.1154e-05, 6.1392e-05, 6.1631e-05, 6.1869e-05, 6.2107e-05, 6.2345e-05, 6.2583e-05, 6.2821e-05, 6.3060e-05, 6.3298e-05, 6.3536e-05, 6.3774e-05, 6.4012e-05, 6.4251e-05, 6.4489e-05, 6.4727e-05, 6.4965e-05, 6.5203e-05, 6.5441e-05, 6.5680e-05, 6.5918e-05, 6.6156e-05, 6.6394e-05, 6.6632e-05, 6.6871e-05, 6.7109e-05, 6.7347e-05, 6.7585e-05, 6.7823e-05, 6.8062e-05, 6.8300e-05, 6.8538e-05, 6.8776e-05, 6.9014e-05, 6.9252e-05, 6.9491e-05, 6.9729e-05, 6.9967e-05, 7.0205e-05, 7.0443e-05, 7.0682e-05, 7.0920e-05, 7.1158e-05, 7.1396e-05, 7.1634e-05, 7.1872e-05, 7.2111e-05, 7.2349e-05, 7.2587e-05, 7.2825e-05, 7.3063e-05, 7.3302e-05, 7.3540e-05, 7.3778e-05, 7.4016e-05, 7.4254e-05, 7.4493e-05, 7.4731e-05, 7.4969e-05, 7.5207e-05, 7.5445e-05, 7.5683e-05, 7.5922e-05, 7.6160e-05, 7.6398e-05, 7.6636e-05, 7.6874e-05, 7.7113e-05, 7.7351e-05, 7.7589e-05, 7.7827e-05, 7.8065e-05, 7.8304e-05, 7.8542e-05, 7.8780e-05, 7.9018e-05, 7.9256e-05, 7.9494e-05, 7.9733e-05, 7.9971e-05, 8.0209e-05, 8.0447e-05, 8.0685e-05, 8.0924e-05, 8.1162e-05, 8.1400e-05, 8.1638e-05, 8.1876e-05, 8.2114e-05, 8.2353e-05, 8.2591e-05, 8.2829e-05, 8.3067e-05, 8.3305e-05, 8.3544e-05, 8.3782e-05, 8.4020e-05, 8.4258e-05, 8.4496e-05, 8.4735e-05, 8.4973e-05, 8.5211e-05, 8.5449e-05, 8.5687e-05, 8.5925e-05, 8.6164e-05, 8.6402e-05, 8.6640e-05, 8.6878e-05, 8.7116e-05, 8.7355e-05, 8.7593e-05, 8.7831e-05, 8.8069e-05, 8.8307e-05, 8.8545e-05, 8.8784e-05, 8.9022e-05, 8.9260e-05, 8.9498e-05, 8.9736e-05, 8.9975e-05, 9.0213e-05, 9.0451e-05, 9.0689e-05, 9.0927e-05, 9.1166e-05, 9.1404e-05, 9.1642e-05, 9.1880e-05, 9.2118e-05, 9.2356e-05, 9.2595e-05, 9.2833e-05, 9.3071e-05, 9.3309e-05, 9.3547e-05, 9.3786e-05, 9.4024e-05, 9.4262e-05, 9.4500e-05, 9.4738e-05, 9.4977e-05, 9.5215e-05, 9.5453e-05, 9.5691e-05, 9.5929e-05, 9.6167e-05, 9.6406e-05, 9.6644e-05, 9.6882e-05, 9.7120e-05, 9.7358e-05, 9.7597e-05, 9.7835e-05, 9.8073e-05, 9.8311e-05, 9.8549e-05, 9.8787e-05, 9.9026e-05, 9.9264e-05, 9.9502e-05, 9.9740e-05, 9.9978e-05, 1.0022e-04, 1.0045e-04, 1.0069e-04, 1.0093e-04, 1.0117e-04, 1.0141e-04, 1.0165e-04, 1.0188e-04, 1.0212e-04, 1.0236e-04, 1.0260e-04, 1.0284e-04, 1.0307e-04, 1.0331e-04, 1.0355e-04, 1.0379e-04, 1.0403e-04, 1.0427e-04, 1.0450e-04, 1.0474e-04, 1.0498e-04, 1.0522e-04, 1.0546e-04, 1.0569e-04, 1.0593e-04, 1.0617e-04, 1.0641e-04, 1.0665e-04, 1.0689e-04, 1.0712e-04, 1.0736e-04, 1.0760e-04, 1.0784e-04, 1.0808e-04, 1.0831e-04, 1.0855e-04, 1.0879e-04, 1.0903e-04, 1.0927e-04, 1.0951e-04, 1.0974e-04, 1.0998e-04, 1.1022e-04, 1.1046e-04, 1.1070e-04, 1.1093e-04, 1.1117e-04, 1.1141e-04, 1.1165e-04, 1.1189e-04, 1.1213e-04, 1.1236e-04, 1.1260e-04, 1.1284e-04, 1.1308e-04, 1.1332e-04, 1.1355e-04, 1.1379e-04, 1.1403e-04, 1.1427e-04, 1.1451e-04, 1.1475e-04, 1.1498e-04, 1.1522e-04, 1.1546e-04, 1.1570e-04, 1.1594e-04, 1.1618e-04, 1.1641e-04, 1.1665e-04, 1.1689e-04, 1.1713e-04, 1.1737e-04, 1.1760e-04, 1.1784e-04, 1.1808e-04, 1.1832e-04, 1.1856e-04, 1.1880e-04, 1.1903e-04, 1.1927e-04, 1.1951e-04, 1.1975e-04, 1.1999e-04, 1.2022e-04, 1.2046e-04, 1.2070e-04, 1.2094e-04, 1.2118e-04, 1.2142e-04, 1.2165e-04, 1.2189e-04, // NOLINT - 1.2213e-04, 1.2237e-04, 1.2261e-04, 1.2284e-04, 1.2308e-04, 1.2332e-04, 1.2356e-04, 1.2380e-04, 1.2404e-04, 1.2427e-04, 1.2451e-04, 1.2475e-04, 1.2499e-04, 1.2523e-04, 1.2546e-04, 1.2570e-04, 1.2594e-04, 1.2618e-04, 1.2642e-04, 1.2666e-04, 1.2689e-04, 1.2713e-04, 1.2737e-04, 1.2761e-04, 1.2785e-04, 1.2808e-04, 1.2832e-04, 1.2856e-04, 1.2880e-04, 1.2904e-04, 1.2928e-04, 1.2951e-04, 1.2975e-04, 1.2999e-04, 1.3023e-04, 1.3047e-04, 1.3070e-04, 1.3094e-04, 1.3118e-04, 1.3142e-04, 1.3166e-04, 1.3190e-04, 1.3213e-04, 1.3237e-04, 1.3261e-04, 1.3285e-04, 1.3309e-04, 1.3332e-04, 1.3356e-04, 1.3380e-04, 1.3404e-04, 1.3428e-04, 1.3452e-04, 1.3475e-04, 1.3499e-04, 1.3523e-04, 1.3547e-04, 1.3571e-04, 1.3594e-04, 1.3618e-04, 1.3642e-04, 1.3666e-04, 1.3690e-04, 1.3714e-04, 1.3737e-04, 1.3761e-04, 1.3785e-04, 1.3809e-04, 1.3833e-04, 1.3856e-04, 1.3880e-04, 1.3904e-04, 1.3928e-04, 1.3952e-04, 1.3976e-04, 1.3999e-04, 1.4023e-04, 1.4047e-04, 1.4071e-04, 1.4095e-04, 1.4118e-04, 1.4142e-04, 1.4166e-04, 1.4190e-04, 1.4214e-04, 1.4238e-04, 1.4261e-04, 1.4285e-04, 1.4309e-04, 1.4333e-04, 1.4357e-04, 1.4380e-04, 1.4404e-04, 1.4428e-04, 1.4452e-04, 1.4476e-04, 1.4500e-04, 1.4523e-04, 1.4547e-04, 1.4571e-04, 1.4595e-04, 1.4619e-04, 1.4642e-04, 1.4666e-04, 1.4690e-04, 1.4714e-04, 1.4738e-04, 1.4762e-04, 1.4785e-04, 1.4809e-04, 1.4833e-04, 1.4857e-04, 1.4881e-04, 1.4904e-04, 1.4928e-04, 1.4952e-04, 1.4976e-04, 1.5000e-04, 1.5024e-04, 1.5047e-04, 1.5071e-04, 1.5095e-04, 1.5119e-04, 1.5143e-04, 1.5166e-04, 1.5190e-04, 1.5214e-04, 1.5238e-04, 1.5262e-04, 1.5286e-04, 1.5309e-04, 1.5333e-04, 1.5357e-04, 1.5381e-04, 1.5405e-04, 1.5428e-04, 1.5452e-04, 1.5476e-04, 1.5500e-04, 1.5524e-04, 1.5548e-04, 1.5571e-04, 1.5595e-04, 1.5619e-04, 1.5643e-04, 1.5667e-04, 1.5690e-04, 1.5714e-04, 1.5738e-04, 1.5762e-04, 1.5786e-04, 1.5810e-04, 1.5833e-04, 1.5857e-04, 1.5881e-04, 1.5905e-04, 1.5929e-04, 1.5952e-04, 1.5976e-04, 1.6000e-04, 1.6024e-04, 1.6048e-04, 1.6072e-04, 1.6095e-04, 1.6119e-04, 1.6143e-04, 1.6167e-04, 1.6191e-04, 1.6214e-04, 1.6238e-04, 1.6262e-04, 1.6286e-04, 1.6310e-04, 1.6334e-04, 1.6357e-04, 1.6381e-04, 1.6405e-04, 1.6429e-04, 1.6453e-04, 1.6476e-04, 1.6500e-04, 1.6524e-04, 1.6548e-04, 1.6572e-04, 1.6596e-04, 1.6619e-04, 1.6643e-04, 1.6667e-04, 1.6691e-04, 1.6715e-04, 1.6738e-04, 1.6762e-04, 1.6786e-04, 1.6810e-04, 1.6834e-04, 1.6858e-04, 1.6881e-04, 1.6905e-04, 1.6929e-04, 1.6953e-04, 1.6977e-04, 1.7001e-04, 1.7024e-04, 1.7048e-04, 1.7072e-04, 1.7096e-04, 1.7120e-04, 1.7143e-04, 1.7167e-04, 1.7191e-04, 1.7215e-04, 1.7239e-04, 1.7263e-04, 1.7286e-04, 1.7310e-04, 1.7334e-04, 1.7358e-04, 1.7382e-04, 1.7405e-04, 1.7429e-04, 1.7453e-04, 1.7477e-04, 1.7501e-04, 1.7525e-04, 1.7548e-04, 1.7572e-04, 1.7596e-04, 1.7620e-04, 1.7644e-04, 1.7667e-04, 1.7691e-04, 1.7715e-04, 1.7739e-04, 1.7763e-04, 1.7787e-04, 1.7810e-04, 1.7834e-04, 1.7858e-04, 1.7882e-04, 1.7906e-04, 1.7929e-04, 1.7953e-04, 1.7977e-04, 1.8001e-04, 1.8025e-04, 1.8049e-04, 1.8072e-04, 1.8096e-04, 1.8120e-04, 1.8144e-04, 1.8168e-04, 1.8191e-04, 1.8215e-04, 1.8239e-04, 1.8263e-04, 1.8287e-04, // NOLINT - 1.8311e-04, 1.8334e-04, 1.8358e-04, 1.8382e-04, 1.8406e-04, 1.8430e-04, 1.8453e-04, 1.8477e-04, 1.8501e-04, 1.8525e-04, 1.8549e-04, 1.8573e-04, 1.8596e-04, 1.8620e-04, 1.8644e-04, 1.8668e-04, 1.8692e-04, 1.8715e-04, 1.8739e-04, 1.8763e-04, 1.8787e-04, 1.8811e-04, 1.8835e-04, 1.8858e-04, 1.8882e-04, 1.8906e-04, 1.8930e-04, 1.8954e-04, 1.8977e-04, 1.9001e-04, 1.9025e-04, 1.9049e-04, 1.9073e-04, 1.9097e-04, 1.9120e-04, 1.9144e-04, 1.9168e-04, 1.9192e-04, 1.9216e-04, 1.9239e-04, 1.9263e-04, 1.9287e-04, 1.9311e-04, 1.9335e-04, 1.9359e-04, 1.9382e-04, 1.9406e-04, 1.9430e-04, 1.9454e-04, 1.9478e-04, 1.9501e-04, 1.9525e-04, 1.9549e-04, 1.9573e-04, 1.9597e-04, 1.9621e-04, 1.9644e-04, 1.9668e-04, 1.9692e-04, 1.9716e-04, 1.9740e-04, 1.9763e-04, 1.9787e-04, 1.9811e-04, 1.9835e-04, 1.9859e-04, 1.9883e-04, 1.9906e-04, 1.9930e-04, 1.9954e-04, 1.9978e-04, 2.0002e-04, 2.0025e-04, 2.0049e-04, 2.0073e-04, 2.0097e-04, 2.0121e-04, 2.0145e-04, 2.0168e-04, 2.0192e-04, 2.0216e-04, 2.0240e-04, 2.0264e-04, 2.0287e-04, 2.0311e-04, 2.0335e-04, 2.0359e-04, 2.0383e-04, 2.0407e-04, 2.0430e-04, 2.0454e-04, 2.0478e-04, 2.0502e-04, 2.0526e-04, 2.0549e-04, 2.0573e-04, 2.0597e-04, 2.0621e-04, 2.0645e-04, 2.0669e-04, 2.0692e-04, 2.0716e-04, 2.0740e-04, 2.0764e-04, 2.0788e-04, 2.0811e-04, 2.0835e-04, 2.0859e-04, 2.0883e-04, 2.0907e-04, 2.0931e-04, 2.0954e-04, 2.0978e-04, 2.1002e-04, 2.1026e-04, 2.1050e-04, 2.1073e-04, 2.1097e-04, 2.1121e-04, 2.1145e-04, 2.1169e-04, 2.1193e-04, 2.1216e-04, 2.1240e-04, 2.1264e-04, 2.1288e-04, 2.1312e-04, 2.1335e-04, 2.1359e-04, 2.1383e-04, 2.1407e-04, 2.1431e-04, 2.1455e-04, 2.1478e-04, 2.1502e-04, 2.1526e-04, 2.1550e-04, 2.1574e-04, 2.1597e-04, 2.1621e-04, 2.1645e-04, 2.1669e-04, 2.1693e-04, 2.1717e-04, 2.1740e-04, 2.1764e-04, 2.1788e-04, 2.1812e-04, 2.1836e-04, 2.1859e-04, 2.1883e-04, 2.1907e-04, 2.1931e-04, 2.1955e-04, 2.1979e-04, 2.2002e-04, 2.2026e-04, 2.2050e-04, 2.2074e-04, 2.2098e-04, 2.2121e-04, 2.2145e-04, 2.2169e-04, 2.2193e-04, 2.2217e-04, 2.2241e-04, 2.2264e-04, 2.2288e-04, 2.2312e-04, 2.2336e-04, 2.2360e-04, 2.2383e-04, 2.2407e-04, 2.2431e-04, 2.2455e-04, 2.2479e-04, 2.2503e-04, 2.2526e-04, 2.2550e-04, 2.2574e-04, 2.2598e-04, 2.2622e-04, 2.2646e-04, 2.2669e-04, 2.2693e-04, 2.2717e-04, 2.2741e-04, 2.2765e-04, 2.2788e-04, 2.2812e-04, 2.2836e-04, 2.2860e-04, 2.2884e-04, 2.2908e-04, 2.2931e-04, 2.2955e-04, 2.2979e-04, 2.3003e-04, 2.3027e-04, 2.3050e-04, 2.3074e-04, 2.3098e-04, 2.3122e-04, 2.3146e-04, 2.3170e-04, 2.3193e-04, 2.3217e-04, 2.3241e-04, 2.3265e-04, 2.3289e-04, 2.3312e-04, 2.3336e-04, 2.3360e-04, 2.3384e-04, 2.3408e-04, 2.3432e-04, 2.3455e-04, 2.3479e-04, 2.3503e-04, 2.3527e-04, 2.3551e-04, 2.3574e-04, 2.3598e-04, 2.3622e-04, 2.3646e-04, 2.3670e-04, 2.3694e-04, 2.3717e-04, 2.3741e-04, 2.3765e-04, 2.3789e-04, 2.3813e-04, 2.3836e-04, 2.3860e-04, 2.3884e-04, 2.3908e-04, 2.3932e-04, 2.3956e-04, 2.3979e-04, 2.4003e-04, 2.4027e-04, 2.4051e-04, 2.4075e-04, 2.4098e-04, 2.4122e-04, 2.4146e-04, 2.4170e-04, 2.4194e-04, 2.4218e-04, 2.4241e-04, 2.4265e-04, 2.4289e-04, 2.4313e-04, 2.4337e-04, 2.4360e-04, 2.4384e-04, // NOLINT - 2.4480e-04, 2.4575e-04, 2.4670e-04, 2.4766e-04, 2.4861e-04, 2.4956e-04, 2.5052e-04, 2.5147e-04, 2.5242e-04, 2.5337e-04, 2.5433e-04, 2.5528e-04, 2.5623e-04, 2.5719e-04, 2.5814e-04, 2.5909e-04, 2.6005e-04, 2.6100e-04, 2.6195e-04, 2.6291e-04, 2.6386e-04, 2.6481e-04, 2.6577e-04, 2.6672e-04, 2.6767e-04, 2.6863e-04, 2.6958e-04, 2.7053e-04, 2.7149e-04, 2.7244e-04, 2.7339e-04, 2.7435e-04, 2.7530e-04, 2.7625e-04, 2.7720e-04, 2.7816e-04, 2.7911e-04, 2.8006e-04, 2.8102e-04, 2.8197e-04, 2.8292e-04, 2.8388e-04, 2.8483e-04, 2.8578e-04, 2.8674e-04, 2.8769e-04, 2.8864e-04, 2.8960e-04, 2.9055e-04, 2.9150e-04, 2.9246e-04, 2.9341e-04, 2.9436e-04, 2.9532e-04, 2.9627e-04, 2.9722e-04, 2.9818e-04, 2.9913e-04, 3.0008e-04, 3.0104e-04, 3.0199e-04, 3.0294e-04, 3.0389e-04, 3.0485e-04, 3.0580e-04, 3.0675e-04, 3.0771e-04, 3.0866e-04, 3.0961e-04, 3.1057e-04, 3.1152e-04, 3.1247e-04, 3.1343e-04, 3.1438e-04, 3.1533e-04, 3.1629e-04, 3.1724e-04, 3.1819e-04, 3.1915e-04, 3.2010e-04, 3.2105e-04, 3.2201e-04, 3.2296e-04, 3.2391e-04, 3.2487e-04, 3.2582e-04, 3.2677e-04, 3.2772e-04, 3.2868e-04, 3.2963e-04, 3.3058e-04, 3.3154e-04, 3.3249e-04, 3.3344e-04, 3.3440e-04, 3.3535e-04, 3.3630e-04, 3.3726e-04, 3.3821e-04, 3.3916e-04, 3.4012e-04, 3.4107e-04, 3.4202e-04, 3.4298e-04, 3.4393e-04, 3.4488e-04, 3.4584e-04, 3.4679e-04, 3.4774e-04, 3.4870e-04, 3.4965e-04, 3.5060e-04, 3.5156e-04, 3.5251e-04, 3.5346e-04, 3.5441e-04, 3.5537e-04, 3.5632e-04, 3.5727e-04, 3.5823e-04, 3.5918e-04, 3.6013e-04, 3.6109e-04, 3.6204e-04, 3.6299e-04, 3.6395e-04, 3.6490e-04, 3.6585e-04, 3.6681e-04, 3.6776e-04, 3.6871e-04, 3.6967e-04, 3.7062e-04, 3.7157e-04, 3.7253e-04, 3.7348e-04, 3.7443e-04, 3.7539e-04, 3.7634e-04, 3.7729e-04, 3.7825e-04, 3.7920e-04, 3.8015e-04, 3.8110e-04, 3.8206e-04, 3.8301e-04, 3.8396e-04, 3.8492e-04, 3.8587e-04, 3.8682e-04, 3.8778e-04, 3.8873e-04, 3.8968e-04, 3.9064e-04, 3.9159e-04, 3.9254e-04, 3.9350e-04, 3.9445e-04, 3.9540e-04, 3.9636e-04, 3.9731e-04, 3.9826e-04, 3.9922e-04, 4.0017e-04, 4.0112e-04, 4.0208e-04, 4.0303e-04, 4.0398e-04, 4.0493e-04, 4.0589e-04, 4.0684e-04, 4.0779e-04, 4.0875e-04, 4.0970e-04, 4.1065e-04, 4.1161e-04, 4.1256e-04, 4.1351e-04, 4.1447e-04, 4.1542e-04, 4.1637e-04, 4.1733e-04, 4.1828e-04, 4.1923e-04, 4.2019e-04, 4.2114e-04, 4.2209e-04, 4.2305e-04, 4.2400e-04, 4.2495e-04, 4.2591e-04, 4.2686e-04, 4.2781e-04, 4.2877e-04, 4.2972e-04, 4.3067e-04, 4.3162e-04, 4.3258e-04, 4.3353e-04, 4.3448e-04, 4.3544e-04, 4.3639e-04, 4.3734e-04, 4.3830e-04, 4.3925e-04, 4.4020e-04, 4.4116e-04, 4.4211e-04, 4.4306e-04, 4.4402e-04, 4.4497e-04, 4.4592e-04, 4.4688e-04, 4.4783e-04, 4.4878e-04, 4.4974e-04, 4.5069e-04, 4.5164e-04, 4.5260e-04, 4.5355e-04, 4.5450e-04, 4.5545e-04, 4.5641e-04, 4.5736e-04, 4.5831e-04, 4.5927e-04, 4.6022e-04, 4.6117e-04, 4.6213e-04, 4.6308e-04, 4.6403e-04, 4.6499e-04, 4.6594e-04, 4.6689e-04, 4.6785e-04, 4.6880e-04, 4.6975e-04, 4.7071e-04, 4.7166e-04, 4.7261e-04, 4.7357e-04, 4.7452e-04, 4.7547e-04, 4.7643e-04, 4.7738e-04, 4.7833e-04, 4.7929e-04, 4.8024e-04, 4.8119e-04, 4.8214e-04, 4.8310e-04, 4.8405e-04, 4.8500e-04, 4.8596e-04, 4.8691e-04, 4.8786e-04, // NOLINT - 4.8977e-04, 4.9168e-04, 4.9358e-04, 4.9549e-04, 4.9740e-04, 4.9931e-04, 5.0121e-04, 5.0312e-04, 5.0503e-04, 5.0693e-04, 5.0884e-04, 5.1075e-04, 5.1265e-04, 5.1456e-04, 5.1647e-04, 5.1837e-04, 5.2028e-04, 5.2219e-04, 5.2409e-04, 5.2600e-04, 5.2791e-04, 5.2982e-04, 5.3172e-04, 5.3363e-04, 5.3554e-04, 5.3744e-04, 5.3935e-04, 5.4126e-04, 5.4316e-04, 5.4507e-04, 5.4698e-04, 5.4888e-04, 5.5079e-04, 5.5270e-04, 5.5460e-04, 5.5651e-04, 5.5842e-04, 5.6033e-04, 5.6223e-04, 5.6414e-04, 5.6605e-04, 5.6795e-04, 5.6986e-04, 5.7177e-04, 5.7367e-04, 5.7558e-04, 5.7749e-04, 5.7939e-04, 5.8130e-04, 5.8321e-04, 5.8512e-04, 5.8702e-04, 5.8893e-04, 5.9084e-04, 5.9274e-04, 5.9465e-04, 5.9656e-04, 5.9846e-04, 6.0037e-04, 6.0228e-04, 6.0418e-04, 6.0609e-04, 6.0800e-04, 6.0990e-04, 6.1181e-04, 6.1372e-04, 6.1563e-04, 6.1753e-04, 6.1944e-04, 6.2135e-04, 6.2325e-04, 6.2516e-04, 6.2707e-04, 6.2897e-04, 6.3088e-04, 6.3279e-04, 6.3469e-04, 6.3660e-04, 6.3851e-04, 6.4041e-04, 6.4232e-04, 6.4423e-04, 6.4614e-04, 6.4804e-04, 6.4995e-04, 6.5186e-04, 6.5376e-04, 6.5567e-04, 6.5758e-04, 6.5948e-04, 6.6139e-04, 6.6330e-04, 6.6520e-04, 6.6711e-04, 6.6902e-04, 6.7092e-04, 6.7283e-04, 6.7474e-04, 6.7665e-04, 6.7855e-04, 6.8046e-04, 6.8237e-04, 6.8427e-04, 6.8618e-04, 6.8809e-04, 6.8999e-04, 6.9190e-04, 6.9381e-04, 6.9571e-04, 6.9762e-04, 6.9953e-04, 7.0143e-04, 7.0334e-04, 7.0525e-04, 7.0716e-04, 7.0906e-04, 7.1097e-04, 7.1288e-04, 7.1478e-04, 7.1669e-04, 7.1860e-04, 7.2050e-04, 7.2241e-04, 7.2432e-04, 7.2622e-04, 7.2813e-04, 7.3004e-04, 7.3195e-04, 7.3385e-04, 7.3576e-04, 7.3767e-04, 7.3957e-04, 7.4148e-04, 7.4339e-04, 7.4529e-04, 7.4720e-04, 7.4911e-04, 7.5101e-04, 7.5292e-04, 7.5483e-04, 7.5673e-04, 7.5864e-04, 7.6055e-04, 7.6246e-04, 7.6436e-04, 7.6627e-04, 7.6818e-04, 7.7008e-04, 7.7199e-04, 7.7390e-04, 7.7580e-04, 7.7771e-04, 7.7962e-04, 7.8152e-04, 7.8343e-04, 7.8534e-04, 7.8724e-04, 7.8915e-04, 7.9106e-04, 7.9297e-04, 7.9487e-04, 7.9678e-04, 7.9869e-04, 8.0059e-04, 8.0250e-04, 8.0441e-04, 8.0631e-04, 8.0822e-04, 8.1013e-04, 8.1203e-04, 8.1394e-04, 8.1585e-04, 8.1775e-04, 8.1966e-04, 8.2157e-04, 8.2348e-04, 8.2538e-04, 8.2729e-04, 8.2920e-04, 8.3110e-04, 8.3301e-04, 8.3492e-04, 8.3682e-04, 8.3873e-04, 8.4064e-04, 8.4254e-04, 8.4445e-04, 8.4636e-04, 8.4826e-04, 8.5017e-04, 8.5208e-04, 8.5399e-04, 8.5589e-04, 8.5780e-04, 8.5971e-04, 8.6161e-04, 8.6352e-04, 8.6543e-04, 8.6733e-04, 8.6924e-04, 8.7115e-04, 8.7305e-04, 8.7496e-04, 8.7687e-04, 8.7878e-04, 8.8068e-04, 8.8259e-04, 8.8450e-04, 8.8640e-04, 8.8831e-04, 8.9022e-04, 8.9212e-04, 8.9403e-04, 8.9594e-04, 8.9784e-04, 8.9975e-04, 9.0166e-04, 9.0356e-04, 9.0547e-04, 9.0738e-04, 9.0929e-04, 9.1119e-04, 9.1310e-04, 9.1501e-04, 9.1691e-04, 9.1882e-04, 9.2073e-04, 9.2263e-04, 9.2454e-04, 9.2645e-04, 9.2835e-04, 9.3026e-04, 9.3217e-04, 9.3407e-04, 9.3598e-04, 9.3789e-04, 9.3980e-04, 9.4170e-04, 9.4361e-04, 9.4552e-04, 9.4742e-04, 9.4933e-04, 9.5124e-04, 9.5314e-04, 9.5505e-04, 9.5696e-04, 9.5886e-04, 9.6077e-04, 9.6268e-04, 9.6458e-04, 9.6649e-04, 9.6840e-04, 9.7031e-04, 9.7221e-04, 9.7412e-04, 9.7603e-04, // NOLINT - 9.7984e-04, 9.8365e-04, 9.8747e-04, 9.9128e-04, 9.9510e-04, 9.9891e-04, 1.0027e-03, 1.0065e-03, 1.0104e-03, 1.0142e-03, 1.0180e-03, 1.0218e-03, 1.0256e-03, 1.0294e-03, 1.0332e-03, 1.0371e-03, 1.0409e-03, 1.0447e-03, 1.0485e-03, 1.0523e-03, 1.0561e-03, 1.0599e-03, 1.0638e-03, 1.0676e-03, 1.0714e-03, 1.0752e-03, 1.0790e-03, 1.0828e-03, 1.0866e-03, 1.0905e-03, 1.0943e-03, 1.0981e-03, 1.1019e-03, 1.1057e-03, 1.1095e-03, 1.1133e-03, 1.1172e-03, 1.1210e-03, 1.1248e-03, 1.1286e-03, 1.1324e-03, 1.1362e-03, 1.1400e-03, 1.1439e-03, 1.1477e-03, 1.1515e-03, 1.1553e-03, 1.1591e-03, 1.1629e-03, 1.1667e-03, 1.1706e-03, 1.1744e-03, 1.1782e-03, 1.1820e-03, 1.1858e-03, 1.1896e-03, 1.1934e-03, 1.1973e-03, 1.2011e-03, 1.2049e-03, 1.2087e-03, 1.2125e-03, 1.2163e-03, 1.2201e-03, 1.2240e-03, 1.2278e-03, 1.2316e-03, 1.2354e-03, 1.2392e-03, 1.2430e-03, 1.2468e-03, 1.2507e-03, 1.2545e-03, 1.2583e-03, 1.2621e-03, 1.2659e-03, 1.2697e-03, 1.2735e-03, 1.2774e-03, 1.2812e-03, 1.2850e-03, 1.2888e-03, 1.2926e-03, 1.2964e-03, 1.3002e-03, 1.3040e-03, 1.3079e-03, 1.3117e-03, 1.3155e-03, 1.3193e-03, 1.3231e-03, 1.3269e-03, 1.3307e-03, 1.3346e-03, 1.3384e-03, 1.3422e-03, 1.3460e-03, 1.3498e-03, 1.3536e-03, 1.3574e-03, 1.3613e-03, 1.3651e-03, 1.3689e-03, 1.3727e-03, 1.3765e-03, 1.3803e-03, 1.3841e-03, 1.3880e-03, 1.3918e-03, 1.3956e-03, 1.3994e-03, 1.4032e-03, 1.4070e-03, 1.4108e-03, 1.4147e-03, 1.4185e-03, 1.4223e-03, 1.4261e-03, 1.4299e-03, 1.4337e-03, 1.4375e-03, 1.4414e-03, 1.4452e-03, 1.4490e-03, 1.4528e-03, 1.4566e-03, 1.4604e-03, 1.4642e-03, 1.4681e-03, 1.4719e-03, 1.4757e-03, 1.4795e-03, 1.4833e-03, 1.4871e-03, 1.4909e-03, 1.4948e-03, 1.4986e-03, 1.5024e-03, 1.5062e-03, 1.5100e-03, 1.5138e-03, 1.5176e-03, 1.5215e-03, 1.5253e-03, 1.5291e-03, 1.5329e-03, 1.5367e-03, 1.5405e-03, 1.5443e-03, 1.5482e-03, 1.5520e-03, 1.5558e-03, 1.5596e-03, 1.5634e-03, 1.5672e-03, 1.5710e-03, 1.5749e-03, 1.5787e-03, 1.5825e-03, 1.5863e-03, 1.5901e-03, 1.5939e-03, 1.5977e-03, 1.6016e-03, 1.6054e-03, 1.6092e-03, 1.6130e-03, 1.6168e-03, 1.6206e-03, 1.6244e-03, 1.6283e-03, 1.6321e-03, 1.6359e-03, 1.6397e-03, 1.6435e-03, 1.6473e-03, 1.6511e-03, 1.6550e-03, 1.6588e-03, 1.6626e-03, 1.6664e-03, 1.6702e-03, 1.6740e-03, 1.6778e-03, 1.6817e-03, 1.6855e-03, 1.6893e-03, 1.6931e-03, 1.6969e-03, 1.7007e-03, 1.7045e-03, 1.7084e-03, 1.7122e-03, 1.7160e-03, 1.7198e-03, 1.7236e-03, 1.7274e-03, 1.7312e-03, 1.7351e-03, 1.7389e-03, 1.7427e-03, 1.7465e-03, 1.7503e-03, 1.7541e-03, 1.7579e-03, 1.7618e-03, 1.7656e-03, 1.7694e-03, 1.7732e-03, 1.7770e-03, 1.7808e-03, 1.7846e-03, 1.7885e-03, 1.7923e-03, 1.7961e-03, 1.7999e-03, 1.8037e-03, 1.8075e-03, 1.8113e-03, 1.8152e-03, 1.8190e-03, 1.8228e-03, 1.8266e-03, 1.8304e-03, 1.8342e-03, 1.8380e-03, 1.8419e-03, 1.8457e-03, 1.8495e-03, 1.8533e-03, 1.8571e-03, 1.8609e-03, 1.8647e-03, 1.8686e-03, 1.8724e-03, 1.8762e-03, 1.8800e-03, 1.8838e-03, 1.8876e-03, 1.8914e-03, 1.8953e-03, 1.8991e-03, 1.9029e-03, 1.9067e-03, 1.9105e-03, 1.9143e-03, 1.9181e-03, 1.9220e-03, 1.9258e-03, 1.9296e-03, 1.9334e-03, 1.9372e-03, 1.9410e-03, 1.9448e-03, 1.9487e-03, 1.9525e-03, // NOLINT - 1.9601e-03, 1.9677e-03, 1.9754e-03, 1.9830e-03, 1.9906e-03, 1.9982e-03, 2.0059e-03, 2.0135e-03, 2.0211e-03, 2.0288e-03, 2.0364e-03, 2.0440e-03, 2.0516e-03, 2.0593e-03, 2.0669e-03, 2.0745e-03, 2.0822e-03, 2.0898e-03, 2.0974e-03, 2.1050e-03, 2.1127e-03, 2.1203e-03, 2.1279e-03, 2.1356e-03, 2.1432e-03, 2.1508e-03, 2.1585e-03, 2.1661e-03, 2.1737e-03, 2.1813e-03, 2.1890e-03, 2.1966e-03, 2.2042e-03, 2.2119e-03, 2.2195e-03, 2.2271e-03, 2.2347e-03, 2.2424e-03, 2.2500e-03, 2.2576e-03, 2.2653e-03, 2.2729e-03, 2.2805e-03, 2.2881e-03, 2.2958e-03, 2.3034e-03, 2.3110e-03, 2.3187e-03, 2.3263e-03, 2.3339e-03, 2.3415e-03, 2.3492e-03, 2.3568e-03, 2.3644e-03, 2.3721e-03, 2.3797e-03, 2.3873e-03, 2.3949e-03, 2.4026e-03, 2.4102e-03, 2.4178e-03, 2.4255e-03, 2.4331e-03, 2.4407e-03, 2.4483e-03, 2.4560e-03, 2.4636e-03, 2.4712e-03, 2.4789e-03, 2.4865e-03, 2.4941e-03, 2.5018e-03, 2.5094e-03, 2.5170e-03, 2.5246e-03, 2.5323e-03, 2.5399e-03, 2.5475e-03, 2.5552e-03, 2.5628e-03, 2.5704e-03, 2.5780e-03, 2.5857e-03, 2.5933e-03, 2.6009e-03, 2.6086e-03, 2.6162e-03, 2.6238e-03, 2.6314e-03, 2.6391e-03, 2.6467e-03, 2.6543e-03, 2.6620e-03, 2.6696e-03, 2.6772e-03, 2.6848e-03, 2.6925e-03, 2.7001e-03, 2.7077e-03, 2.7154e-03, 2.7230e-03, 2.7306e-03, 2.7382e-03, 2.7459e-03, 2.7535e-03, 2.7611e-03, 2.7688e-03, 2.7764e-03, 2.7840e-03, 2.7917e-03, 2.7993e-03, 2.8069e-03, 2.8145e-03, 2.8222e-03, 2.8298e-03, 2.8374e-03, 2.8451e-03, 2.8527e-03, 2.8603e-03, 2.8679e-03, 2.8756e-03, 2.8832e-03, 2.8908e-03, 2.8985e-03, 2.9061e-03, 2.9137e-03, 2.9213e-03, 2.9290e-03, 2.9366e-03, 2.9442e-03, 2.9519e-03, 2.9595e-03, 2.9671e-03, 2.9747e-03, 2.9824e-03, 2.9900e-03, 2.9976e-03, 3.0053e-03, 3.0129e-03, 3.0205e-03, 3.0281e-03, 3.0358e-03, 3.0434e-03, 3.0510e-03, 3.0587e-03, 3.0663e-03, 3.0739e-03, 3.0816e-03, 3.0892e-03, 3.0968e-03, 3.1044e-03, 3.1121e-03, 3.1197e-03, 3.1273e-03, 3.1350e-03, 3.1426e-03, 3.1502e-03, 3.1578e-03, 3.1655e-03, 3.1731e-03, 3.1807e-03, 3.1884e-03, 3.1960e-03, 3.2036e-03, 3.2112e-03, 3.2189e-03, 3.2265e-03, 3.2341e-03, 3.2418e-03, 3.2494e-03, 3.2570e-03, 3.2646e-03, 3.2723e-03, 3.2799e-03, 3.2875e-03, 3.2952e-03, 3.3028e-03, 3.3104e-03, 3.3180e-03, 3.3257e-03, 3.3333e-03, 3.3409e-03, 3.3486e-03, 3.3562e-03, 3.3638e-03, 3.3715e-03, 3.3791e-03, 3.3867e-03, 3.3943e-03, 3.4020e-03, 3.4096e-03, 3.4172e-03, 3.4249e-03, 3.4325e-03, 3.4401e-03, 3.4477e-03, 3.4554e-03, 3.4630e-03, 3.4706e-03, 3.4783e-03, 3.4859e-03, 3.4935e-03, 3.5011e-03, 3.5088e-03, 3.5164e-03, 3.5240e-03, 3.5317e-03, 3.5393e-03, 3.5469e-03, 3.5545e-03, 3.5622e-03, 3.5698e-03, 3.5774e-03, 3.5851e-03, 3.5927e-03, 3.6003e-03, 3.6079e-03, 3.6156e-03, 3.6232e-03, 3.6308e-03, 3.6385e-03, 3.6461e-03, 3.6537e-03, 3.6613e-03, 3.6690e-03, 3.6766e-03, 3.6842e-03, 3.6919e-03, 3.6995e-03, 3.7071e-03, 3.7148e-03, 3.7224e-03, 3.7300e-03, 3.7376e-03, 3.7453e-03, 3.7529e-03, 3.7605e-03, 3.7682e-03, 3.7758e-03, 3.7834e-03, 3.7910e-03, 3.7987e-03, 3.8063e-03, 3.8139e-03, 3.8216e-03, 3.8292e-03, 3.8368e-03, 3.8444e-03, 3.8521e-03, 3.8597e-03, 3.8673e-03, 3.8750e-03, 3.8826e-03, 3.8902e-03, 3.8978e-03, 3.9055e-03, // NOLINT - 3.9207e-03, 3.9360e-03, 3.9513e-03, 3.9665e-03, 3.9818e-03, 3.9970e-03, 4.0123e-03, 4.0275e-03, 4.0428e-03, 4.0581e-03, 4.0733e-03, 4.0886e-03, 4.1038e-03, 4.1191e-03, 4.1343e-03, 4.1496e-03, 4.1649e-03, 4.1801e-03, 4.1954e-03, 4.2106e-03, 4.2259e-03, 4.2412e-03, 4.2564e-03, 4.2717e-03, 4.2869e-03, 4.3022e-03, 4.3174e-03, 4.3327e-03, 4.3480e-03, 4.3632e-03, 4.3785e-03, 4.3937e-03, 4.4090e-03, 4.4243e-03, 4.4395e-03, 4.4548e-03, 4.4700e-03, 4.4853e-03, 4.5005e-03, 4.5158e-03, 4.5311e-03, 4.5463e-03, 4.5616e-03, 4.5768e-03, 4.5921e-03, 4.6074e-03, 4.6226e-03, 4.6379e-03, 4.6531e-03, 4.6684e-03, 4.6836e-03, 4.6989e-03, 4.7142e-03, 4.7294e-03, 4.7447e-03, 4.7599e-03, 4.7752e-03, 4.7905e-03, 4.8057e-03, 4.8210e-03, 4.8362e-03, 4.8515e-03, 4.8667e-03, 4.8820e-03, 4.8973e-03, 4.9125e-03, 4.9278e-03, 4.9430e-03, 4.9583e-03, 4.9736e-03, 4.9888e-03, 5.0041e-03, 5.0193e-03, 5.0346e-03, 5.0498e-03, 5.0651e-03, 5.0804e-03, 5.0956e-03, 5.1109e-03, 5.1261e-03, 5.1414e-03, 5.1567e-03, 5.1719e-03, 5.1872e-03, 5.2024e-03, 5.2177e-03, 5.2329e-03, 5.2482e-03, 5.2635e-03, 5.2787e-03, 5.2940e-03, 5.3092e-03, 5.3245e-03, 5.3398e-03, 5.3550e-03, 5.3703e-03, 5.3855e-03, 5.4008e-03, 5.4160e-03, 5.4313e-03, 5.4466e-03, 5.4618e-03, 5.4771e-03, 5.4923e-03, 5.5076e-03, 5.5229e-03, 5.5381e-03, 5.5534e-03, 5.5686e-03, 5.5839e-03, 5.5991e-03, 5.6144e-03, 5.6297e-03, 5.6449e-03, 5.6602e-03, 5.6754e-03, 5.6907e-03, 5.7060e-03, 5.7212e-03, 5.7365e-03, 5.7517e-03, 5.7670e-03, 5.7822e-03, 5.7975e-03, 5.8128e-03, 5.8280e-03, 5.8433e-03, 5.8585e-03, 5.8738e-03, 5.8891e-03, 5.9043e-03, 5.9196e-03, 5.9348e-03, 5.9501e-03, 5.9653e-03, 5.9806e-03, 5.9959e-03, 6.0111e-03, 6.0264e-03, 6.0416e-03, 6.0569e-03, 6.0722e-03, 6.0874e-03, 6.1027e-03, 6.1179e-03, 6.1332e-03, 6.1484e-03, 6.1637e-03, 6.1790e-03, 6.1942e-03, 6.2095e-03, 6.2247e-03, 6.2400e-03, 6.2553e-03, 6.2705e-03, 6.2858e-03, 6.3010e-03, 6.3163e-03, 6.3315e-03, 6.3468e-03, 6.3621e-03, 6.3773e-03, 6.3926e-03, 6.4078e-03, 6.4231e-03, 6.4384e-03, 6.4536e-03, 6.4689e-03, 6.4841e-03, 6.4994e-03, 6.5146e-03, 6.5299e-03, 6.5452e-03, 6.5604e-03, 6.5757e-03, 6.5909e-03, 6.6062e-03, 6.6215e-03, 6.6367e-03, 6.6520e-03, 6.6672e-03, 6.6825e-03, 6.6977e-03, 6.7130e-03, 6.7283e-03, 6.7435e-03, 6.7588e-03, 6.7740e-03, 6.7893e-03, 6.8046e-03, 6.8198e-03, 6.8351e-03, 6.8503e-03, 6.8656e-03, 6.8808e-03, 6.8961e-03, 6.9114e-03, 6.9266e-03, 6.9419e-03, 6.9571e-03, 6.9724e-03, 6.9877e-03, 7.0029e-03, 7.0182e-03, 7.0334e-03, 7.0487e-03, 7.0639e-03, 7.0792e-03, 7.0945e-03, 7.1097e-03, 7.1250e-03, 7.1402e-03, 7.1555e-03, 7.1708e-03, 7.1860e-03, 7.2013e-03, 7.2165e-03, 7.2318e-03, 7.2470e-03, 7.2623e-03, 7.2776e-03, 7.2928e-03, 7.3081e-03, 7.3233e-03, 7.3386e-03, 7.3539e-03, 7.3691e-03, 7.3844e-03, 7.3996e-03, 7.4149e-03, 7.4301e-03, 7.4454e-03, 7.4607e-03, 7.4759e-03, 7.4912e-03, 7.5064e-03, 7.5217e-03, 7.5370e-03, 7.5522e-03, 7.5675e-03, 7.5827e-03, 7.5980e-03, 7.6132e-03, 7.6285e-03, 7.6438e-03, 7.6590e-03, 7.6743e-03, 7.6895e-03, 7.7048e-03, 7.7201e-03, 7.7353e-03, 7.7506e-03, 7.7658e-03, 7.7811e-03, 7.7963e-03, 7.8116e-03, // NOLINT - 7.8421e-03, 7.8726e-03, 7.9032e-03, 7.9337e-03, 7.9642e-03, 7.9947e-03, 8.0252e-03, 8.0557e-03, 8.0863e-03, 8.1168e-03, 8.1473e-03, 8.1778e-03, 8.2083e-03, 8.2388e-03, 8.2694e-03, 8.2999e-03, 8.3304e-03, 8.3609e-03, 8.3914e-03, 8.4219e-03, 8.4525e-03, 8.4830e-03, 8.5135e-03, 8.5440e-03, 8.5745e-03, 8.6051e-03, 8.6356e-03, 8.6661e-03, 8.6966e-03, 8.7271e-03, 8.7576e-03, 8.7882e-03, 8.8187e-03, 8.8492e-03, 8.8797e-03, 8.9102e-03, 8.9407e-03, 8.9713e-03, 9.0018e-03, 9.0323e-03, 9.0628e-03, 9.0933e-03, 9.1238e-03, 9.1544e-03, 9.1849e-03, 9.2154e-03, 9.2459e-03, 9.2764e-03, 9.3069e-03, 9.3375e-03, 9.3680e-03, 9.3985e-03, 9.4290e-03, 9.4595e-03, 9.4900e-03, 9.5206e-03, 9.5511e-03, 9.5816e-03, 9.6121e-03, 9.6426e-03, 9.6731e-03, 9.7037e-03, 9.7342e-03, 9.7647e-03, 9.7952e-03, 9.8257e-03, 9.8563e-03, 9.8868e-03, 9.9173e-03, 9.9478e-03, 9.9783e-03, 1.0009e-02, 1.0039e-02, 1.0070e-02, 1.0100e-02, 1.0131e-02, 1.0161e-02, 1.0192e-02, 1.0222e-02, 1.0253e-02, 1.0283e-02, 1.0314e-02, 1.0345e-02, 1.0375e-02, 1.0406e-02, 1.0436e-02, 1.0467e-02, 1.0497e-02, 1.0528e-02, 1.0558e-02, 1.0589e-02, 1.0619e-02, 1.0650e-02, 1.0680e-02, 1.0711e-02, 1.0741e-02, 1.0772e-02, 1.0802e-02, 1.0833e-02, 1.0863e-02, 1.0894e-02, 1.0924e-02, 1.0955e-02, 1.0985e-02, 1.1016e-02, 1.1046e-02, 1.1077e-02, 1.1107e-02, 1.1138e-02, 1.1168e-02, 1.1199e-02, 1.1230e-02, 1.1260e-02, 1.1291e-02, 1.1321e-02, 1.1352e-02, 1.1382e-02, 1.1413e-02, 1.1443e-02, 1.1474e-02, 1.1504e-02, 1.1535e-02, 1.1565e-02, 1.1596e-02, 1.1626e-02, 1.1657e-02, 1.1687e-02, 1.1718e-02, 1.1748e-02, 1.1779e-02, 1.1809e-02, 1.1840e-02, 1.1870e-02, 1.1901e-02, 1.1931e-02, 1.1962e-02, 1.1992e-02, 1.2023e-02, 1.2053e-02, 1.2084e-02, 1.2115e-02, 1.2145e-02, 1.2176e-02, 1.2206e-02, 1.2237e-02, 1.2267e-02, 1.2298e-02, 1.2328e-02, 1.2359e-02, 1.2389e-02, 1.2420e-02, 1.2450e-02, 1.2481e-02, 1.2511e-02, 1.2542e-02, 1.2572e-02, 1.2603e-02, 1.2633e-02, 1.2664e-02, 1.2694e-02, 1.2725e-02, 1.2755e-02, 1.2786e-02, 1.2816e-02, 1.2847e-02, 1.2877e-02, 1.2908e-02, 1.2938e-02, 1.2969e-02, 1.3000e-02, 1.3030e-02, 1.3061e-02, 1.3091e-02, 1.3122e-02, 1.3152e-02, 1.3183e-02, 1.3213e-02, 1.3244e-02, 1.3274e-02, 1.3305e-02, 1.3335e-02, 1.3366e-02, 1.3396e-02, 1.3427e-02, 1.3457e-02, 1.3488e-02, 1.3518e-02, 1.3549e-02, 1.3579e-02, 1.3610e-02, 1.3640e-02, 1.3671e-02, 1.3701e-02, 1.3732e-02, 1.3762e-02, 1.3793e-02, 1.3823e-02, 1.3854e-02, 1.3885e-02, 1.3915e-02, 1.3946e-02, 1.3976e-02, 1.4007e-02, 1.4037e-02, 1.4068e-02, 1.4098e-02, 1.4129e-02, 1.4159e-02, 1.4190e-02, 1.4220e-02, 1.4251e-02, 1.4281e-02, 1.4312e-02, 1.4342e-02, 1.4373e-02, 1.4403e-02, 1.4434e-02, 1.4464e-02, 1.4495e-02, 1.4525e-02, 1.4556e-02, 1.4586e-02, 1.4617e-02, 1.4647e-02, 1.4678e-02, 1.4708e-02, 1.4739e-02, 1.4770e-02, 1.4800e-02, 1.4831e-02, 1.4861e-02, 1.4892e-02, 1.4922e-02, 1.4953e-02, 1.4983e-02, 1.5014e-02, 1.5044e-02, 1.5075e-02, 1.5105e-02, 1.5136e-02, 1.5166e-02, 1.5197e-02, 1.5227e-02, 1.5258e-02, 1.5288e-02, 1.5319e-02, 1.5349e-02, 1.5380e-02, 1.5410e-02, 1.5441e-02, 1.5471e-02, 1.5502e-02, 1.5532e-02, 1.5563e-02, 1.5593e-02, 1.5624e-02, // NOLINT - 1.5746e-02, 1.5868e-02, 1.5990e-02, 1.6112e-02, 1.6234e-02, 1.6356e-02, 1.6478e-02, 1.6601e-02, 1.6723e-02, 1.6845e-02, 1.6967e-02, 1.7089e-02, 1.7211e-02, 1.7333e-02, 1.7455e-02, 1.7577e-02, 1.7699e-02, 1.7821e-02, 1.7943e-02, 1.8065e-02, 1.8187e-02, 1.8310e-02, 1.8432e-02, 1.8554e-02, 1.8676e-02, 1.8798e-02, 1.8920e-02, 1.9042e-02, 1.9164e-02, 1.9286e-02, 1.9408e-02, 1.9530e-02, 1.9652e-02, 1.9774e-02, 1.9896e-02, 2.0018e-02, 2.0141e-02, 2.0263e-02, 2.0385e-02, 2.0507e-02, 2.0629e-02, 2.0751e-02, 2.0873e-02, 2.0995e-02, 2.1117e-02, 2.1239e-02, 2.1361e-02, 2.1483e-02, 2.1605e-02, 2.1727e-02, 2.1850e-02, 2.1972e-02, 2.2094e-02, 2.2216e-02, 2.2338e-02, 2.2460e-02, 2.2582e-02, 2.2704e-02, 2.2826e-02, 2.2948e-02, 2.3070e-02, 2.3192e-02, 2.3314e-02, 2.3436e-02, 2.3558e-02, 2.3681e-02, 2.3803e-02, 2.3925e-02, 2.4047e-02, 2.4169e-02, 2.4291e-02, 2.4413e-02, 2.4535e-02, 2.4657e-02, 2.4779e-02, 2.4901e-02, 2.5023e-02, 2.5145e-02, 2.5267e-02, 2.5390e-02, 2.5512e-02, 2.5634e-02, 2.5756e-02, 2.5878e-02, 2.6000e-02, 2.6122e-02, 2.6244e-02, 2.6366e-02, 2.6488e-02, 2.6610e-02, 2.6732e-02, 2.6854e-02, 2.6976e-02, 2.7099e-02, 2.7221e-02, 2.7343e-02, 2.7465e-02, 2.7587e-02, 2.7709e-02, 2.7831e-02, 2.7953e-02, 2.8075e-02, 2.8197e-02, 2.8319e-02, 2.8441e-02, 2.8563e-02, 2.8685e-02, 2.8807e-02, 2.8930e-02, 2.9052e-02, 2.9174e-02, 2.9296e-02, 2.9418e-02, 2.9540e-02, 2.9662e-02, 2.9784e-02, 2.9906e-02, 3.0028e-02, 3.0150e-02, 3.0272e-02, 3.0394e-02, 3.0516e-02, 3.0639e-02, 3.0761e-02, 3.0883e-02, 3.1005e-02, 3.1127e-02, 3.1249e-02, 3.1493e-02, 3.1737e-02, 3.1981e-02, 3.2225e-02, 3.2470e-02, 3.2714e-02, 3.2958e-02, 3.3202e-02, 3.3446e-02, 3.3690e-02, 3.3934e-02, 3.4179e-02, 3.4423e-02, 3.4667e-02, 3.4911e-02, 3.5155e-02, 3.5399e-02, 3.5643e-02, 3.5888e-02, 3.6132e-02, 3.6376e-02, 3.6620e-02, 3.6864e-02, 3.7108e-02, 3.7352e-02, 3.7596e-02, 3.7841e-02, 3.8085e-02, 3.8329e-02, 3.8573e-02, 3.8817e-02, 3.9061e-02, 3.9305e-02, 3.9550e-02, 3.9794e-02, 4.0038e-02, 4.0282e-02, 4.0526e-02, 4.0770e-02, 4.1014e-02, 4.1259e-02, 4.1503e-02, 4.1747e-02, 4.1991e-02, 4.2235e-02, 4.2479e-02, 4.2723e-02, 4.2968e-02, 4.3212e-02, 4.3456e-02, 4.3700e-02, 4.3944e-02, 4.4188e-02, 4.4432e-02, 4.4677e-02, 4.4921e-02, 4.5165e-02, 4.5409e-02, 4.5653e-02, 4.5897e-02, 4.6141e-02, 4.6386e-02, 4.6630e-02, 4.6874e-02, 4.7118e-02, 4.7362e-02, 4.7606e-02, 4.7850e-02, 4.8095e-02, 4.8339e-02, 4.8583e-02, 4.8827e-02, 4.9071e-02, 4.9315e-02, 4.9559e-02, 4.9803e-02, 5.0048e-02, 5.0292e-02, 5.0536e-02, 5.0780e-02, 5.1024e-02, 5.1268e-02, 5.1512e-02, 5.1757e-02, 5.2001e-02, 5.2245e-02, 5.2489e-02, 5.2733e-02, 5.2977e-02, 5.3221e-02, 5.3466e-02, 5.3710e-02, 5.3954e-02, 5.4198e-02, 5.4442e-02, 5.4686e-02, 5.4930e-02, 5.5175e-02, 5.5419e-02, 5.5663e-02, 5.5907e-02, 5.6151e-02, 5.6395e-02, 5.6639e-02, 5.6884e-02, 5.7128e-02, 5.7372e-02, 5.7616e-02, 5.7860e-02, 5.8104e-02, 5.8348e-02, 5.8593e-02, 5.8837e-02, 5.9081e-02, 5.9325e-02, 5.9569e-02, 5.9813e-02, 6.0057e-02, 6.0301e-02, 6.0546e-02, 6.0790e-02, 6.1034e-02, 6.1278e-02, 6.1522e-02, 6.1766e-02, 6.2010e-02, 6.2255e-02, 6.2499e-02, // NOLINT - 6.2743e-02, 6.2987e-02, 6.3231e-02, 6.3475e-02, 6.3719e-02, 6.3964e-02, 6.4208e-02, 6.4452e-02, 6.4696e-02, 6.4940e-02, 6.5184e-02, 6.5428e-02, 6.5673e-02, 6.5917e-02, 6.6161e-02, 6.6405e-02, 6.6649e-02, 6.6893e-02, 6.7137e-02, 6.7382e-02, 6.7626e-02, 6.7870e-02, 6.8114e-02, 6.8358e-02, 6.8602e-02, 6.8846e-02, 6.9091e-02, 6.9335e-02, 6.9579e-02, 6.9823e-02, 7.0067e-02, 7.0311e-02, 7.0555e-02, 7.0799e-02, 7.1044e-02, 7.1288e-02, 7.1532e-02, 7.1776e-02, 7.2020e-02, 7.2264e-02, 7.2508e-02, 7.2753e-02, 7.2997e-02, 7.3241e-02, 7.3485e-02, 7.3729e-02, 7.3973e-02, 7.4217e-02, 7.4462e-02, 7.4706e-02, 7.4950e-02, 7.5194e-02, 7.5438e-02, 7.5682e-02, 7.5926e-02, 7.6171e-02, 7.6415e-02, 7.6659e-02, 7.6903e-02, 7.7147e-02, 7.7391e-02, 7.7635e-02, 7.7880e-02, 7.8124e-02, 7.8368e-02, 7.8612e-02, 7.8856e-02, 7.9100e-02, 7.9344e-02, 7.9589e-02, 7.9833e-02, 8.0077e-02, 8.0321e-02, 8.0565e-02, 8.0809e-02, 8.1053e-02, 8.1298e-02, 8.1542e-02, 8.1786e-02, 8.2030e-02, 8.2274e-02, 8.2518e-02, 8.2762e-02, 8.3006e-02, 8.3251e-02, 8.3495e-02, 8.3739e-02, 8.3983e-02, 8.4227e-02, 8.4471e-02, 8.4715e-02, 8.4960e-02, 8.5204e-02, 8.5448e-02, 8.5692e-02, 8.5936e-02, 8.6180e-02, 8.6424e-02, 8.6669e-02, 8.6913e-02, 8.7157e-02, 8.7401e-02, 8.7645e-02, 8.7889e-02, 8.8133e-02, 8.8378e-02, 8.8622e-02, 8.8866e-02, 8.9110e-02, 8.9354e-02, 8.9598e-02, 8.9842e-02, 9.0087e-02, 9.0331e-02, 9.0575e-02, 9.0819e-02, 9.1063e-02, 9.1307e-02, 9.1551e-02, 9.1796e-02, 9.2040e-02, 9.2284e-02, 9.2528e-02, 9.2772e-02, 9.3016e-02, 9.3260e-02, 9.3504e-02, 9.3749e-02, 9.4237e-02, 9.4725e-02, 9.5213e-02, 9.5702e-02, 9.6190e-02, 9.6678e-02, 9.7167e-02, 9.7655e-02, 9.8143e-02, 9.8631e-02, 9.9120e-02, 9.9608e-02, 1.0010e-01, 1.0058e-01, 1.0107e-01, 1.0156e-01, 1.0205e-01, 1.0254e-01, 1.0303e-01, 1.0351e-01, 1.0400e-01, 1.0449e-01, 1.0498e-01, 1.0547e-01, 1.0596e-01, 1.0644e-01, 1.0693e-01, 1.0742e-01, 1.0791e-01, 1.0840e-01, 1.0889e-01, 1.0937e-01, 1.0986e-01, 1.1035e-01, 1.1084e-01, 1.1133e-01, 1.1182e-01, 1.1230e-01, 1.1279e-01, 1.1328e-01, 1.1377e-01, 1.1426e-01, 1.1474e-01, 1.1523e-01, 1.1572e-01, 1.1621e-01, 1.1670e-01, 1.1719e-01, 1.1767e-01, 1.1816e-01, 1.1865e-01, 1.1914e-01, 1.1963e-01, 1.2012e-01, 1.2060e-01, 1.2109e-01, 1.2158e-01, 1.2207e-01, 1.2256e-01, 1.2305e-01, 1.2353e-01, 1.2402e-01, 1.2451e-01, 1.2500e-01, 1.2549e-01, 1.2598e-01, 1.2646e-01, 1.2695e-01, 1.2744e-01, 1.2793e-01, 1.2842e-01, 1.2890e-01, 1.2939e-01, 1.2988e-01, 1.3037e-01, 1.3086e-01, 1.3135e-01, 1.3183e-01, 1.3232e-01, 1.3281e-01, 1.3330e-01, 1.3379e-01, 1.3428e-01, 1.3476e-01, 1.3525e-01, 1.3574e-01, 1.3623e-01, 1.3672e-01, 1.3721e-01, 1.3769e-01, 1.3818e-01, 1.3867e-01, 1.3916e-01, 1.3965e-01, 1.4014e-01, 1.4062e-01, 1.4111e-01, 1.4160e-01, 1.4209e-01, 1.4258e-01, 1.4306e-01, 1.4355e-01, 1.4404e-01, 1.4453e-01, 1.4502e-01, 1.4551e-01, 1.4599e-01, 1.4648e-01, 1.4697e-01, 1.4746e-01, 1.4795e-01, 1.4844e-01, 1.4892e-01, 1.4941e-01, 1.4990e-01, 1.5039e-01, 1.5088e-01, 1.5137e-01, 1.5185e-01, 1.5234e-01, 1.5283e-01, 1.5332e-01, 1.5381e-01, 1.5430e-01, 1.5478e-01, 1.5527e-01, 1.5576e-01, 1.5625e-01, // NOLINT - 1.5674e-01, 1.5723e-01, 1.5771e-01, 1.5820e-01, 1.5869e-01, 1.5918e-01, 1.5967e-01, 1.6015e-01, 1.6064e-01, 1.6113e-01, 1.6162e-01, 1.6211e-01, 1.6260e-01, 1.6308e-01, 1.6357e-01, 1.6406e-01, 1.6455e-01, 1.6504e-01, 1.6553e-01, 1.6601e-01, 1.6650e-01, 1.6699e-01, 1.6748e-01, 1.6797e-01, 1.6846e-01, 1.6894e-01, 1.6943e-01, 1.6992e-01, 1.7041e-01, 1.7090e-01, 1.7139e-01, 1.7187e-01, 1.7236e-01, 1.7285e-01, 1.7334e-01, 1.7383e-01, 1.7431e-01, 1.7480e-01, 1.7529e-01, 1.7578e-01, 1.7627e-01, 1.7676e-01, 1.7724e-01, 1.7773e-01, 1.7822e-01, 1.7871e-01, 1.7920e-01, 1.7969e-01, 1.8017e-01, 1.8066e-01, 1.8115e-01, 1.8164e-01, 1.8213e-01, 1.8262e-01, 1.8310e-01, 1.8359e-01, 1.8408e-01, 1.8457e-01, 1.8506e-01, 1.8555e-01, 1.8603e-01, 1.8652e-01, 1.8701e-01, 1.8750e-01, 1.8848e-01, 1.8945e-01, 1.9043e-01, 1.9140e-01, 1.9238e-01, 1.9336e-01, 1.9433e-01, 1.9531e-01, 1.9629e-01, 1.9726e-01, 1.9824e-01, 1.9922e-01, 2.0019e-01, 2.0117e-01, 2.0215e-01, 2.0312e-01, 2.0410e-01, 2.0508e-01, 2.0605e-01, 2.0703e-01, 2.0801e-01, 2.0898e-01, 2.0996e-01, 2.1094e-01, 2.1191e-01, 2.1289e-01, 2.1387e-01, 2.1484e-01, 2.1582e-01, 2.1680e-01, 2.1777e-01, 2.1875e-01, 2.1972e-01, 2.2070e-01, 2.2168e-01, 2.2265e-01, 2.2363e-01, 2.2461e-01, 2.2558e-01, 2.2656e-01, 2.2754e-01, 2.2851e-01, 2.2949e-01, 2.3047e-01, 2.3144e-01, 2.3242e-01, 2.3340e-01, 2.3437e-01, 2.3535e-01, 2.3633e-01, 2.3730e-01, 2.3828e-01, 2.3926e-01, 2.4023e-01, 2.4121e-01, 2.4219e-01, 2.4316e-01, 2.4414e-01, 2.4512e-01, 2.4609e-01, 2.4707e-01, 2.4805e-01, 2.4902e-01, 2.5000e-01, 2.5097e-01, 2.5195e-01, 2.5293e-01, 2.5390e-01, 2.5488e-01, 2.5586e-01, 2.5683e-01, 2.5781e-01, 2.5879e-01, 2.5976e-01, 2.6074e-01, 2.6172e-01, 2.6269e-01, 2.6367e-01, 2.6465e-01, 2.6562e-01, 2.6660e-01, 2.6758e-01, 2.6855e-01, 2.6953e-01, 2.7051e-01, 2.7148e-01, 2.7246e-01, 2.7344e-01, 2.7441e-01, 2.7539e-01, 2.7637e-01, 2.7734e-01, 2.7832e-01, 2.7930e-01, 2.8027e-01, 2.8125e-01, 2.8222e-01, 2.8320e-01, 2.8418e-01, 2.8515e-01, 2.8613e-01, 2.8711e-01, 2.8808e-01, 2.8906e-01, 2.9004e-01, 2.9101e-01, 2.9199e-01, 2.9297e-01, 2.9394e-01, 2.9492e-01, 2.9590e-01, 2.9687e-01, 2.9785e-01, 2.9883e-01, 2.9980e-01, 3.0078e-01, 3.0176e-01, 3.0273e-01, 3.0371e-01, 3.0469e-01, 3.0566e-01, 3.0664e-01, 3.0762e-01, 3.0859e-01, 3.0957e-01, 3.1055e-01, 3.1152e-01, 3.1250e-01, 3.1347e-01, 3.1445e-01, 3.1543e-01, 3.1640e-01, 3.1738e-01, 3.1836e-01, 3.1933e-01, 3.2031e-01, 3.2129e-01, 3.2226e-01, 3.2324e-01, 3.2422e-01, 3.2519e-01, 3.2617e-01, 3.2715e-01, 3.2812e-01, 3.2910e-01, 3.3008e-01, 3.3105e-01, 3.3203e-01, 3.3301e-01, 3.3398e-01, 3.3496e-01, 3.3594e-01, 3.3691e-01, 3.3789e-01, 3.3887e-01, 3.3984e-01, 3.4082e-01, 3.4180e-01, 3.4277e-01, 3.4375e-01, 3.4472e-01, 3.4570e-01, 3.4668e-01, 3.4765e-01, 3.4863e-01, 3.4961e-01, 3.5058e-01, 3.5156e-01, 3.5254e-01, 3.5351e-01, 3.5449e-01, 3.5547e-01, 3.5644e-01, 3.5742e-01, 3.5840e-01, 3.5937e-01, 3.6035e-01, 3.6133e-01, 3.6230e-01, 3.6328e-01, 3.6426e-01, 3.6523e-01, 3.6621e-01, 3.6719e-01, 3.6816e-01, 3.6914e-01, 3.7012e-01, 3.7109e-01, 3.7207e-01, 3.7305e-01, 3.7402e-01, 3.7500e-01, // NOLINT - 3.7695e-01, 3.7890e-01, 3.8086e-01, 3.8281e-01, 3.8476e-01, 3.8672e-01, 3.8867e-01, 3.9062e-01, 3.9258e-01, 3.9453e-01, 3.9648e-01, 3.9844e-01, 4.0039e-01, 4.0234e-01, 4.0430e-01, 4.0625e-01, 4.0820e-01, 4.1015e-01, 4.1211e-01, 4.1406e-01, 4.1601e-01, 4.1797e-01, 4.1992e-01, 4.2187e-01, 4.2383e-01, 4.2578e-01, 4.2773e-01, 4.2969e-01, 4.3164e-01, 4.3359e-01, 4.3555e-01, 4.3750e-01, 4.3945e-01, 4.4140e-01, 4.4336e-01, 4.4531e-01, 4.4726e-01, 4.4922e-01, 4.5117e-01, 4.5312e-01, 4.5508e-01, 4.5703e-01, 4.5898e-01, 4.6094e-01, 4.6289e-01, 4.6484e-01, 4.6680e-01, 4.6875e-01, 4.7070e-01, 4.7265e-01, 4.7461e-01, 4.7656e-01, 4.7851e-01, 4.8047e-01, 4.8242e-01, 4.8437e-01, 4.8633e-01, 4.8828e-01, 4.9023e-01, 4.9219e-01, 4.9414e-01, 4.9609e-01, 4.9805e-01, 5.0000e-01, 5.0195e-01, 5.0390e-01, 5.0586e-01, 5.0781e-01, 5.0976e-01, 5.1172e-01, 5.1367e-01, 5.1562e-01, 5.1758e-01, 5.1953e-01, 5.2148e-01, 5.2344e-01, 5.2539e-01, 5.2734e-01, 5.2930e-01, 5.3125e-01, 5.3320e-01, 5.3515e-01, 5.3711e-01, 5.3906e-01, 5.4101e-01, 5.4297e-01, 5.4492e-01, 5.4687e-01, 5.4883e-01, 5.5078e-01, 5.5273e-01, 5.5469e-01, 5.5664e-01, 5.5859e-01, 5.6055e-01, 5.6250e-01, 5.6445e-01, 5.6640e-01, 5.6836e-01, 5.7031e-01, 5.7226e-01, 5.7422e-01, 5.7617e-01, 5.7812e-01, 5.8008e-01, 5.8203e-01, 5.8398e-01, 5.8594e-01, 5.8789e-01, 5.8984e-01, 5.9180e-01, 5.9375e-01, 5.9570e-01, 5.9765e-01, 5.9961e-01, 6.0156e-01, 6.0351e-01, 6.0547e-01, 6.0742e-01, 6.0937e-01, 6.1133e-01, 6.1328e-01, 6.1523e-01, 6.1719e-01, 6.1914e-01, 6.2109e-01, 6.2305e-01, 6.2500e-01, 6.2695e-01, 6.2890e-01, 6.3086e-01, 6.3281e-01, 6.3476e-01, 6.3672e-01, 6.3867e-01, 6.4062e-01, 6.4258e-01, 6.4453e-01, 6.4648e-01, 6.4844e-01, 6.5039e-01, 6.5234e-01, 6.5430e-01, 6.5625e-01, 6.5820e-01, 6.6015e-01, 6.6211e-01, 6.6406e-01, 6.6601e-01, 6.6797e-01, 6.6992e-01, 6.7187e-01, 6.7383e-01, 6.7578e-01, 6.7773e-01, 6.7969e-01, 6.8164e-01, 6.8359e-01, 6.8554e-01, 6.8750e-01, 6.8945e-01, 6.9140e-01, 6.9336e-01, 6.9531e-01, 6.9726e-01, 6.9922e-01, 7.0117e-01, 7.0312e-01, 7.0508e-01, 7.0703e-01, 7.0898e-01, 7.1094e-01, 7.1289e-01, 7.1484e-01, 7.1679e-01, 7.1875e-01, 7.2070e-01, 7.2265e-01, 7.2461e-01, 7.2656e-01, 7.2851e-01, 7.3047e-01, 7.3242e-01, 7.3437e-01, 7.3633e-01, 7.3828e-01, 7.4023e-01, 7.4219e-01, 7.4414e-01, 7.4609e-01, 7.4804e-01, 7.5000e-01, 7.5390e-01, 7.5781e-01, 7.6172e-01, 7.6562e-01, 7.6953e-01, 7.7344e-01, 7.7734e-01, 7.8125e-01, 7.8515e-01, 7.8906e-01, 7.9297e-01, 7.9687e-01, 8.0078e-01, 8.0469e-01, 8.0859e-01, 8.1250e-01, 8.1640e-01, 8.2031e-01, 8.2422e-01, 8.2812e-01, 8.3203e-01, 8.3594e-01, 8.3984e-01, 8.4375e-01, 8.4765e-01, 8.5156e-01, 8.5547e-01, 8.5937e-01, 8.6328e-01, 8.6719e-01, 8.7109e-01, 8.7500e-01, 8.7890e-01, 8.8281e-01, 8.8672e-01, 8.9062e-01, 8.9453e-01, 8.9844e-01, 9.0234e-01, 9.0625e-01, 9.1015e-01, 9.1406e-01, 9.1797e-01, 9.2187e-01, 9.2578e-01, 9.2969e-01, 9.3359e-01, 9.3750e-01, 9.4140e-01, 9.4531e-01, 9.4922e-01, 9.5312e-01, 9.5703e-01, 9.6094e-01, 9.6484e-01, 9.6875e-01, 9.7265e-01, 9.7656e-01, 9.8047e-01, 9.8437e-01, 9.8828e-01, 9.9219e-01, 9.9609e-01, 1.0000e+00 // NOLINT -}; +float ox_lut_func(int x) { + if (x < 512) { + return x * 5.94873e-8; + } else if (512 <= x && x < 768) { + return 3.0458e-05 + (x-512) * 1.19913e-7; + } else if (768 <= x && x < 1536) { + return 6.1154e-05 + (x-768) * 2.38493e-7; + } else if (1536 <= x && x < 1792) { + return 0.0002448 + (x-1536) * 9.56930e-7; + } else if (1792 <= x && x < 2048) { + return 0.00048977 + (x-1792) * 1.91441e-6; + } else if (2048 <= x && x < 2304) { + return 0.00097984 + (x-2048) * 3.82937e-6; + } else if (2304 <= x && x < 2560) { + return 0.0019601 + (x-2304) * 7.659055e-6; + } else if (2560 <= x && x < 2816) { + return 0.0039207 + (x-2560) * 1.525e-5; + } else { + return 0.0078421 + (exp((x-2816)/273.0) - 1) * 0.0092421; + } +} float4 normalize_pv(int4 parsed, float vignette_factor) { // PWL - float4 pv = {ox03c10_lut[parsed.s0], ox03c10_lut[parsed.s1], ox03c10_lut[parsed.s2], ox03c10_lut[parsed.s3]}; + float4 pv = {ox_lut_func(parsed.s0), ox_lut_func(parsed.s1), ox_lut_func(parsed.s2), ox_lut_func(parsed.s3)}; return clamp(pv*vignette_factor*256.0, 0.0, 1.0); } @@ -40,4 +43,4 @@ float3 apply_gamma(float3 rgb, int expo_time) { return -0.507089*exp(-12.54124638*rgb) + 0.9655*powr(rgb, 0.5) - 0.472597*rgb + 0.507089; } -#endif \ No newline at end of file +#endif From 0ee8bb8f8e280ecac91d41d309981a6124c937b0 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 26 Sep 2024 19:48:43 -0700 Subject: [PATCH 149/214] add come to stop maneuver --- tools/longitudinal_maneuvers/maneuversd.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/tools/longitudinal_maneuvers/maneuversd.py b/tools/longitudinal_maneuvers/maneuversd.py index 6100a7ca89..88ea54378f 100755 --- a/tools/longitudinal_maneuvers/maneuversd.py +++ b/tools/longitudinal_maneuvers/maneuversd.py @@ -72,6 +72,12 @@ class Maneuver: MANEUVERS = [ + Maneuver( + "come to stop", + [Action(-0.5, 12)], + repeat=2, + initial_speed=5., + ), Maneuver( "start from stop", [Action(1.5, 3)], From 238a1fc56a24763288bf582fd71f8f248ad59e5e Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Fri, 27 Sep 2024 08:59:36 -0700 Subject: [PATCH 150/214] HKG: 2024 Genesis G80 HDA2 (#33662) --- docs/CARS.md | 3 ++- opendbc_repo | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index eea3eef1fc..072e366e98 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,7 +4,7 @@ A supported vehicle is one that just works when you install a comma device. All supported cars provide a better experience than any stock system. Supported vehicles reference the US market unless otherwise specified. -# 288 Supported Cars +# 289 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Hardware Needed
 |Video| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:| @@ -50,6 +50,7 @@ A supported vehicle is one that just works when you install a comma device. All |Genesis|G70 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|G80 2017|All|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai J connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|G80 2018-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Genesis|G80 (2.5T Advanced Trim, with HDA II) 2024[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|G90 2017-20|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|GV60 (Advanced Trim) 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|GV60 (Performance Trim) 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| diff --git a/opendbc_repo b/opendbc_repo index b11c159d87..d2ca1860d8 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit b11c159d87635ce698ec79d55516f202afa86f91 +Subproject commit d2ca1860d894c246758b22551a6f7d322ba1cae0 From b9f9854743676b7c8f8b9a20cef0e6a9fdd01206 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 27 Sep 2024 14:49:13 -0700 Subject: [PATCH 151/214] maneuversd: run start from stop maneuver for longer --- tools/longitudinal_maneuvers/maneuversd.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/longitudinal_maneuvers/maneuversd.py b/tools/longitudinal_maneuvers/maneuversd.py index 88ea54378f..8bcfa69a14 100755 --- a/tools/longitudinal_maneuvers/maneuversd.py +++ b/tools/longitudinal_maneuvers/maneuversd.py @@ -80,7 +80,7 @@ MANEUVERS = [ ), Maneuver( "start from stop", - [Action(1.5, 3)], + [Action(1.5, 5)], repeat=3, initial_speed=0., ), @@ -91,7 +91,7 @@ MANEUVERS = [ Action(1, 2), Action(-1, 2), Action(1, 2), Action(-1, 2), ], - repeat=1, + repeat=2, initial_speed=0., ), Maneuver( From 6b232cf91f05385e5964a56f346a18f55d43d9da Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 27 Sep 2024 17:48:34 -0700 Subject: [PATCH 152/214] maneuversd: run creep test for slightly longer --- tools/longitudinal_maneuvers/maneuversd.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tools/longitudinal_maneuvers/maneuversd.py b/tools/longitudinal_maneuvers/maneuversd.py index 8bcfa69a14..07582c3e6c 100755 --- a/tools/longitudinal_maneuvers/maneuversd.py +++ b/tools/longitudinal_maneuvers/maneuversd.py @@ -87,9 +87,9 @@ MANEUVERS = [ Maneuver( "creep: alternate between +1m/s^2 and -1m/s^2", [ - Action(1, 2), Action(-1, 2), - Action(1, 2), Action(-1, 2), - Action(1, 2), Action(-1, 2), + Action(1, 3), Action(-1, 3), + Action(1, 3), Action(-1, 3), + Action(1, 3), Action(-1, 3), ], repeat=2, initial_speed=0., From f7b800673b314742211490b2890749a7e83930e7 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 27 Sep 2024 17:49:09 -0700 Subject: [PATCH 153/214] smaller legend in the report --- tools/longitudinal_maneuvers/generate_report.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/longitudinal_maneuvers/generate_report.py b/tools/longitudinal_maneuvers/generate_report.py index a396e51127..eb8c13271a 100755 --- a/tools/longitudinal_maneuvers/generate_report.py +++ b/tools/longitudinal_maneuvers/generate_report.py @@ -92,7 +92,7 @@ def report(platform, route, _description, CP, maneuvers): # TODO localizer accel ax[0].set_ylabel('Acceleration (m/s^2)') #ax[0].set_ylim(-6.5, 6.5) - ax[0].legend() + ax[0].legend(prop={'size': 30}) if target_cross_time is not None: ax[0].plot(target_cross_time, aTarget, marker='o', markersize=50, markeredgewidth=7, markeredgecolor='black', markerfacecolor='None') From df529de1d0e469df5b59625420370a5197de17bd Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 27 Sep 2024 21:26:54 -0700 Subject: [PATCH 154/214] Lexus ES TSS2: improve start from stop response time (#33666) * bump * docs --- docs/CARS.md | 2 +- opendbc_repo | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 072e366e98..43bd18cdcd 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -53,7 +53,7 @@ A supported vehicle is one that just works when you install a comma device. All |Genesis|G80 (2.5T Advanced Trim, with HDA II) 2024[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|G90 2017-20|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|GV60 (Advanced Trim) 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Genesis|GV60 (Performance Trim) 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Genesis|GV60 (Performance Trim) 2022-23[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|GV70 (2.5T Trim, without HDA II) 2022-23[5](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|GV70 (3.5T Trim, without HDA II) 2022-23[5](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Genesis|GV70 Electrified (with HDA II) 2023[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| diff --git a/opendbc_repo b/opendbc_repo index d2ca1860d8..b556672f9c 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit d2ca1860d894c246758b22551a6f7d322ba1cae0 +Subproject commit b556672f9cb714fc05ac4af252dfabcf6865d27a From 04a266eaebcf0787f28cd4a5453a1c064517748a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Fri, 27 Sep 2024 22:48:32 -0700 Subject: [PATCH 155/214] Game Boy Model (#33661) * 559069cd-40a6-4456-9052-08659f376ca3/370 * 028fb9bc-b33e-4c26-9cf7-e3c44a85276a/400 * Update ref * Update tolerance --- selfdrive/modeld/constants.py | 20 +++++++++---------- selfdrive/modeld/models/supercombo.onnx | 4 ++-- selfdrive/test/process_replay/model_replay.py | 2 +- .../process_replay/model_replay_ref_commit | 2 +- 4 files changed, 14 insertions(+), 14 deletions(-) diff --git a/selfdrive/modeld/constants.py b/selfdrive/modeld/constants.py index 4d2888d231..82161a5b67 100644 --- a/selfdrive/modeld/constants.py +++ b/selfdrive/modeld/constants.py @@ -72,14 +72,14 @@ class Plan: class Meta: ENGAGED = slice(0, 1) # next 2, 4, 6, 8, 10 seconds - GAS_DISENGAGE = slice(1, 41, 8) - BRAKE_DISENGAGE = slice(2, 41, 8) - STEER_OVERRIDE = slice(3, 41, 8) - HARD_BRAKE_3 = slice(4, 41, 8) - HARD_BRAKE_4 = slice(5, 41, 8) - HARD_BRAKE_5 = slice(6, 41, 8) - GAS_PRESS = slice(7, 41, 8) - BRAKE_PRESS = slice(8, 41, 8) + GAS_DISENGAGE = slice(1, 31, 6) + BRAKE_DISENGAGE = slice(2, 31, 6) + STEER_OVERRIDE = slice(3, 31, 6) + HARD_BRAKE_3 = slice(4, 31, 6) + HARD_BRAKE_4 = slice(5, 31, 6) + HARD_BRAKE_5 = slice(6, 31, 6) # next 0, 2, 4, 6, 8, 10 seconds - LEFT_BLINKER = slice(41, 53, 2) - RIGHT_BLINKER = slice(42, 53, 2) + GAS_PRESS = slice(31, 55, 4) + BRAKE_PRESS = slice(32, 55, 4) + LEFT_BLINKER = slice(33, 55, 4) + RIGHT_BLINKER = slice(34, 55, 4) diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 111cb76dbb..f8002d5a91 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:d42319e42e8ba1a818c845ee0c687ece6afd98e59fef142895be33dd230974c2 -size 62481231 +oid sha256:0dab94dc94db5e372f56d26f9dda98bd31fd76e4c16027da611132263848d0c1 +size 62486347 diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index ead3a3b4b5..af05ff5e44 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -129,7 +129,7 @@ if __name__ == "__main__": for i in range(4): for field in ('x', 'y', 'z', 't'): ignore.append(f'modelV2.laneLines.{i}.{field}') - tolerance = .2 if PC else None + tolerance = .3 if PC else None results: Any = {TEST_ROUTE: {}} log_paths: Any = {TEST_ROUTE: {"models": {'ref': BASE_URL + log_fn, 'new': log_fn}}} results[TEST_ROUTE]["models"] = compare_logs(cmp_log, log_msgs, tolerance=tolerance, ignore_fields=ignore) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 3e4f435964..9e62d47538 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -7cd64f431b814adfa11118643efe3822c496922b +68279894530723a9129c64e8e771018bc4dda6b3 From 368bc74dfd13dbd91856478c9b5f56fc009dff05 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 27 Sep 2024 23:30:49 -0700 Subject: [PATCH 156/214] bump opendbc --- opendbc_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc_repo b/opendbc_repo index b556672f9c..173ab90402 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit b556672f9cb714fc05ac4af252dfabcf6865d27a +Subproject commit 173ab90402f85c07cd65750c7f31cc97a8b07d59 From 33952d0a602e45c2b7d1c6e4386d340625a5bcbf Mon Sep 17 00:00:00 2001 From: Mauricio Alvarez Leon <65101411+BBBmau@users.noreply.github.com> Date: Sat, 28 Sep 2024 13:21:48 -0700 Subject: [PATCH 157/214] `ui`: auto-expand summary when diff is present. (#33668) * ui: use details open when diff is present * remove comment --- .github/workflows/ui_preview.yaml | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/.github/workflows/ui_preview.yaml b/.github/workflows/ui_preview.yaml index a2033f8180..24956516f8 100644 --- a/.github/workflows/ui_preview.yaml +++ b/.github/workflows/ui_preview.yaml @@ -88,14 +88,15 @@ jobs: A=($scenes) DIFF="" - TABLE="
" - TABLE="${TABLE}All Screenshots" + open=false + TABLE="All Screenshots" TABLE="${TABLE}
master master proposed
" for ((i=0; i<${#A[*]}; i=i+1)); do if ! compare -fuzz 2% -highlight-color DeepSkyBlue1 -lowlight-color Black -compose Src ${{ github.workspace }}/master_ui/${A[$i]}.png ${{ github.workspace }}/pr_ui/${A[$i]}.png ${{ github.workspace }}/pr_ui/${A[$i]}_diff.png; then + open=true convert ${{ github.workspace }}/pr_ui/${A[$i]}_diff.png -transparent black mask.png composite mask.png ${{ github.workspace }}/master_ui/${A[$i]}.png composite_diff.png convert -delay 20 ${{ github.workspace }}/master_ui/${A[$i]}.png composite_diff.png -loop 0 ${{ github.workspace }}/pr_ui/${A[$i]}_diff.gif @@ -134,7 +135,11 @@ jobs: TABLE="${TABLE}
" TABLE="${TABLE}
" - + if open; then + TABLE="
${TABLE}" + else + TABLE="
${TABLE}" + fi echo "DIFF=$DIFF$TABLE" >> "$GITHUB_OUTPUT" - name: Saving proposed ui From 4da090a4e1972eb1c70b4847f729b28ba805af64 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Sat, 28 Sep 2024 15:33:01 -0700 Subject: [PATCH 158/214] Game Boy Model V2 (#33669) * 78cec5a0-577b-49ac-b443-f7cd327649bd/400 * ref commit --- selfdrive/modeld/models/supercombo.onnx | 2 +- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index f8002d5a91..8b7126c44a 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:0dab94dc94db5e372f56d26f9dda98bd31fd76e4c16027da611132263848d0c1 +oid sha256:fb2018c74cdd9e5cb070ec7bed7f8581fabd55e39057d0a03aaffd2e42408154 size 62486347 diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 9e62d47538..2faabd0587 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -68279894530723a9129c64e8e771018bc4dda6b3 +ff10a803005f5116a8f3d88629503bc52b15b93f From edf9522bc064aa30b348e53c674b052c860cc9fc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Sat, 28 Sep 2024 18:34:31 -0700 Subject: [PATCH 159/214] Model and YUV pipeline to uint8 (#33671) * Squash * 78cec5a0-577b-49ac-b443-f7cd327649bd/400 * bump tinygrad --- selfdrive/modeld/models/commonmodel.cc | 14 +++++++------- selfdrive/modeld/models/commonmodel.h | 4 ++-- selfdrive/modeld/models/commonmodel.pxd | 2 +- selfdrive/modeld/models/commonmodel_pyx.pyx | 4 ++-- selfdrive/modeld/models/supercombo.onnx | 4 ++-- selfdrive/modeld/transforms/loadyuv.cl | 18 ++++++++---------- tinygrad_repo | 2 +- 7 files changed, 23 insertions(+), 25 deletions(-) diff --git a/selfdrive/modeld/models/commonmodel.cc b/selfdrive/modeld/models/commonmodel.cc index 57c14dfa88..d2d37bbc5a 100644 --- a/selfdrive/modeld/models/commonmodel.cc +++ b/selfdrive/modeld/models/commonmodel.cc @@ -7,28 +7,28 @@ #include "common/clutil.h" ModelFrame::ModelFrame(cl_device_id device_id, cl_context context) { - input_frames = std::make_unique(buf_size); + input_frames = std::make_unique(buf_size); q = CL_CHECK_ERR(clCreateCommandQueue(context, device_id, 0, &err)); y_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_WIDTH * MODEL_HEIGHT, NULL, &err)); u_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); v_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); - net_input_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_FRAME_SIZE * sizeof(float), NULL, &err)); + net_input_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_FRAME_SIZE * sizeof(uint8_t), NULL, &err)); transform_init(&transform, context, device_id); loadyuv_init(&loadyuv, context, device_id, MODEL_WIDTH, MODEL_HEIGHT); } -float* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3 &projection, cl_mem *output) { +uint8_t* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3 &projection, cl_mem *output) { transform_queue(&this->transform, q, - yuv_cl, frame_width, frame_height, frame_stride, frame_uv_offset, - y_cl, u_cl, v_cl, MODEL_WIDTH, MODEL_HEIGHT, projection); + yuv_cl, frame_width, frame_height, frame_stride, frame_uv_offset, + y_cl, u_cl, v_cl, MODEL_WIDTH, MODEL_HEIGHT, projection); if (output == NULL) { loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, net_input_cl); - std::memmove(&input_frames[0], &input_frames[MODEL_FRAME_SIZE], sizeof(float) * MODEL_FRAME_SIZE); - CL_CHECK(clEnqueueReadBuffer(q, net_input_cl, CL_TRUE, 0, MODEL_FRAME_SIZE * sizeof(float), &input_frames[MODEL_FRAME_SIZE], 0, nullptr, nullptr)); + std::memmove(&input_frames[0], &input_frames[MODEL_FRAME_SIZE], sizeof(uint8_t) * MODEL_FRAME_SIZE); + CL_CHECK(clEnqueueReadBuffer(q, net_input_cl, CL_TRUE, 0, MODEL_FRAME_SIZE * sizeof(uint8_t), &input_frames[MODEL_FRAME_SIZE], 0, nullptr, nullptr)); clFinish(q); return &input_frames[0]; } else { diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h index 0b5d87fd6c..ea39466670 100644 --- a/selfdrive/modeld/models/commonmodel.h +++ b/selfdrive/modeld/models/commonmodel.h @@ -20,7 +20,7 @@ class ModelFrame { public: ModelFrame(cl_device_id device_id, cl_context context); ~ModelFrame(); - float* prepare(cl_mem yuv_cl, int width, int height, int frame_stride, int frame_uv_offset, const mat3& transform, cl_mem *output); + uint8_t* prepare(cl_mem yuv_cl, int width, int height, int frame_stride, int frame_uv_offset, const mat3& transform, cl_mem *output); const int MODEL_WIDTH = 512; const int MODEL_HEIGHT = 256; @@ -32,5 +32,5 @@ private: LoadYUVState loadyuv; cl_command_queue q; cl_mem y_cl, u_cl, v_cl, net_input_cl; - std::unique_ptr input_frames; + std::unique_ptr input_frames; }; diff --git a/selfdrive/modeld/models/commonmodel.pxd b/selfdrive/modeld/models/commonmodel.pxd index f37014219d..3348af3f17 100644 --- a/selfdrive/modeld/models/commonmodel.pxd +++ b/selfdrive/modeld/models/commonmodel.pxd @@ -15,4 +15,4 @@ cdef extern from "selfdrive/modeld/models/commonmodel.h": cppclass ModelFrame: int buf_size ModelFrame(cl_device_id, cl_context) - float * prepare(cl_mem, int, int, int, int, mat3, cl_mem*) + unsigned char * prepare(cl_mem, int, int, int, int, mat3, cl_mem*) diff --git a/selfdrive/modeld/models/commonmodel_pyx.pyx b/selfdrive/modeld/models/commonmodel_pyx.pyx index 46ac575cc2..99f9c5dc17 100644 --- a/selfdrive/modeld/models/commonmodel_pyx.pyx +++ b/selfdrive/modeld/models/commonmodel_pyx.pyx @@ -35,11 +35,11 @@ cdef class ModelFrame: def prepare(self, VisionBuf buf, float[:] projection, CLMem output): cdef mat3 cprojection memcpy(cprojection.v, &projection[0], 9*sizeof(float)) - cdef float * data + cdef unsigned char * data if output is None: data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, NULL) else: data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, output.mem) if not data: return None - return np.asarray( data) + return np.asarray( data) diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 8b7126c44a..aeb3ea3b2b 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:fb2018c74cdd9e5cb070ec7bed7f8581fabd55e39057d0a03aaffd2e42408154 -size 62486347 +oid sha256:47417a13d8a8d6af6a1562834eee538e3b43242c6e277ab6f1978a78a6785b7d +size 62486469 diff --git a/selfdrive/modeld/transforms/loadyuv.cl b/selfdrive/modeld/transforms/loadyuv.cl index 7dd3d973a3..3a6b3ebc4f 100644 --- a/selfdrive/modeld/transforms/loadyuv.cl +++ b/selfdrive/modeld/transforms/loadyuv.cl @@ -1,7 +1,7 @@ #define UV_SIZE ((TRANSFORMED_WIDTH/2)*(TRANSFORMED_HEIGHT/2)) __kernel void loadys(__global uchar8 const * const Y, - __global float * out, + __global uchar * out, int out_offset) { const int gid = get_global_id(0); @@ -10,13 +10,12 @@ __kernel void loadys(__global uchar8 const * const Y, const int ox = ois % TRANSFORMED_WIDTH; const uchar8 ys = Y[gid]; - const float8 ysf = convert_float8(ys); // 02 // 13 - __global float* outy0; - __global float* outy1; + __global uchar* outy0; + __global uchar* outy1; if ((oy & 1) == 0) { outy0 = out + out_offset; //y0 outy1 = out + out_offset + UV_SIZE*2; //y2 @@ -25,21 +24,20 @@ __kernel void loadys(__global uchar8 const * const Y, outy1 = out + out_offset + UV_SIZE*3; //y3 } - vstore4(ysf.s0246, 0, outy0 + (oy/2) * (TRANSFORMED_WIDTH/2) + ox/2); - vstore4(ysf.s1357, 0, outy1 + (oy/2) * (TRANSFORMED_WIDTH/2) + ox/2); + vstore4(ys.s0246, 0, outy0 + (oy/2) * (TRANSFORMED_WIDTH/2) + ox/2); + vstore4(ys.s1357, 0, outy1 + (oy/2) * (TRANSFORMED_WIDTH/2) + ox/2); } __kernel void loaduv(__global uchar8 const * const in, - __global float8 * out, + __global uchar8 * out, int out_offset) { const int gid = get_global_id(0); const uchar8 inv = in[gid]; - const float8 outv = convert_float8(inv); - out[gid + out_offset / 8] = outv; + out[gid + out_offset / 8] = inv; } -__kernel void copy(__global float8 * inout, +__kernel void copy(__global uchar8 * inout, int in_offset) { const int gid = get_global_id(0); diff --git a/tinygrad_repo b/tinygrad_repo index 3e15fa0dae..9dda6d260d 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit 3e15fa0daefae75e2ddef98f82be5b5d37820631 +Subproject commit 9dda6d260db0255750bacff61e3cee1e580567e1 From ce0e3d5603ff2716d33d0c162f7bf69905ba493c Mon Sep 17 00:00:00 2001 From: Mauricio Alvarez Leon <65101411+BBBmau@users.noreply.github.com> Date: Sun, 29 Sep 2024 08:54:03 -0700 Subject: [PATCH 160/214] `ci`: fix if conditional in ui preview (#33673) fix if conditional --- .github/workflows/ui_preview.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ui_preview.yaml b/.github/workflows/ui_preview.yaml index 24956516f8..972a96dc39 100644 --- a/.github/workflows/ui_preview.yaml +++ b/.github/workflows/ui_preview.yaml @@ -135,7 +135,7 @@ jobs: TABLE="${TABLE}" TABLE="${TABLE}
" - if open; then + if $open; then TABLE="
${TABLE}" else TABLE="
${TABLE}" From 8bb7a8d310c24c52d859add9dbbb1dc462f5f5ea Mon Sep 17 00:00:00 2001 From: ugtthis <142481257+ugtthis@users.noreply.github.com> Date: Sun, 29 Sep 2024 10:03:29 -0700 Subject: [PATCH 161/214] Assets/icon: Rm redundant PNG file (#33565) Rm redundant file - use existing png to replace Co-authored-by: Adeeb Shihadeh --- selfdrive/assets/offroad/icon_openpilot.png | 3 --- selfdrive/ui/qt/offroad/settings.cc | 2 +- 2 files changed, 1 insertion(+), 4 deletions(-) delete mode 100644 selfdrive/assets/offroad/icon_openpilot.png diff --git a/selfdrive/assets/offroad/icon_openpilot.png b/selfdrive/assets/offroad/icon_openpilot.png deleted file mode 100644 index ae6faa45ea..0000000000 --- a/selfdrive/assets/offroad/icon_openpilot.png +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:a3cd3b91673eded1282e2082be0efa8e54ed477b5feb3580e521d08078e18ed1 -size 42640 diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 7024a2a802..a2b91534dd 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -22,7 +22,7 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { "OpenpilotEnabledToggle", tr("Enable openpilot"), tr("Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off."), - "../assets/offroad/icon_openpilot.png", + "../assets/img_chffr_wheel.png", }, { "ExperimentalLongitudinalEnabled", From 2cb526a5a9fc49a3f0d0fce61248ac6253030cb4 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 30 Sep 2024 01:06:34 +0800 Subject: [PATCH 162/214] camerad: refactor gain index loop for clarity (#33613) * Refactor Gain Index Loop for Clarity * Update system/camerad/cameras/camera_qcom2.cc * Update system/camerad/cameras/camera_qcom2.cc --------- Co-authored-by: Comma Device Co-authored-by: Adeeb Shihadeh --- system/camerad/cameras/camera_qcom2.cc | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 1bbd8202b2..3d5507add9 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -178,9 +178,10 @@ void CameraState::set_camera_exposure(float grey_frac) { new_exp_t = exposure_time; enable_dc_gain = false; } else { - // Simple brute force optimizer to choose sensor parameters - // to reach desired EV - for (int g = std::max((int)sensor->analog_gain_min_idx, gain_idx - 1); g <= std::min((int)sensor->analog_gain_max_idx, gain_idx + 1); g++) { + // Simple brute force optimizer to choose sensor parameters to reach desired EV + int min_g = std::max(gain_idx - 1, sensor->analog_gain_min_idx); + int max_g = std::min(gain_idx + 1, sensor->analog_gain_max_idx); + for (int g = min_g; g <= max_g; g++) { float gain = sensor->sensor_analog_gains[g] * get_gain_factor(); // Compute optimal time for given gain From f99d81d0faf24b33793edf26ba02c00ecbe1f7f7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 29 Sep 2024 10:10:57 -0700 Subject: [PATCH 163/214] remove cars from stale blacklist --- .github/workflows/stale.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/stale.yaml b/.github/workflows/stale.yaml index f7f92a0387..d0dead5126 100644 --- a/.github/workflows/stale.yaml +++ b/.github/workflows/stale.yaml @@ -21,7 +21,7 @@ jobs: close-pr-message: 'This PR has been automatically closed due to inactivity. Feel free to re-open once activity resumes.' stale-pr-label: stale delete-branch: ${{ github.event.pull_request.head.repo.full_name == 'commaai/openpilot' }} # only delete branches on the main repo - exempt-pr-labels: "ignore stale,needs testing,car port,car" # if wip or it needs testing from the community, don't mark as stale + exempt-pr-labels: "ignore stale,needs testing" # if wip or it needs testing from the community, don't mark as stale days-before-pr-stale: ${{ env.DAYS_BEFORE_PR_STALE }} days-before-pr-close: ${{ env.DAYS_BEFORE_PR_CLOSE }} From 3c456f5b8ddb63f6b75986226c0640e2a048ecca Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 30 Sep 2024 01:15:26 +0800 Subject: [PATCH 164/214] submaster: improve avg frequency calculation for efficiency (#33516) improve avg freq calculation for efficiency --- cereal/messaging/__init__.py | 21 +++++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/cereal/messaging/__init__.py b/cereal/messaging/__init__.py index 0c420e94e0..2466f6e9c0 100644 --- a/cereal/messaging/__init__.py +++ b/cereal/messaging/__init__.py @@ -109,12 +109,26 @@ class FrequencyTracker: self.min_freq = min_freq * 0.8 self.max_freq = max_freq * 1.2 self.recv_dts: Deque[float] = deque(maxlen=int(10 * freq)) + self.recv_dts_sum = 0.0 + self.recent_recv_dts: Deque[float] = deque(maxlen=int(freq)) + self.recent_recv_dts_sum = 0.0 self.prev_time = 0.0 def record_recv_time(self, cur_time: float) -> None: # TODO: Handle case where cur_time is less than prev_time if self.prev_time > 1e-5: - self.recv_dts.append(cur_time - self.prev_time) + dt = cur_time - self.prev_time + + if len(self.recv_dts) == self.recv_dts.maxlen: + self.recv_dts_sum -= self.recv_dts[0] + self.recv_dts.append(dt) + self.recv_dts_sum += dt + + if len(self.recent_recv_dts) == self.recent_recv_dts.maxlen: + self.recent_recv_dts_sum -= self.recent_recv_dts[0] + self.recent_recv_dts.append(dt) + self.recent_recv_dts_sum += dt + self.prev_time = cur_time @property @@ -122,12 +136,11 @@ class FrequencyTracker: if not self.recv_dts: return False - avg_freq = len(self.recv_dts) / sum(self.recv_dts) + avg_freq = len(self.recv_dts) / self.recv_dts_sum if self.min_freq <= avg_freq <= self.max_freq: return True - recent_dts = list(self.recv_dts)[-int(self.recv_dts.maxlen / 10):] - avg_freq_recent = len(recent_dts) / sum(recent_dts) + avg_freq_recent = len(self.recent_recv_dts) / self.recent_recv_dts_sum return self.min_freq <= avg_freq_recent <= self.max_freq From 3b6f1a0b39419ab7b2e68226934c7db3e0fa7b1a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 29 Sep 2024 10:55:39 -0700 Subject: [PATCH 165/214] test_onroad: update CPU usages after recent changes --- selfdrive/test/test_onroad.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 964848e3d3..b99662df78 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -36,19 +36,19 @@ CPU usage budget MAX_TOTAL_CPU = 265. # total for all 8 cores PROCS = { # Baseline CPU usage by process - "selfdrive.controls.controlsd": 18.0, - "selfdrive.selfdrived.selfdrived": 21.0, + "selfdrive.controls.controlsd": 16.0, + "selfdrive.selfdrived.selfdrived": 16.0, "selfdrive.car.card": 30.0, "./loggerd": 14.0, "./encoderd": 17.0, "./camerad": 14.5, - "selfdrive.controls.plannerd": 11.0, + "selfdrive.controls.plannerd": 9.0, "./ui": 18.0, "selfdrive.locationd.paramsd": 9.0, "./sensord": 7.0, "selfdrive.controls.radard": 2.0, "selfdrive.modeld.modeld": 17.0, - "selfdrive.modeld.dmonitoringmodeld": 8.0, + "selfdrive.modeld.dmonitoringmodeld": 11.0, "system.hardware.hardwared": 3.87, "selfdrive.locationd.calibrationd": 2.0, "selfdrive.locationd.torqued": 5.0, From a2b3b1540ded1a4476a028ff2dd549ae10caeadf Mon Sep 17 00:00:00 2001 From: Bruce Wayne Date: Sun, 29 Sep 2024 19:48:31 -0700 Subject: [PATCH 166/214] onnx model needs cast --- selfdrive/modeld/models/supercombo.onnx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index aeb3ea3b2b..100fd14c98 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:47417a13d8a8d6af6a1562834eee538e3b43242c6e277ab6f1978a78a6785b7d +oid sha256:21c88ca8a3de59fb11dc3e5888476f6bb627f3647eb0d199680d598e8bf31c0c size 62486469 From 390eee0717344b6c59e2478d2e96e998e3f1230b Mon Sep 17 00:00:00 2001 From: Bruce Wayne Date: Sun, 29 Sep 2024 20:02:32 -0700 Subject: [PATCH 167/214] Revert "onnx model needs cast" This reverts commit a2b3b1540ded1a4476a028ff2dd549ae10caeadf. --- selfdrive/modeld/models/supercombo.onnx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 100fd14c98..aeb3ea3b2b 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:21c88ca8a3de59fb11dc3e5888476f6bb627f3647eb0d199680d598e8bf31c0c +oid sha256:47417a13d8a8d6af6a1562834eee538e3b43242c6e277ab6f1978a78a6785b7d size 62486469 From 3b08501db379d4f718e7a76a249f1a0cf8f25db7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Sun, 29 Sep 2024 20:33:35 -0700 Subject: [PATCH 168/214] Game Boy Model V3 (#33674) * f4afab38-2ee3-4a71-904a-f2e5d4ec119a/400 * Model replay * fix onnx cast * tol --- selfdrive/modeld/models/supercombo.onnx | 2 +- selfdrive/test/process_replay/model_replay.py | 3 +++ selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 3 files changed, 5 insertions(+), 2 deletions(-) diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index aeb3ea3b2b..100fd14c98 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:47417a13d8a8d6af6a1562834eee538e3b43242c6e277ab6f1978a78a6785b7d +oid sha256:21c88ca8a3de59fb11dc3e5888476f6bb627f3647eb0d199680d598e8bf31c0c size 62486469 diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index af05ff5e44..9ee1b6be4e 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -129,6 +129,9 @@ if __name__ == "__main__": for i in range(4): for field in ('x', 'y', 'z', 't'): ignore.append(f'modelV2.laneLines.{i}.{field}') + for i in range(2): + for field in ('x', 'y', 'z', 't'): + ignore.append(f'modelV2.roadEdges.{i}.{field}') tolerance = .3 if PC else None results: Any = {TEST_ROUTE: {}} log_paths: Any = {TEST_ROUTE: {"models": {'ref': BASE_URL + log_fn, 'new': log_fn}}} diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 2faabd0587..182a17c7b7 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -ff10a803005f5116a8f3d88629503bc52b15b93f +76b8121429ad69d6548f744a39680ade324947e2 From 19bd96004e8e8de1e9923358c2b92ce64be10897 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Sun, 29 Sep 2024 23:23:16 -0700 Subject: [PATCH 169/214] Cleanup shift (#33677) * Cleanup shift code * Unsafe buffer copy * fix bugs --- selfdrive/modeld/models/commonmodel.cc | 13 +++++++------ selfdrive/modeld/models/commonmodel.h | 1 + selfdrive/modeld/transforms/loadyuv.cc | 22 ++++++++++++---------- selfdrive/modeld/transforms/loadyuv.cl | 8 +++++--- selfdrive/modeld/transforms/loadyuv.h | 6 +++++- 5 files changed, 30 insertions(+), 20 deletions(-) diff --git a/selfdrive/modeld/models/commonmodel.cc b/selfdrive/modeld/models/commonmodel.cc index d2d37bbc5a..a188a4ebd3 100644 --- a/selfdrive/modeld/models/commonmodel.cc +++ b/selfdrive/modeld/models/commonmodel.cc @@ -13,7 +13,7 @@ ModelFrame::ModelFrame(cl_device_id device_id, cl_context context) { y_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_WIDTH * MODEL_HEIGHT, NULL, &err)); u_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); v_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); - net_input_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_FRAME_SIZE * sizeof(uint8_t), NULL, &err)); + net_input_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, frame_size_bytes, NULL, &err)); transform_init(&transform, context, device_id); loadyuv_init(&loadyuv, context, device_id, MODEL_WIDTH, MODEL_HEIGHT); @@ -24,15 +24,16 @@ uint8_t* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, i yuv_cl, frame_width, frame_height, frame_stride, frame_uv_offset, y_cl, u_cl, v_cl, MODEL_WIDTH, MODEL_HEIGHT, projection); + loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, net_input_cl); if (output == NULL) { - loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, net_input_cl); - - std::memmove(&input_frames[0], &input_frames[MODEL_FRAME_SIZE], sizeof(uint8_t) * MODEL_FRAME_SIZE); - CL_CHECK(clEnqueueReadBuffer(q, net_input_cl, CL_TRUE, 0, MODEL_FRAME_SIZE * sizeof(uint8_t), &input_frames[MODEL_FRAME_SIZE], 0, nullptr, nullptr)); + std::memmove(&input_frames[0], &input_frames[MODEL_FRAME_SIZE], frame_size_bytes); + CL_CHECK(clEnqueueReadBuffer(q, net_input_cl, CL_TRUE, 0, frame_size_bytes, &input_frames[MODEL_FRAME_SIZE], 0, nullptr, nullptr)); clFinish(q); return &input_frames[0]; } else { - loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, *output, true); + copy_queue(&loadyuv, q, *output, *output, frame_size_bytes, 0, frame_size_bytes); + copy_queue(&loadyuv, q, net_input_cl, *output, 0, frame_size_bytes, frame_size_bytes); + // NOTE: Since thneed is using a different command queue, this clFinish is needed to ensure the image is ready. clFinish(q); return NULL; diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h index ea39466670..fb527fc7a1 100644 --- a/selfdrive/modeld/models/commonmodel.h +++ b/selfdrive/modeld/models/commonmodel.h @@ -26,6 +26,7 @@ public: const int MODEL_HEIGHT = 256; const int MODEL_FRAME_SIZE = MODEL_WIDTH * MODEL_HEIGHT * 3 / 2; const int buf_size = MODEL_FRAME_SIZE * 2; + const size_t frame_size_bytes = MODEL_FRAME_SIZE * sizeof(uint8_t); private: Transform transform; diff --git a/selfdrive/modeld/transforms/loadyuv.cc b/selfdrive/modeld/transforms/loadyuv.cc index c7ce7b0830..c93f5cd038 100644 --- a/selfdrive/modeld/transforms/loadyuv.cc +++ b/selfdrive/modeld/transforms/loadyuv.cc @@ -33,17 +33,8 @@ void loadyuv_destroy(LoadYUVState* s) { void loadyuv_queue(LoadYUVState* s, cl_command_queue q, cl_mem y_cl, cl_mem u_cl, cl_mem v_cl, - cl_mem out_cl, bool do_shift) { + cl_mem out_cl) { cl_int global_out_off = 0; - if (do_shift) { - // shift the image in slot 1 to slot 0, then place the new image in slot 1 - global_out_off += (s->width*s->height) + (s->width/2)*(s->height/2)*2; - CL_CHECK(clSetKernelArg(s->copy_krnl, 0, sizeof(cl_mem), &out_cl)); - CL_CHECK(clSetKernelArg(s->copy_krnl, 1, sizeof(cl_int), &global_out_off)); - const size_t copy_work_size = global_out_off/8; - CL_CHECK(clEnqueueNDRangeKernel(q, s->copy_krnl, 1, NULL, - ©_work_size, NULL, 0, 0, NULL)); - } CL_CHECK(clSetKernelArg(s->loadys_krnl, 0, sizeof(cl_mem), &y_cl)); CL_CHECK(clSetKernelArg(s->loadys_krnl, 1, sizeof(cl_mem), &out_cl)); @@ -72,3 +63,14 @@ void loadyuv_queue(LoadYUVState* s, cl_command_queue q, CL_CHECK(clEnqueueNDRangeKernel(q, s->loaduv_krnl, 1, NULL, &loaduv_work_size, NULL, 0, 0, NULL)); } + +void copy_queue(LoadYUVState* s, cl_command_queue q, cl_mem src, cl_mem dst, + size_t src_offset, size_t dst_offset, size_t size) { + CL_CHECK(clSetKernelArg(s->copy_krnl, 0, sizeof(cl_mem), &src)); + CL_CHECK(clSetKernelArg(s->copy_krnl, 1, sizeof(cl_mem), &dst)); + CL_CHECK(clSetKernelArg(s->copy_krnl, 2, sizeof(cl_int), &src_offset)); + CL_CHECK(clSetKernelArg(s->copy_krnl, 3, sizeof(cl_int), &dst_offset)); + const size_t copy_work_size = size/8; + CL_CHECK(clEnqueueNDRangeKernel(q, s->copy_krnl, 1, NULL, + ©_work_size, NULL, 0, 0, NULL)); +} \ No newline at end of file diff --git a/selfdrive/modeld/transforms/loadyuv.cl b/selfdrive/modeld/transforms/loadyuv.cl index 3a6b3ebc4f..970187a6d7 100644 --- a/selfdrive/modeld/transforms/loadyuv.cl +++ b/selfdrive/modeld/transforms/loadyuv.cl @@ -37,9 +37,11 @@ __kernel void loaduv(__global uchar8 const * const in, out[gid + out_offset / 8] = inv; } -__kernel void copy(__global uchar8 * inout, - int in_offset) +__kernel void copy(__global uchar8 * in, + __global uchar8 * out, + int in_offset, + int out_offset) { const int gid = get_global_id(0); - inout[gid] = inout[gid + in_offset / 8]; + out[gid + out_offset / 8] = in[gid + in_offset / 8]; } diff --git a/selfdrive/modeld/transforms/loadyuv.h b/selfdrive/modeld/transforms/loadyuv.h index 7d27ef5d46..659059cd25 100644 --- a/selfdrive/modeld/transforms/loadyuv.h +++ b/selfdrive/modeld/transforms/loadyuv.h @@ -13,4 +13,8 @@ void loadyuv_destroy(LoadYUVState* s); void loadyuv_queue(LoadYUVState* s, cl_command_queue q, cl_mem y_cl, cl_mem u_cl, cl_mem v_cl, - cl_mem out_cl, bool do_shift = false); + cl_mem out_cl); + + +void copy_queue(LoadYUVState* s, cl_command_queue q, cl_mem src, cl_mem dst, + size_t src_offset, size_t dst_offset, size_t size); \ No newline at end of file From d4e257213d0c7b097e5b1f0d3c983a0a3e7b7137 Mon Sep 17 00:00:00 2001 From: Bruce Wayne Date: Mon, 30 Sep 2024 00:05:28 -0700 Subject: [PATCH 170/214] Modeld: cannot run without wide img --- selfdrive/modeld/modeld.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index 86813fcb8e..abaaf299f7 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -96,8 +96,7 @@ class ModelState: # if getCLBuffer is not None, frame will be None self.model.setInputBuffer("input_imgs", self.frame.prepare(buf, transform.flatten(), self.model.getCLBuffer("input_imgs"))) - if wbuf is not None: - self.model.setInputBuffer("big_input_imgs", self.wide_frame.prepare(wbuf, transform_wide.flatten(), self.model.getCLBuffer("big_input_imgs"))) + self.model.setInputBuffer("big_input_imgs", self.wide_frame.prepare(wbuf, transform_wide.flatten(), self.model.getCLBuffer("big_input_imgs"))) if prepare_only: return None From 4a2c24b5b37dcafa67a11142ac8d0cdca6720586 Mon Sep 17 00:00:00 2001 From: Mauricio Alvarez Leon <65101411+BBBmau@users.noreply.github.com> Date: Mon, 30 Sep 2024 08:59:39 -0700 Subject: [PATCH 171/214] `CI`: fix if conditional in `ui_preview.yaml` (#33675) * fix if conditional * open * open fix --- .github/workflows/ui_preview.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/ui_preview.yaml b/.github/workflows/ui_preview.yaml index 972a96dc39..13337bacbe 100644 --- a/.github/workflows/ui_preview.yaml +++ b/.github/workflows/ui_preview.yaml @@ -135,11 +135,13 @@ jobs: TABLE="${TABLE}" TABLE="${TABLE}
" + if $open; then TABLE="
${TABLE}" else TABLE="
${TABLE}" fi + echo "DIFF=$DIFF$TABLE" >> "$GITHUB_OUTPUT" - name: Saving proposed ui From c6cd23210cc156f9e474a8065c5ade45d14602c3 Mon Sep 17 00:00:00 2001 From: ugtthis <142481257+ugtthis@users.noreply.github.com> Date: Mon, 30 Sep 2024 09:00:00 -0700 Subject: [PATCH 172/214] prime.cc/typo: Fixes variable name typo (#33678) Fixes variable name typo --- selfdrive/ui/qt/widgets/prime.cc | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index 9bc96fcdad..62f5c0ab50 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -180,20 +180,20 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { QFrame* finishRegistration = new QFrame; finishRegistration->setObjectName("primeWidget"); - QVBoxLayout* finishRegistationLayout = new QVBoxLayout(finishRegistration); - finishRegistationLayout->setSpacing(38); - finishRegistationLayout->setContentsMargins(64, 48, 64, 48); + QVBoxLayout* finishRegistrationLayout = new QVBoxLayout(finishRegistration); + finishRegistrationLayout->setSpacing(38); + finishRegistrationLayout->setContentsMargins(64, 48, 64, 48); QLabel* registrationTitle = new QLabel(tr("Finish Setup")); registrationTitle->setStyleSheet("font-size: 75px; font-weight: bold;"); - finishRegistationLayout->addWidget(registrationTitle); + finishRegistrationLayout->addWidget(registrationTitle); QLabel* registrationDescription = new QLabel(tr("Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.")); registrationDescription->setWordWrap(true); registrationDescription->setStyleSheet("font-size: 50px; font-weight: light;"); - finishRegistationLayout->addWidget(registrationDescription); + finishRegistrationLayout->addWidget(registrationDescription); - finishRegistationLayout->addStretch(); + finishRegistrationLayout->addStretch(); QPushButton* pair = new QPushButton(tr("Pair device")); pair->setStyleSheet(R"( @@ -208,7 +208,7 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { background-color: #3049F4; } )"); - finishRegistationLayout->addWidget(pair); + finishRegistrationLayout->addWidget(pair); popup = new PairingPopup(this); QObject::connect(pair, &QPushButton::clicked, popup, &PairingPopup::exec); From b4cf9c09888a7e85ada4096a2b7e331c860df86d Mon Sep 17 00:00:00 2001 From: commaci-public <60409688+commaci-public@users.noreply.github.com> Date: Mon, 30 Sep 2024 13:46:04 -0700 Subject: [PATCH 173/214] [bot] Update Python packages (#33679) * Update Python packages * thats unfortunate * global --------- Co-authored-by: Vehicle Researcher Co-authored-by: Maxime Desroches --- SConstruct | 4 + opendbc_repo | 2 +- panda | 2 +- uv.lock | 342 ++++++++++++++++++++++++++------------------------- 4 files changed, 180 insertions(+), 170 deletions(-) diff --git a/SConstruct b/SConstruct index fea47440cf..8aa46b9359 100644 --- a/SConstruct +++ b/SConstruct @@ -64,6 +64,10 @@ AddOption('--pc-thneed', dest='pc_thneed', help='use thneed on pc') +AddOption('--mutation', + action='store_true', + help='generate mutation-ready code') + AddOption('--minimal', action='store_false', dest='extras', diff --git a/opendbc_repo b/opendbc_repo index 173ab90402..6a35629a6b 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 173ab90402f85c07cd65750c7f31cc97a8b07d59 +Subproject commit 6a35629a6b5f55167ed9d9923411ce9e49e6a76f diff --git a/panda b/panda index 2037a2ead7..08c95bf47b 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 2037a2ead7257deadf6165734fd19b9b87de6eb7 +Subproject commit 08c95bf47ba6d0c5d11a7616e42e10b8dbde19eb diff --git a/uv.lock b/uv.lock index 2be225145b..81c6fa00c2 100644 --- a/uv.lock +++ b/uv.lock @@ -11,16 +11,16 @@ resolution-markers = [ [[package]] name = "aiohappyeyeballs" -version = "2.4.0" +version = "2.4.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/2d/f7/22bba300a16fd1cad99da1a23793fe43963ee326d012fdf852d0b4035955/aiohappyeyeballs-2.4.0.tar.gz", hash = "sha256:55a1714f084e63d49639800f95716da97a1f173d46a16dfcfda0016abb93b6b2", size = 16786 } +sdist = { url = "https://files.pythonhosted.org/packages/c7/d9/e710a5c9e51b4d5a977c823ce323a81d344da8c1b6fba16bb270a8be800d/aiohappyeyeballs-2.4.2.tar.gz", hash = "sha256:4ca893e6c5c1f5bf3888b04cb5a3bee24995398efef6e0b9f747b5e89d84fd74", size = 18391 } wheels = [ - { url = "https://files.pythonhosted.org/packages/18/b6/58ea188899950d759a837f9a58b2aee1d1a380ea4d6211ce9b1823748851/aiohappyeyeballs-2.4.0-py3-none-any.whl", hash = "sha256:7ce92076e249169a13c2f49320d1967425eaf1f407522d707d59cac7628d62bd", size = 12155 }, + { url = "https://files.pythonhosted.org/packages/13/64/40165ff77ade5203284e3015cf88e11acb07d451f6bf83fff71192912a0d/aiohappyeyeballs-2.4.2-py3-none-any.whl", hash = "sha256:8522691d9a154ba1145b157d6d5c15e5c692527ce6a53c5e5f9876977f6dab2f", size = 14105 }, ] [[package]] name = "aiohttp" -version = "3.10.5" +version = "3.10.8" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "aiohappyeyeballs" }, @@ -30,53 +30,53 @@ dependencies = [ { name = "multidict" }, { name = "yarl" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ca/28/ca549838018140b92a19001a8628578b0f2a3b38c16826212cc6f706e6d4/aiohttp-3.10.5.tar.gz", hash = "sha256:f071854b47d39591ce9a17981c46790acb30518e2f83dfca8db2dfa091178691", size = 7524360 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/f1/90/54ccb1e4eadfb6c95deff695582453f6208584431d69bf572782e9ae542b/aiohttp-3.10.5-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8c6a4e5e40156d72a40241a25cc226051c0a8d816610097a8e8f517aeacd59a2", size = 586455 }, - { url = "https://files.pythonhosted.org/packages/c3/7a/95e88c02756e7e718f054e1bb3ec6ad5d0ee4a2ca2bb1768c5844b3de30a/aiohttp-3.10.5-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2c634a3207a5445be65536d38c13791904fda0748b9eabf908d3fe86a52941cf", size = 397255 }, - { url = "https://files.pythonhosted.org/packages/07/4f/767387b39990e1ee9aba8ce642abcc286d84d06e068dc167dab983898f18/aiohttp-3.10.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:4aff049b5e629ef9b3e9e617fa6e2dfeda1bf87e01bcfecaf3949af9e210105e", size = 388973 }, - { url = "https://files.pythonhosted.org/packages/61/46/0df41170a4d228c07b661b1ba9d87101d99a79339dc93b8b1183d8b20545/aiohttp-3.10.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1942244f00baaacaa8155eca94dbd9e8cc7017deb69b75ef67c78e89fdad3c77", size = 1326126 }, - { url = "https://files.pythonhosted.org/packages/af/20/da0d65e07ce49d79173fed41598f487a0a722e87cfbaa8bb7e078a7c1d39/aiohttp-3.10.5-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e04a1f2a65ad2f93aa20f9ff9f1b672bf912413e5547f60749fa2ef8a644e061", size = 1364538 }, - { url = "https://files.pythonhosted.org/packages/aa/20/b59728405114e57541ba9d5b96033e69d004e811ded299537f74237629ca/aiohttp-3.10.5-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7f2bfc0032a00405d4af2ba27f3c429e851d04fad1e5ceee4080a1c570476697", size = 1399896 }, - { url = "https://files.pythonhosted.org/packages/2a/92/006690c31b830acbae09d2618e41308fe4c81c0679b3b33a3af859e0b7bf/aiohttp-3.10.5-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:424ae21498790e12eb759040bbb504e5e280cab64693d14775c54269fd1d2bb7", size = 1312914 }, - { url = "https://files.pythonhosted.org/packages/d4/71/1a253ca215b6c867adbd503f1e142117527ea8775e65962bc09b2fad1d2c/aiohttp-3.10.5-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:975218eee0e6d24eb336d0328c768ebc5d617609affaca5dbbd6dd1984f16ed0", size = 1271301 }, - { url = "https://files.pythonhosted.org/packages/0a/ab/5d1d9ff9ce6cce8fa54774d0364e64a0f3cd50e512ff09082ced8e5217a1/aiohttp-3.10.5-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:4120d7fefa1e2d8fb6f650b11489710091788de554e2b6f8347c7a20ceb003f5", size = 1291652 }, - { url = "https://files.pythonhosted.org/packages/75/5f/f90510ea954b9ae6e7a53d2995b97a3e5c181110fdcf469bc9238445871d/aiohttp-3.10.5-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:b90078989ef3fc45cf9221d3859acd1108af7560c52397ff4ace8ad7052a132e", size = 1286289 }, - { url = "https://files.pythonhosted.org/packages/be/9e/1f523414237798660921817c82b9225a363af436458caf584d2fa6a2eb4a/aiohttp-3.10.5-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:ba5a8b74c2a8af7d862399cdedce1533642fa727def0b8c3e3e02fcb52dca1b1", size = 1341848 }, - { url = "https://files.pythonhosted.org/packages/f6/36/443472ddaa85d7d80321fda541d9535b23ecefe0bf5792cc3955ea635190/aiohttp-3.10.5-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:02594361128f780eecc2a29939d9dfc870e17b45178a867bf61a11b2a4367277", size = 1361619 }, - { url = "https://files.pythonhosted.org/packages/19/f6/3ecbac0bc4359c7d7ba9e85c6b10f57e20edaf1f97751ad2f892db231ad0/aiohttp-3.10.5-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:8fb4fc029e135859f533025bc82047334e24b0d489e75513144f25408ecaf058", size = 1320869 }, - { url = "https://files.pythonhosted.org/packages/34/7e/ed74ffb36e3a0cdec1b05d8fbaa29cb532371d5a20058b3a8052fc90fe7c/aiohttp-3.10.5-cp311-cp311-win32.whl", hash = "sha256:e1ca1ef5ba129718a8fc827b0867f6aa4e893c56eb00003b7367f8a733a9b072", size = 359271 }, - { url = "https://files.pythonhosted.org/packages/98/1b/718901f04bc8c886a742be9e83babb7b93facabf7c475cc95e2b3ab80b4d/aiohttp-3.10.5-cp311-cp311-win_amd64.whl", hash = "sha256:349ef8a73a7c5665cca65c88ab24abe75447e28aa3bc4c93ea5093474dfdf0ff", size = 379143 }, - { url = "https://files.pythonhosted.org/packages/d9/1c/74f9dad4a2fc4107e73456896283d915937f48177b99867b63381fadac6e/aiohttp-3.10.5-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:305be5ff2081fa1d283a76113b8df7a14c10d75602a38d9f012935df20731487", size = 583468 }, - { url = "https://files.pythonhosted.org/packages/12/29/68d090551f2b58ce76c2b436ced8dd2dfd32115d41299bf0b0c308a5483c/aiohttp-3.10.5-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:3a1c32a19ee6bbde02f1cb189e13a71b321256cc1d431196a9f824050b160d5a", size = 394066 }, - { url = "https://files.pythonhosted.org/packages/8f/f7/971f88b4cdcaaa4622925ba7d86de47b48ec02a9040a143514b382f78da4/aiohttp-3.10.5-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:61645818edd40cc6f455b851277a21bf420ce347baa0b86eaa41d51ef58ba23d", size = 389098 }, - { url = "https://files.pythonhosted.org/packages/f1/5a/fe3742efdce551667b2ddf1158b27c5b8eb1edc13d5e14e996e52e301025/aiohttp-3.10.5-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6c225286f2b13bab5987425558baa5cbdb2bc925b2998038fa028245ef421e75", size = 1332742 }, - { url = "https://files.pythonhosted.org/packages/1a/52/a25c0334a1845eb4967dff279151b67ca32a948145a5812ed660ed900868/aiohttp-3.10.5-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8ba01ebc6175e1e6b7275c907a3a36be48a2d487549b656aa90c8a910d9f3178", size = 1372134 }, - { url = "https://files.pythonhosted.org/packages/96/3d/33c1d8efc2d8ec36bff9a8eca2df9fdf8a45269c6e24a88e74f2aa4f16bd/aiohttp-3.10.5-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8eaf44ccbc4e35762683078b72bf293f476561d8b68ec8a64f98cf32811c323e", size = 1414413 }, - { url = "https://files.pythonhosted.org/packages/64/74/0f1ddaa5f0caba1d946f0dd0c31f5744116e4a029beec454ec3726d3311f/aiohttp-3.10.5-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b1c43eb1ab7cbf411b8e387dc169acb31f0ca0d8c09ba63f9eac67829585b44f", size = 1328107 }, - { url = "https://files.pythonhosted.org/packages/0a/32/c10118f0ad50e4093227234f71fd0abec6982c29367f65f32ee74ed652c4/aiohttp-3.10.5-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:de7a5299827253023c55ea549444e058c0eb496931fa05d693b95140a947cb73", size = 1280126 }, - { url = "https://files.pythonhosted.org/packages/c6/c9/77e3d648d97c03a42acfe843d03e97be3c5ef1b4d9de52e5bd2d28eed8e7/aiohttp-3.10.5-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:4790f0e15f00058f7599dab2b206d3049d7ac464dc2e5eae0e93fa18aee9e7bf", size = 1292660 }, - { url = "https://files.pythonhosted.org/packages/7e/5d/99c71f8e5c8b64295be421b4c42d472766b263a1fe32e91b64bf77005bf2/aiohttp-3.10.5-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:44b324a6b8376a23e6ba25d368726ee3bc281e6ab306db80b5819999c737d820", size = 1300988 }, - { url = "https://files.pythonhosted.org/packages/8f/2c/76d2377dd947f52fbe8afb19b18a3b816d66c7966755c04030f93b1f7b2d/aiohttp-3.10.5-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:0d277cfb304118079e7044aad0b76685d30ecb86f83a0711fc5fb257ffe832ca", size = 1339268 }, - { url = "https://files.pythonhosted.org/packages/fd/e6/3d9d935cc705d57ed524d82ec5d6b678a53ac1552720ae41282caa273584/aiohttp-3.10.5-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:54d9ddea424cd19d3ff6128601a4a4d23d54a421f9b4c0fff740505813739a91", size = 1366993 }, - { url = "https://files.pythonhosted.org/packages/fe/c2/f7eed4d602f3f224600d03ab2e1a7734999b0901b1c49b94dc5891340433/aiohttp-3.10.5-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:4f1c9866ccf48a6df2b06823e6ae80573529f2af3a0992ec4fe75b1a510df8a6", size = 1329459 }, - { url = "https://files.pythonhosted.org/packages/ce/8f/27f205b76531fc592abe29e1ad265a16bf934a9f609509c02d765e6a8055/aiohttp-3.10.5-cp312-cp312-win32.whl", hash = "sha256:dc4826823121783dccc0871e3f405417ac116055bf184ac04c36f98b75aacd12", size = 356968 }, - { url = "https://files.pythonhosted.org/packages/39/8c/4f6c0b2b3629f6be6c81ab84d9d577590f74f01d4412bfc4067958eaa1e1/aiohttp-3.10.5-cp312-cp312-win_amd64.whl", hash = "sha256:22c0a23a3b3138a6bf76fc553789cb1a703836da86b0f306b6f0dc1617398abc", size = 377650 }, - { url = "https://files.pythonhosted.org/packages/7b/b9/03b4327897a5b5d29338fa9b514f1c2f66a3e4fc88a4e40fad478739314d/aiohttp-3.10.5-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:7f6b639c36734eaa80a6c152a238242bedcee9b953f23bb887e9102976343092", size = 576994 }, - { url = "https://files.pythonhosted.org/packages/67/1b/20c2e159cd07b8ed6dde71c2258233902fdf415b2fe6174bd2364ba63107/aiohttp-3.10.5-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:f29930bc2921cef955ba39a3ff87d2c4398a0394ae217f41cb02d5c26c8b1b77", size = 390684 }, - { url = "https://files.pythonhosted.org/packages/4d/6b/ff83b34f157e370431d8081c5d1741963f4fb12f9aaddb2cacbf50305225/aiohttp-3.10.5-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:f489a2c9e6455d87eabf907ac0b7d230a9786be43fbe884ad184ddf9e9c1e385", size = 386176 }, - { url = "https://files.pythonhosted.org/packages/4d/a1/6e92817eb657de287560962df4959b7ddd22859c4b23a0309e2d3de12538/aiohttp-3.10.5-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:123dd5b16b75b2962d0fff566effb7a065e33cd4538c1692fb31c3bda2bfb972", size = 1303310 }, - { url = "https://files.pythonhosted.org/packages/04/29/200518dc7a39c30ae6d5bc232d7207446536e93d3d9299b8e95db6e79c54/aiohttp-3.10.5-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b98e698dc34966e5976e10bbca6d26d6724e6bdea853c7c10162a3235aba6e16", size = 1340445 }, - { url = "https://files.pythonhosted.org/packages/8e/20/53f7bba841ba7b5bb5dea580fea01c65524879ba39cb917d08c845524717/aiohttp-3.10.5-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c3b9162bab7e42f21243effc822652dc5bb5e8ff42a4eb62fe7782bcbcdfacf6", size = 1385121 }, - { url = "https://files.pythonhosted.org/packages/f1/b4/d99354ad614c48dd38fb1ee880a1a54bd9ab2c3bcad3013048d4a1797d3a/aiohttp-3.10.5-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1923a5c44061bffd5eebeef58cecf68096e35003907d8201a4d0d6f6e387ccaa", size = 1299669 }, - { url = "https://files.pythonhosted.org/packages/51/39/ca1de675f2a5729c71c327e52ac6344e63f036bd37281686ae5c3fb13bfb/aiohttp-3.10.5-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d55f011da0a843c3d3df2c2cf4e537b8070a419f891c930245f05d329c4b0689", size = 1252638 }, - { url = "https://files.pythonhosted.org/packages/54/cf/a3ae7ff43138422d477348e309ef8275779701bf305ff6054831ef98b782/aiohttp-3.10.5-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:afe16a84498441d05e9189a15900640a2d2b5e76cf4efe8cbb088ab4f112ee57", size = 1266889 }, - { url = "https://files.pythonhosted.org/packages/6e/7a/c6027ad70d9fb23cf254a26144de2723821dade1a624446aa22cd0b6d012/aiohttp-3.10.5-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:f8112fb501b1e0567a1251a2fd0747baae60a4ab325a871e975b7bb67e59221f", size = 1266249 }, - { url = "https://files.pythonhosted.org/packages/64/fd/ed136d46bc2c7e3342fed24662b4827771d55ceb5a7687847aae977bfc17/aiohttp-3.10.5-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:1e72589da4c90337837fdfe2026ae1952c0f4a6e793adbbfbdd40efed7c63599", size = 1311036 }, - { url = "https://files.pythonhosted.org/packages/76/9a/43eeb0166f1119256d6f43468f900db1aed7fbe32069d2a71c82f987db4d/aiohttp-3.10.5-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:4d46c7b4173415d8e583045fbc4daa48b40e31b19ce595b8d92cf639396c15d5", size = 1338756 }, - { url = "https://files.pythonhosted.org/packages/d5/bc/d01ff0810b3f5e26896f76d44225ed78b088ddd33079b85cd1a23514318b/aiohttp-3.10.5-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:33e6bc4bab477c772a541f76cd91e11ccb6d2efa2b8d7d7883591dfb523e5987", size = 1299976 }, - { url = "https://files.pythonhosted.org/packages/3e/c9/50a297c4f7ab57a949f4add2d3eafe5f3e68bb42f739e933f8b32a092bda/aiohttp-3.10.5-cp313-cp313-win32.whl", hash = "sha256:c58c6837a2c2a7cf3133983e64173aec11f9c2cd8e87ec2fdc16ce727bcf1a04", size = 355609 }, - { url = "https://files.pythonhosted.org/packages/65/28/aee9d04fb0b3b1f90622c338a08e54af5198e704a910e20947c473298fd0/aiohttp-3.10.5-cp313-cp313-win_amd64.whl", hash = "sha256:38172a70005252b6893088c0f5e8a47d173df7cc2b2bd88650957eb84fcf5022", size = 375697 }, +sdist = { url = "https://files.pythonhosted.org/packages/4e/05/da5ff89c85444a6ade9079e73580fb3f78c6ba0e170a2472f15400d03e02/aiohttp-3.10.8.tar.gz", hash = "sha256:21f8225f7dc187018e8433c9326be01477fb2810721e048b33ac49091b19fb4a", size = 7540022 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/07/ca/2fc934c4c86865d0eb9c46f8f57443f0655f2a4a5c1dde60ec1d6d0f0881/aiohttp-3.10.8-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:33a68011a38020ed4ff41ae0dbf4a96a202562ecf2024bdd8f65385f1d07f6ef", size = 586333 }, + { url = "https://files.pythonhosted.org/packages/4a/07/7215d085dc10dd2e10f36832b2ca278f30970b4db98d5ebfed9e228d5c0c/aiohttp-3.10.8-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:6c7efa6616a95e3bd73b8a69691012d2ef1f95f9ea0189e42f338fae080c2fc6", size = 398817 }, + { url = "https://files.pythonhosted.org/packages/c4/e4/77b029c12d025d1e448662977f1e7c6fb33a19c42181c8d20c2791b5c5d9/aiohttp-3.10.8-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ddb9b9764cfb4459acf01c02d2a59d3e5066b06a846a364fd1749aa168efa2be", size = 390465 }, + { url = "https://files.pythonhosted.org/packages/17/f5/206e6a58a3a5be39662a07f531a6033384e361e272735437c5c15176c601/aiohttp-3.10.8-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3c7f270f4ca92760f98a42c45a58674fff488e23b144ec80b1cc6fa2effed377", size = 1306316 }, + { url = "https://files.pythonhosted.org/packages/33/e7/3b6b5ad02e367f30927bb93263127c23290f5b11900d036429f4787e1948/aiohttp-3.10.8-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:6984dda9d79064361ab58d03f6c1e793ea845c6cfa89ffe1a7b9bb400dfd56bd", size = 1344486 }, + { url = "https://files.pythonhosted.org/packages/ae/9f/f27ba4cd2bffb4885aa35827a21878dbd3f50d6e5b205ce1107ce79edc40/aiohttp-3.10.8-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3f6d47e392c27206701565c8df4cac6ebed28fdf6dcaea5b1eea7a4631d8e6db", size = 1378320 }, + { url = "https://files.pythonhosted.org/packages/54/76/b106eb516d327527a6b1e0409a3553745ad34480eddfd0d7cad48ddc9848/aiohttp-3.10.8-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a72f89aea712c619b2ca32c6f4335c77125ede27530ad9705f4f349357833695", size = 1292542 }, + { url = "https://files.pythonhosted.org/packages/7d/0c/c116a27253c0bc76959ab8df5a109d482c0977d4028e1b3ec7fac038bb1a/aiohttp-3.10.8-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c36074b26f3263879ba8e4dbd33db2b79874a3392f403a70b772701363148b9f", size = 1251608 }, + { url = "https://files.pythonhosted.org/packages/9e/05/f9624dc401f72a3ee4cddea1a555b430e9a7be9d0cd2ab53dbec2fc78279/aiohttp-3.10.8-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:e32148b4a745e70a255a1d44b5664de1f2e24fcefb98a75b60c83b9e260ddb5b", size = 1271551 }, + { url = "https://files.pythonhosted.org/packages/6d/77/19a032cfb9fdfd69591cf173c23c62992774b2ff978e4dab3038a1955e14/aiohttp-3.10.8-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:5aa1a073514cf59c81ad49a4ed9b5d72b2433638cd53160fd2f3a9cfa94718db", size = 1266089 }, + { url = "https://files.pythonhosted.org/packages/12/63/58ebde5ea32cf5f19c83d6dc2c582ca5f0c42ce4cf084216a3cda4b2e34a/aiohttp-3.10.8-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:d3a79200a9d5e621c4623081ddb25380b713c8cf5233cd11c1aabad990bb9381", size = 1321455 }, + { url = "https://files.pythonhosted.org/packages/1a/22/d8439a280161b542a28f88794ab55917cdc672544b87db52d3c41ce8d9a1/aiohttp-3.10.8-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:e45fdfcb2d5bcad83373e4808825b7512953146d147488114575780640665027", size = 1339057 }, + { url = "https://files.pythonhosted.org/packages/bc/67/1a76a69adfe3013863df4142d37059fb357146815b29596945d61fb940cb/aiohttp-3.10.8-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:f78e2a78432c537ae876a93013b7bc0027ba5b93ad7b3463624c4b6906489332", size = 1298892 }, + { url = "https://files.pythonhosted.org/packages/38/13/7294cb679ab7a80e5b0d0aa97c527690cffed2f34cb8892d73ebdb4204e8/aiohttp-3.10.8-cp311-cp311-win32.whl", hash = "sha256:f8179855a4e4f3b931cb1764ec87673d3fbdcca2af496c8d30567d7b034a13db", size = 362066 }, + { url = "https://files.pythonhosted.org/packages/bc/4a/8881d4d7259427897e1a314c2724e65fd0d20084c72cac8360665f96c347/aiohttp-3.10.8-cp311-cp311-win_amd64.whl", hash = "sha256:ef9b484604af05ca745b6108ca1aaa22ae1919037ae4f93aaf9a37ba42e0b835", size = 381406 }, + { url = "https://files.pythonhosted.org/packages/bb/ce/a8ff9f5bd2b36e3049cfe8d53656fed03075221ff42f946c581325bdc8fc/aiohttp-3.10.8-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:ab2d6523575fc98896c80f49ac99e849c0b0e69cc80bf864eed6af2ae728a52b", size = 583366 }, + { url = "https://files.pythonhosted.org/packages/91/5c/75287ab8a6ae9cbe02d45ebb36b1e899c11da5eb47060e0dcb98ee30a951/aiohttp-3.10.8-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:f5d5d5401744dda50b943d8764508d0e60cc2d3305ac1e6420935861a9d544bc", size = 395525 }, + { url = "https://files.pythonhosted.org/packages/a8/5a/aca17d71eb7e0f4611b2f28cb04e05aaebe6c7c2a7d1364e494da9722714/aiohttp-3.10.8-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:de23085cf90911600ace512e909114385026b16324fa203cc74c81f21fd3276a", size = 390727 }, + { url = "https://files.pythonhosted.org/packages/1b/ee/c1663449864ec9dd3d2a61dde09112bea5e1d881496c36146a96fe85da62/aiohttp-3.10.8-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4618f0d2bf523043866a9ff8458900d8eb0a6d4018f251dae98e5f1fb699f3a8", size = 1311898 }, + { url = "https://files.pythonhosted.org/packages/8b/7e/ed2eb276fdf946a9303f3f80033555d3eaa0eadbcdd0c31b153e33b495fc/aiohttp-3.10.8-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:21c1925541ca84f7b5e0df361c0a813a7d6a56d3b0030ebd4b220b8d232015f9", size = 1350380 }, + { url = "https://files.pythonhosted.org/packages/0c/3f/1d74a1311b14a1d69aad06775ffc1c09c195db67d951c8319220b9c64fdc/aiohttp-3.10.8-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:497a7d20caea8855c5429db3cdb829385467217d7feb86952a6107e033e031b9", size = 1392486 }, + { url = "https://files.pythonhosted.org/packages/9f/95/b940d71b1f61cf2ed48f2918c292609d251dba012a8e033afc0c778ed6a7/aiohttp-3.10.8-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c887019dbcb4af58a091a45ccf376fffe800b5531b45c1efccda4bedf87747ea", size = 1306135 }, + { url = "https://files.pythonhosted.org/packages/9b/25/b096aebc2f9b3ed738a4a667b841780b1dcd23ce5dff7dfabab4d09de4c8/aiohttp-3.10.8-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:40d2d719c3c36a7a65ed26400e2b45b2d9ed7edf498f4df38b2ae130f25a0d01", size = 1260085 }, + { url = "https://files.pythonhosted.org/packages/9e/cf/bc024d8a848ee4feaae6a037034cf8b173a14ea9cb5c2988b6e5018abf33/aiohttp-3.10.8-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:57359785f27394a8bcab0da6dcd46706d087dfebf59a8d0ad2e64a4bc2f6f94f", size = 1270968 }, + { url = "https://files.pythonhosted.org/packages/40/1d/2513347c445d1aaa694e79f4d45f80d777ea3e4d772d9480577834dc2c1c/aiohttp-3.10.8-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:a961ee6f2cdd1a2be4735333ab284691180d40bad48f97bb598841bfcbfb94ec", size = 1280083 }, + { url = "https://files.pythonhosted.org/packages/22/e1/4be1b057044c3d874e795744446c682715b232281adbe94612ddc9877ee4/aiohttp-3.10.8-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:fe3d79d6af839ffa46fdc5d2cf34295390894471e9875050eafa584cb781508d", size = 1316638 }, + { url = "https://files.pythonhosted.org/packages/6d/c3/84492f103c724d3149bba413e1dc081e573c44013bd2cc8f4addd51cf365/aiohttp-3.10.8-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:9a281cba03bdaa341c70b7551b2256a88d45eead149f48b75a96d41128c240b3", size = 1343764 }, + { url = "https://files.pythonhosted.org/packages/cf/b7/50cc827dd54df087d7c30293b29fbc13a7ea45a3ac54a4a12127b271265c/aiohttp-3.10.8-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:c6769d71bfb1ed60321363a9bc05e94dcf05e38295ef41d46ac08919e5b00d19", size = 1306007 }, + { url = "https://files.pythonhosted.org/packages/1e/c0/a4cb21ad677757368743d73aff27047dfc0d7248cb39dec06c059b773c24/aiohttp-3.10.8-cp312-cp312-win32.whl", hash = "sha256:a3081246bab4d419697ee45e555cef5cd1def7ac193dff6f50be761d2e44f194", size = 359125 }, + { url = "https://files.pythonhosted.org/packages/d2/0f/1ecbc18eed29952393d5a9c4636bfe789dde3c98fe0a0a4759d323478e72/aiohttp-3.10.8-cp312-cp312-win_amd64.whl", hash = "sha256:ab1546fc8e00676febc81c548a876c7bde32f881b8334b77f84719ab2c7d28dc", size = 379143 }, + { url = "https://files.pythonhosted.org/packages/9f/dd/3d944769ed65d3d245f8f976040654b3eae2e21d05c81f91fb450365bddf/aiohttp-3.10.8-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:b1a012677b8e0a39e181e218de47d6741c5922202e3b0b65e412e2ce47c39337", size = 575934 }, + { url = "https://files.pythonhosted.org/packages/2a/bf/a6a1d14b0e5f90d53b1f0850204f9fafdfec7c1d99dda8aaea1dd93ba181/aiohttp-3.10.8-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:2df786c96c57cd6b87156ba4c5f166af7b88f3fc05f9d592252fdc83d8615a3c", size = 391728 }, + { url = "https://files.pythonhosted.org/packages/0e/1b/27cc6efa6ca3e563973c7e03e8b7e26b75b4046aefea991bad42c028a906/aiohttp-3.10.8-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:8885ca09d3a9317219c0831276bfe26984b17b2c37b7bf70dd478d17092a4772", size = 387247 }, + { url = "https://files.pythonhosted.org/packages/ae/fd/235401bd4a98ea31cdda7b3822921e2a9cbc3ca0af1958a12a2709261735/aiohttp-3.10.8-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4dbf252ac19860e0ab56cd480d2805498f47c5a2d04f5995d8d8a6effd04b48c", size = 1286909 }, + { url = "https://files.pythonhosted.org/packages/ab/1c/8ae6b12be2ae88e94be34d96765d6cc820d61d320f33c0423de8af0cfa47/aiohttp-3.10.8-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3b2036479b6b94afaaca7d07b8a68dc0e67b0caf5f6293bb6a5a1825f5923000", size = 1323446 }, + { url = "https://files.pythonhosted.org/packages/23/09/5ebe3a2dbdd008711b659dc2f2a6135bbc055b6c8869688083f4bec6b50a/aiohttp-3.10.8-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:365783e1b7c40b59ed4ce2b5a7491bae48f41cd2c30d52647a5b1ee8604c68ad", size = 1368237 }, + { url = "https://files.pythonhosted.org/packages/47/22/f184c27d03d34ce71e6d4b9976a4ff845d091b725f174b09f641e4a28f63/aiohttp-3.10.8-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:270e653b5a4b557476a1ed40e6b6ce82f331aab669620d7c95c658ef976c9c5e", size = 1282598 }, + { url = "https://files.pythonhosted.org/packages/82/f6/bae1703bfacb19bb35e3522632fc5279793070625a0b5e567b109c0f0e8d/aiohttp-3.10.8-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8960fabc20bfe4fafb941067cda8e23c8c17c98c121aa31c7bf0cdab11b07842", size = 1236350 }, + { url = "https://files.pythonhosted.org/packages/a4/bc/ad73aced93836b8749c70e617c5d389d17a36da9ee220cdb0804f803bd9b/aiohttp-3.10.8-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:f21e8f2abed9a44afc3d15bba22e0dfc71e5fa859bea916e42354c16102b036f", size = 1250172 }, + { url = "https://files.pythonhosted.org/packages/3b/18/027a8497caf3a9c247477831d67ede58e1e42a92fd635ecdb74cf5d45c8b/aiohttp-3.10.8-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:fecd55e7418fabd297fd836e65cbd6371aa4035a264998a091bbf13f94d9c44d", size = 1248783 }, + { url = "https://files.pythonhosted.org/packages/6f/d2/5080c27b656e6d478e820752d633d7a4dab4a2c4fd23a6f645b553fb9da5/aiohttp-3.10.8-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:badb51d851358cd7535b647bb67af4854b64f3c85f0d089c737f75504d5910ec", size = 1293209 }, + { url = "https://files.pythonhosted.org/packages/ae/ec/c38c8690e804cb9bf3e8c473a4a7bb339ed549cd63c469f19995269ca9ec/aiohttp-3.10.8-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:e860985f30f3a015979e63e7ba1a391526cdac1b22b7b332579df7867848e255", size = 1319943 }, + { url = "https://files.pythonhosted.org/packages/df/55/d6e3a13c3f37ad7a3e60a377c96541261c1943837d240f1ab2151a96da6b/aiohttp-3.10.8-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:71462f8eeca477cbc0c9700a9464e3f75f59068aed5e9d4a521a103692da72dc", size = 1281380 }, + { url = "https://files.pythonhosted.org/packages/c3/31/0b84027487fa58a124251b47f9dca781e4777a50d1c4eea4d3fc8950bd10/aiohttp-3.10.8-cp313-cp313-win32.whl", hash = "sha256:177126e971782769b34933e94fddd1089cef0fe6b82fee8a885e539f5b0f0c6a", size = 357352 }, + { url = "https://files.pythonhosted.org/packages/cb/8a/b4f3a8d0fb7f4fdb3869db6c3334e23e11878123605579e067be85f7e01f/aiohttp-3.10.8-cp313-cp313-win_amd64.whl", hash = "sha256:98a4eb60e27033dee9593814ca320ee8c199489fbc6b2699d0f710584db7feb7", size = 376618 }, ] [[package]] @@ -190,7 +190,7 @@ wheels = [ [[package]] name = "azure-storage-blob" -version = "12.23.0" +version = "12.23.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "azure-core" }, @@ -198,9 +198,9 @@ dependencies = [ { name = "isodate" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/6b/64/eb0fbd7865463d9551bcfd6a92947d235f2128aa0b12b6f0254959aa31eb/azure_storage_blob-12.23.0.tar.gz", hash = "sha256:2fadbceda1d99c4a72dfd32e0122d7bca8b5e8d2563f5c624d634aeaff49c9df", size = 566106 } +sdist = { url = "https://files.pythonhosted.org/packages/66/b2/df9ac2ea294e558fa8b6cdade9a14a938b07529f5194303664152819277a/azure_storage_blob-12.23.1.tar.gz", hash = "sha256:a587e54d4e39d2a27bd75109db164ffa2058fe194061e5446c5a89bca918272f", size = 566114 } wheels = [ - { url = "https://files.pythonhosted.org/packages/60/02/024b71fc0af7a361cfaecbd96120615ef53787e0b4213285e18eb259d198/azure_storage_blob-12.23.0-py3-none-any.whl", hash = "sha256:8ac4b34624ed075eda1e38f0c6dadb601e1b199e27a09aa63edc429bf4a23329", size = 405594 }, + { url = "https://files.pythonhosted.org/packages/df/bf/f19dd2261dd6193aa53375fcd58929d613e45d14bcdb778567d1fd5e2d6e/azure_storage_blob-12.23.1-py3-none-any.whl", hash = "sha256:1c2238aa841d1545f42714a5017c010366137a44a0605da2d45f770174bfc6b4", size = 405622 }, ] [[package]] @@ -630,27 +630,33 @@ wheels = [ [[package]] name = "fonttools" -version = "4.53.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/c6/cb/cd80a0da995adde8ade6044a8744aee0da5efea01301cadf770f7fbe7dcc/fonttools-4.53.1.tar.gz", hash = "sha256:e128778a8e9bc11159ce5447f76766cefbd876f44bd79aff030287254e4752c4", size = 3452797 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/8b/6a/206391c869ab22d1374e2575cad7cab36b93b9e3d37f48f4696eed2c6e9e/fonttools-4.53.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:da33440b1413bad53a8674393c5d29ce64d8c1a15ef8a77c642ffd900d07bfe1", size = 2762654 }, - { url = "https://files.pythonhosted.org/packages/f5/7e/4060d88dbfaf446e1c9f0fe9cf13dba36ba47c4da85ce5c1df084ce47e7d/fonttools-4.53.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:5ff7e5e9bad94e3a70c5cd2fa27f20b9bb9385e10cddab567b85ce5d306ea923", size = 2247865 }, - { url = "https://files.pythonhosted.org/packages/e1/67/fff766817e17d67208f8a1e72de15066149485acb5e4ff0816b11fd5fca3/fonttools-4.53.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c6e7170d675d12eac12ad1a981d90f118c06cf680b42a2d74c6c931e54b50719", size = 4873046 }, - { url = "https://files.pythonhosted.org/packages/a4/22/0a0ad59d9367997fd74a00ad2e88d10559122e09f105e94d34c155aecc0a/fonttools-4.53.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bee32ea8765e859670c4447b0817514ca79054463b6b79784b08a8df3a4d78e3", size = 4920859 }, - { url = "https://files.pythonhosted.org/packages/0b/c4/b4e2f1699a5e2244373a6e8175f862f49f377b444adc6c7b1fe1f5b3d04d/fonttools-4.53.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:6e08f572625a1ee682115223eabebc4c6a2035a6917eac6f60350aba297ccadb", size = 4885904 }, - { url = "https://files.pythonhosted.org/packages/64/e7/b9a07c386adf8ad0348163fbcaab74daed6ef18ddb3f49b61b5c19900aeb/fonttools-4.53.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b21952c092ffd827504de7e66b62aba26fdb5f9d1e435c52477e6486e9d128b2", size = 5054708 }, - { url = "https://files.pythonhosted.org/packages/e9/53/2a79462ae38d7943e63290209c04fef89677c67b29cb329cdc549c18d4d5/fonttools-4.53.1-cp311-cp311-win32.whl", hash = "sha256:9dfdae43b7996af46ff9da520998a32b105c7f098aeea06b2226b30e74fbba88", size = 2158885 }, - { url = "https://files.pythonhosted.org/packages/c8/e1/059700c154bd7170d1c37061239836d2e51ff608f47075450f06dd3c292a/fonttools-4.53.1-cp311-cp311-win_amd64.whl", hash = "sha256:d4d0096cb1ac7a77b3b41cd78c9b6bc4a400550e21dc7a92f2b5ab53ed74eb02", size = 2205133 }, - { url = "https://files.pythonhosted.org/packages/87/63/8271f50f3e7bff8b78e03914c4c2893f2f21bd4db2975c60d11ecfbdd174/fonttools-4.53.1-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:d92d3c2a1b39631a6131c2fa25b5406855f97969b068e7e08413325bc0afba58", size = 2756146 }, - { url = "https://files.pythonhosted.org/packages/dd/bd/cb8fd2dddd68089c112bf42a88afe188b8ace73f94406539857dcc9347a6/fonttools-4.53.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:3b3c8ebafbee8d9002bd8f1195d09ed2bd9ff134ddec37ee8f6a6375e6a4f0e8", size = 2244990 }, - { url = "https://files.pythonhosted.org/packages/ae/71/2b9761e25697bdaf3dfe8269541bd4324f3eb0e4cc13f71d7f90cd272394/fonttools-4.53.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:32f029c095ad66c425b0ee85553d0dc326d45d7059dbc227330fc29b43e8ba60", size = 4787604 }, - { url = "https://files.pythonhosted.org/packages/db/2b/5779cfd48625e013c2dfcf0c246474d5b1f5d061a5f1e476037bf9fff3a3/fonttools-4.53.1-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:10f5e6c3510b79ea27bb1ebfcc67048cde9ec67afa87c7dd7efa5c700491ac7f", size = 4871141 }, - { url = "https://files.pythonhosted.org/packages/b8/3d/ac3cec35a503bf789d03e9d155a220c9e574f4f1573f00a3bea55695d535/fonttools-4.53.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:f677ce218976496a587ab17140da141557beb91d2a5c1a14212c994093f2eae2", size = 4764714 }, - { url = "https://files.pythonhosted.org/packages/ac/9f/27135ac0328e22cca1ba23ee6a1a1f971c13e9f0387adc5598d4635c501d/fonttools-4.53.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:9e6ceba2a01b448e36754983d376064730690401da1dd104ddb543519470a15f", size = 5023568 }, - { url = "https://files.pythonhosted.org/packages/04/40/44d6a94e52e91fe104f9ca95944466af34828992cbc66b666f541de137f1/fonttools-4.53.1-cp312-cp312-win32.whl", hash = "sha256:791b31ebbc05197d7aa096bbc7bd76d591f05905d2fd908bf103af4488e60670", size = 2147572 }, - { url = "https://files.pythonhosted.org/packages/6d/9a/b695930e1b4e6929cc60e294489421632a05c105ac8c56ee63ef56a47872/fonttools-4.53.1-cp312-cp312-win_amd64.whl", hash = "sha256:6ed170b5e17da0264b9f6fae86073be3db15fa1bd74061c8331022bca6d09bab", size = 2193313 }, - { url = "https://files.pythonhosted.org/packages/e4/b9/0394d67056d4ad36a3807b439571934b318f1df925593a95e9ec0516b1a7/fonttools-4.53.1-py3-none-any.whl", hash = "sha256:f1f8758a2ad110bd6432203a344269f445a2907dc24ef6bccfd0ac4e14e0d71d", size = 1090472 }, +version = "4.54.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/11/1d/70b58e342e129f9c0ce030029fb4b2b0670084bbbfe1121d008f6a1e361c/fonttools-4.54.1.tar.gz", hash = "sha256:957f669d4922f92c171ba01bef7f29410668db09f6c02111e22b2bce446f3285", size = 3463867 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/aa/2c/8b5d82fe2d9c7f260fb73121418f5e07d4e38c329ea3886a5b0e55586113/fonttools-4.54.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5419771b64248484299fa77689d4f3aeed643ea6630b2ea750eeab219588ba20", size = 2768112 }, + { url = "https://files.pythonhosted.org/packages/37/2e/f94118b92f7b6a9ec93840101b64bfdd09f295b266133857e8e852a5c35c/fonttools-4.54.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:301540e89cf4ce89d462eb23a89464fef50915255ece765d10eee8b2bf9d75b2", size = 2254739 }, + { url = "https://files.pythonhosted.org/packages/45/4b/8a32f56a13e78256192f77d6b65583c43538c7955f5420887bb574b91ddf/fonttools-4.54.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:76ae5091547e74e7efecc3cbf8e75200bc92daaeb88e5433c5e3e95ea8ce5aa7", size = 4879772 }, + { url = "https://files.pythonhosted.org/packages/96/13/748b7f7239893ff0796de11074b0ad8aa4c3da2d9f4d79a128b0b16147f3/fonttools-4.54.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:82834962b3d7c5ca98cb56001c33cf20eb110ecf442725dc5fdf36d16ed1ab07", size = 4927686 }, + { url = "https://files.pythonhosted.org/packages/7c/82/91bc5a378b4a0593fa90ea706f68ce7e9e871c6873e0d91e134d107758db/fonttools-4.54.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d26732ae002cc3d2ecab04897bb02ae3f11f06dd7575d1df46acd2f7c012a8d8", size = 4890789 }, + { url = "https://files.pythonhosted.org/packages/ea/ca/82be5d4f8b78405cdb3f7f3f1316af5e8db93216121f19da9f684a35beee/fonttools-4.54.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:58974b4987b2a71ee08ade1e7f47f410c367cdfc5a94fabd599c88165f56213a", size = 5061351 }, + { url = "https://files.pythonhosted.org/packages/da/2f/fd6e1b01c80c473c3ac52492dcf8d26cdf5f4a89b4f30875ecfbda55e7ff/fonttools-4.54.1-cp311-cp311-win32.whl", hash = "sha256:ab774fa225238986218a463f3fe151e04d8c25d7de09df7f0f5fce27b1243dbc", size = 2166210 }, + { url = "https://files.pythonhosted.org/packages/63/f1/3a081cd047d83b5966cb0d7ef3fea929ee6eddeb94d8fbfdb2a19bd60cc7/fonttools-4.54.1-cp311-cp311-win_amd64.whl", hash = "sha256:07e005dc454eee1cc60105d6a29593459a06321c21897f769a281ff2d08939f6", size = 2211946 }, + { url = "https://files.pythonhosted.org/packages/27/b6/f9d365932dcefefdcc794985f8846471e60932070c557e0f66ed195fccec/fonttools-4.54.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:54471032f7cb5fca694b5f1a0aaeba4af6e10ae989df408e0216f7fd6cdc405d", size = 2761873 }, + { url = "https://files.pythonhosted.org/packages/67/9d/cfbfe36e5061a8f68b154454ba2304eb01f40d4ba9b63e41d9058909baed/fonttools-4.54.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8fa92cb248e573daab8d032919623cc309c005086d743afb014c836636166f08", size = 2251828 }, + { url = "https://files.pythonhosted.org/packages/90/41/5573e074739efd9227dd23647724f01f6f07ad062fe09d02e91c5549dcf7/fonttools-4.54.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0a911591200114969befa7f2cb74ac148bce5a91df5645443371aba6d222e263", size = 4792544 }, + { url = "https://files.pythonhosted.org/packages/08/07/aa85cc62abcc940b25d14b542cf585eebf4830032a7f6a1395d696bb3231/fonttools-4.54.1-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:93d458c8a6a354dc8b48fc78d66d2a8a90b941f7fec30e94c7ad9982b1fa6bab", size = 4875892 }, + { url = "https://files.pythonhosted.org/packages/47/23/c5726c2615446c498a976bed21c35a242a97eee39930a2655d616ca885cc/fonttools-4.54.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:5eb2474a7c5be8a5331146758debb2669bf5635c021aee00fd7c353558fc659d", size = 4769822 }, + { url = "https://files.pythonhosted.org/packages/8f/7b/87f7f7d35e0732ac67422dfa6f05e2b568fb6ca2dcd7f3e4f500293cfd75/fonttools-4.54.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:c9c563351ddc230725c4bdf7d9e1e92cbe6ae8553942bd1fb2b2ff0884e8b714", size = 5029455 }, + { url = "https://files.pythonhosted.org/packages/e0/09/241aa498587889576838aa73c78d22b70ce06970807a5475d372baa7ccb7/fonttools-4.54.1-cp312-cp312-win32.whl", hash = "sha256:fdb062893fd6d47b527d39346e0c5578b7957dcea6d6a3b6794569370013d9ac", size = 2154411 }, + { url = "https://files.pythonhosted.org/packages/b9/0a/a57caaff3bc880779317cb157e5b49dc47fad54effe027016abd355b0651/fonttools-4.54.1-cp312-cp312-win_amd64.whl", hash = "sha256:e4564cf40cebcb53f3dc825e85910bf54835e8a8b6880d59e5159f0f325e637e", size = 2200412 }, + { url = "https://files.pythonhosted.org/packages/05/3d/cc515cae84a11d696f2cb7c139a90997b15f02e2e97ec09a5d79302cbcd7/fonttools-4.54.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:6e37561751b017cf5c40fce0d90fd9e8274716de327ec4ffb0df957160be3bff", size = 2749174 }, + { url = "https://files.pythonhosted.org/packages/03/03/05d4b22d1a674d066380657f60bbc0eda2d206446912e676d1a33a206878/fonttools-4.54.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:357cacb988a18aace66e5e55fe1247f2ee706e01debc4b1a20d77400354cddeb", size = 2246267 }, + { url = "https://files.pythonhosted.org/packages/52/c3/bb6086adb675e8b0963a7dbb7769e7118c95b687dd318cd660aefd4b4c8c/fonttools-4.54.1-cp313-cp313-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f8e953cc0bddc2beaf3a3c3b5dd9ab7554677da72dfaf46951e193c9653e515a", size = 4855090 }, + { url = "https://files.pythonhosted.org/packages/80/a1/d7192b6a104e3f9ea8e5b1c3463a6240399f0fa826a782eff636cbe0495a/fonttools-4.54.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:58d29b9a294573d8319f16f2f79e42428ba9b6480442fa1836e4eb89c4d9d61c", size = 5005449 }, + { url = "https://files.pythonhosted.org/packages/5a/6c/ecfd5c6cd8c9006e85b128d073af26bb263e8aa47506374cb14b25bcf65f/fonttools-4.54.1-cp313-cp313-win32.whl", hash = "sha256:9ef1b167e22709b46bf8168368b7b5d3efeaaa746c6d39661c1b4405b6352e58", size = 2152496 }, + { url = "https://files.pythonhosted.org/packages/63/da/f7a1d837de419e3d4cccbd0dbf53c7399f610f65ceb9bcbf2480f3ae7950/fonttools-4.54.1-cp313-cp313-win_amd64.whl", hash = "sha256:262705b1663f18c04250bd1242b0515d3bbae177bee7752be67c979b7d47f43d", size = 2197257 }, + { url = "https://files.pythonhosted.org/packages/57/5e/de2e6e51cb6894f2f2bc2641f6c845561361b622e96df3cca04df77222c9/fonttools-4.54.1-py3-none-any.whl", hash = "sha256:37cddd62d83dc4f72f7c3f3c2bcf2697e89a30efb152079896544a93907733bd", size = 1096920 }, ] [[package]] @@ -4961,27 +4967,27 @@ wheels = [ [[package]] name = "ruff" -version = "0.6.7" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/8d/7c/3045a526c57cef4b5ec4d5d154692e31429749a49810a53e785de334c4f6/ruff-0.6.7.tar.gz", hash = "sha256:44e52129d82266fa59b587e2cd74def5637b730a69c4542525dfdecfaae38bd5", size = 3073785 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/22/c4/1c5c636f83f905c537785016e9cdd7a36df53c025a2d07940580ecb37bcf/ruff-0.6.7-py3-none-linux_armv6l.whl", hash = "sha256:08277b217534bfdcc2e1377f7f933e1c7957453e8a79764d004e44c40db923f2", size = 10336748 }, - { url = "https://files.pythonhosted.org/packages/84/d9/aa15a56be7ad796f4d7625362aff588f9fc013bbb7323a63571628a2cf2d/ruff-0.6.7-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:c6707a32e03b791f4448dc0dce24b636cbcdee4dd5607adc24e5ee73fd86c00a", size = 9958833 }, - { url = "https://files.pythonhosted.org/packages/27/25/5dd1c32bfc3ad3136c8ebe84312d1bdd2e6c908ac7f60692ec009b7050a8/ruff-0.6.7-py3-none-macosx_11_0_arm64.whl", hash = "sha256:533d66b7774ef224e7cf91506a7dafcc9e8ec7c059263ec46629e54e7b1f90ab", size = 9633369 }, - { url = "https://files.pythonhosted.org/packages/0e/3e/01b25484f3cb08fe6fddedf1f55f3f3c0af861a5b5f5082fbe60ab4b2596/ruff-0.6.7-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:17a86aac6f915932d259f7bec79173e356165518859f94649d8c50b81ff087e9", size = 10637415 }, - { url = "https://files.pythonhosted.org/packages/8a/c9/5bb9b849e4777e0f961de43edf95d2af0ab34999a5feee957be096887876/ruff-0.6.7-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:b3f8822defd260ae2460ea3832b24d37d203c3577f48b055590a426a722d50ef", size = 10097389 }, - { url = "https://files.pythonhosted.org/packages/52/cf/e08f1c290c7d848ddfb2ae811f24f445c18e1d3e50e01c38ffa7f5a50494/ruff-0.6.7-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9ba4efe5c6dbbb58be58dd83feedb83b5e95c00091bf09987b4baf510fee5c99", size = 10951440 }, - { url = "https://files.pythonhosted.org/packages/a2/2d/ca8aa0da5841913c302d8034c6de0ce56c401c685184d8dd23cfdd0003f9/ruff-0.6.7-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:525201b77f94d2b54868f0cbe5edc018e64c22563da6c5c2e5c107a4e85c1c0d", size = 11708900 }, - { url = "https://files.pythonhosted.org/packages/89/fc/9a83c57baee977c82392e19a328b52cebdaf61601af3d99498e278ef5104/ruff-0.6.7-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8854450839f339e1049fdbe15d875384242b8e85d5c6947bb2faad33c651020b", size = 11258892 }, - { url = "https://files.pythonhosted.org/packages/d3/a3/254cc7afef702c68ae9079290c2a1477ae0e81478589baf745026d8a4eb5/ruff-0.6.7-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2f0b62056246234d59cbf2ea66e84812dc9ec4540518e37553513392c171cb18", size = 12367932 }, - { url = "https://files.pythonhosted.org/packages/9f/55/53f10c1bd8c3b2ae79aed18e62b22c6346f9296aa0ec80489b8442bd06a9/ruff-0.6.7-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6b1462fa56c832dc0cea5b4041cfc9c97813505d11cce74ebc6d1aae068de36b", size = 10838629 }, - { url = "https://files.pythonhosted.org/packages/84/72/fb335c2b25432c63d15383ecbd7bfc1915e68cdf8d086a08042052144255/ruff-0.6.7-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:02b083770e4cdb1495ed313f5694c62808e71764ec6ee5db84eedd82fd32d8f5", size = 10648824 }, - { url = "https://files.pythonhosted.org/packages/92/a8/d57e135a8ad99b6a0c6e2a5c590bcacdd57f44340174f4409c3893368610/ruff-0.6.7-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:0c05fd37013de36dfa883a3854fae57b3113aaa8abf5dea79202675991d48624", size = 10174368 }, - { url = "https://files.pythonhosted.org/packages/a7/6f/1a30a6e81dcf2fa9ff3f7011eb87fe76c12a3c6bba74db6a1977d763de1f/ruff-0.6.7-py3-none-musllinux_1_2_i686.whl", hash = "sha256:f49c9caa28d9bbfac4a637ae10327b3db00f47d038f3fbb2195c4d682e925b14", size = 10514383 }, - { url = "https://files.pythonhosted.org/packages/0b/25/df6f2575bc9fe43a6dedfd8dee12896f09a94303e2c828d5f85856bb69a0/ruff-0.6.7-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:a0e1655868164e114ba43a908fd2d64a271a23660195017c17691fb6355d59bb", size = 10902340 }, - { url = "https://files.pythonhosted.org/packages/68/62/f2c1031e2fb7b94f9bf0603744e73db4ef90081b0eb1b9639a6feefd52ea/ruff-0.6.7-py3-none-win32.whl", hash = "sha256:a939ca435b49f6966a7dd64b765c9df16f1faed0ca3b6f16acdf7731969deb35", size = 8448033 }, - { url = "https://files.pythonhosted.org/packages/97/80/193d1604a3f7d75eb1b2a7ce6bf0fdbdbc136889a65caacea6ffb29501b1/ruff-0.6.7-py3-none-win_amd64.whl", hash = "sha256:590445eec5653f36248584579c06252ad2e110a5d1f32db5420de35fb0e1c977", size = 9273543 }, - { url = "https://files.pythonhosted.org/packages/8e/a8/4abb5a9f58f51e4b1ea386be5ab2e547035bc1ee57200d1eca2f8909a33e/ruff-0.6.7-py3-none-win_arm64.whl", hash = "sha256:b28f0d5e2f771c1fe3c7a45d3f53916fc74a480698c4b5731f0bea61e52137c8", size = 8618044 }, +version = "0.6.8" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/74/f9/4ce3e765a72ab8fe0f80f48508ea38b4196daab3da14d803c21349b2d367/ruff-0.6.8.tar.gz", hash = "sha256:a5bf44b1aa0adaf6d9d20f86162b34f7c593bfedabc51239953e446aefc8ce18", size = 3084543 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/db/07/42ee57e8b76ca585297a663a552b4f6d6a99372ca47fdc2276ef72cc0f2f/ruff-0.6.8-py3-none-linux_armv6l.whl", hash = "sha256:77944bca110ff0a43b768f05a529fecd0706aac7bcce36d7f1eeb4cbfca5f0f2", size = 10404327 }, + { url = "https://files.pythonhosted.org/packages/eb/51/d42571ff8156d65086acb72d39aa64cb24181db53b497d0ed6293f43f07a/ruff-0.6.8-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:27b87e1801e786cd6ede4ada3faa5e254ce774de835e6723fd94551464c56b8c", size = 10018797 }, + { url = "https://files.pythonhosted.org/packages/c1/d7/fa5514a60b03976af972b67fe345deb0335dc96b9f9a9fa4df9890472427/ruff-0.6.8-py3-none-macosx_11_0_arm64.whl", hash = "sha256:cd48f945da2a6334f1793d7f701725a76ba93bf3d73c36f6b21fb04d5338dcf5", size = 9691303 }, + { url = "https://files.pythonhosted.org/packages/d6/c4/d812a74976927e51d0782a47539069657ac78535779bfa4d061c4fc8d89d/ruff-0.6.8-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:677e03c00f37c66cea033274295a983c7c546edea5043d0c798833adf4cf4c6f", size = 10719452 }, + { url = "https://files.pythonhosted.org/packages/ec/b6/aa700c4ae6db9b3ee660e23f3c7db596e2b16a3034b797704fba33ddbc96/ruff-0.6.8-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:9f1476236b3eacfacfc0f66aa9e6cd39f2a624cb73ea99189556015f27c0bdeb", size = 10161353 }, + { url = "https://files.pythonhosted.org/packages/ea/39/0b10075ffcd52ff3a581b9b69eac53579deb230aad300ce8f9d0b58e77bc/ruff-0.6.8-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6f5a2f17c7d32991169195d52a04c95b256378bbf0de8cb98478351eb70d526f", size = 10980630 }, + { url = "https://files.pythonhosted.org/packages/c1/af/9eb9efc98334f62652e2f9318f137b2667187851911fac3b395365a83708/ruff-0.6.8-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:5fd0d4b7b1457c49e435ee1e437900ced9b35cb8dc5178921dfb7d98d65a08d0", size = 11768996 }, + { url = "https://files.pythonhosted.org/packages/e0/59/8b1369cf7878358952b1c0a1559b4d6b5c824c003d09b0db26d26c9d094f/ruff-0.6.8-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f8034b19b993e9601f2ddf2c517451e17a6ab5cdb1c13fdff50c1442a7171d87", size = 11317469 }, + { url = "https://files.pythonhosted.org/packages/b9/6d/e252e9b11bbca4114c386ee41ad559d0dac13246201d77ea1223c6fea17f/ruff-0.6.8-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:6cfb227b932ba8ef6e56c9f875d987973cd5e35bc5d05f5abf045af78ad8e098", size = 12467185 }, + { url = "https://files.pythonhosted.org/packages/48/44/7caa223af7d4ea0f0b2bd34acca65a7694a58317714675a2478815ab3f45/ruff-0.6.8-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6ef0411eccfc3909269fed47c61ffebdcb84a04504bafa6b6df9b85c27e813b0", size = 10887766 }, + { url = "https://files.pythonhosted.org/packages/81/ed/394aff3a785f171869158b9d5be61eec9ffb823c3ad5d2bdf2e5f13cb029/ruff-0.6.8-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:007dee844738c3d2e6c24ab5bc7d43c99ba3e1943bd2d95d598582e9c1b27750", size = 10711609 }, + { url = "https://files.pythonhosted.org/packages/47/31/f31d04c842e54699eab7e3b864538fea26e6c94b71806cd10aa49f13e1c1/ruff-0.6.8-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:ce60058d3cdd8490e5e5471ef086b3f1e90ab872b548814e35930e21d848c9ce", size = 10237621 }, + { url = "https://files.pythonhosted.org/packages/20/95/a764e84acf11d425f2f23b8b78b4fd715e9c20be4aac157c6414ca859a67/ruff-0.6.8-py3-none-musllinux_1_2_i686.whl", hash = "sha256:1085c455d1b3fdb8021ad534379c60353b81ba079712bce7a900e834859182fa", size = 10558329 }, + { url = "https://files.pythonhosted.org/packages/2a/76/d4e38846ac9f6dd62dce858a54583911361b5339dcf8f84419241efac93a/ruff-0.6.8-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:70edf6a93b19481affd287d696d9e311388d808671bc209fb8907b46a8c3af44", size = 10954102 }, + { url = "https://files.pythonhosted.org/packages/e7/36/f18c678da6c69f8d022480f3e8ddce6e4a52e07602c1d212056fbd234f8f/ruff-0.6.8-py3-none-win32.whl", hash = "sha256:792213f7be25316f9b46b854df80a77e0da87ec66691e8f012f887b4a671ab5a", size = 8511090 }, + { url = "https://files.pythonhosted.org/packages/4c/c4/0ca7d8ffa358b109db7d7d045a1a076fd8e5d9cbeae022242d3c060931da/ruff-0.6.8-py3-none-win_amd64.whl", hash = "sha256:ec0517dc0f37cad14a5319ba7bba6e7e339d03fbf967a6d69b0907d61be7a263", size = 9350079 }, + { url = "https://files.pythonhosted.org/packages/d9/bd/a8b0c64945a92eaeeb8d0283f27a726a776a1c9d12734d990c5fc7a1278c/ruff-0.6.8-py3-none-win_arm64.whl", hash = "sha256:8d3bb2e3fbb9875172119021a13eed38849e762499e3cfde9588e4b4d70968dc", size = 8669595 }, ] [[package]] @@ -5227,29 +5233,29 @@ wheels = [ [[package]] name = "watchdog" -version = "5.0.2" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/cd/5e/95dcd86d8339fcf76385f7fad5e49cbfd989b6c6199127121c9587febc65/watchdog-5.0.2.tar.gz", hash = "sha256:dcebf7e475001d2cdeb020be630dc5b687e9acdd60d16fea6bb4508e7b94cf76", size = 127779 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/80/52/51046f428e813270cd959bee9d2343f103c10adf10e957f69d6710a38ab8/watchdog-5.0.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:dae7a1879918f6544201d33666909b040a46421054a50e0f773e0d870ed7438d", size = 96276 }, - { url = "https://files.pythonhosted.org/packages/b3/8e/0e5671f3950fd2049bbeb8c965cb53e143bfd72869e5e4c60dda572121cd/watchdog-5.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c4a440f725f3b99133de610bfec93d570b13826f89616377715b9cd60424db6e", size = 88269 }, - { url = "https://files.pythonhosted.org/packages/b5/34/9c436ec85f7234b468e49380f57cc784b4e22f058febe17221f25ce85c4b/watchdog-5.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f8b2918c19e0d48f5f20df458c84692e2a054f02d9df25e6c3c930063eca64c1", size = 88914 }, - { url = "https://files.pythonhosted.org/packages/ef/41/fe19a56aa8ea7e453311f2b4fd2bfb172d21bd72ef6ae0fd40c304c74edf/watchdog-5.0.2-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:aa9cd6e24126d4afb3752a3e70fce39f92d0e1a58a236ddf6ee823ff7dba28ee", size = 96365 }, - { url = "https://files.pythonhosted.org/packages/cc/02/86d631595ec1c5678e23e9359741d2dea460be0712b41a243281b37e90ba/watchdog-5.0.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:f627c5bf5759fdd90195b0c0431f99cff4867d212a67b384442c51136a098ed7", size = 88330 }, - { url = "https://files.pythonhosted.org/packages/d8/a7/5c57f05def91ff11528f0aa0d4c23efc99fa064ec69c262fedc6c9885697/watchdog-5.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d7594a6d32cda2b49df3fd9abf9b37c8d2f3eab5df45c24056b4a671ac661619", size = 88935 }, - { url = "https://files.pythonhosted.org/packages/80/1a/a681c0093eea33b18a7348b398302628ab96647f59eaf06a5a047e8a1f39/watchdog-5.0.2-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:ba32efcccfe2c58f4d01115440d1672b4eb26cdd6fc5b5818f1fb41f7c3e1889", size = 96362 }, - { url = "https://files.pythonhosted.org/packages/c4/aa/0c827bd35716d91b5a4a2a6c5ca7638d936e6055dec8ce85414383ab887f/watchdog-5.0.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:963f7c4c91e3f51c998eeff1b3fb24a52a8a34da4f956e470f4b068bb47b78ee", size = 88336 }, - { url = "https://files.pythonhosted.org/packages/6e/ba/da13d47dacc84bfab52310e74f954eb440c5cdee11ff8786228f17343a3d/watchdog-5.0.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:8c47150aa12f775e22efff1eee9f0f6beee542a7aa1a985c271b1997d340184f", size = 88938 }, - { url = "https://files.pythonhosted.org/packages/5b/cb/c13dfc4714547c4a63f27a50d5d0bbda655ef06d93595c016822ff771032/watchdog-5.0.2-py3-none-manylinux2014_aarch64.whl", hash = "sha256:5597c051587f8757798216f2485e85eac583c3b343e9aa09127a3a6f82c65ee8", size = 78960 }, - { url = "https://files.pythonhosted.org/packages/cb/ed/78acaa8e95e193a46925f7beeed45c29569d0ee572216df622bb0908abf3/watchdog-5.0.2-py3-none-manylinux2014_armv7l.whl", hash = "sha256:53ed1bf71fcb8475dd0ef4912ab139c294c87b903724b6f4a8bd98e026862e6d", size = 78960 }, - { url = "https://files.pythonhosted.org/packages/2f/54/30bde6279d2f77e6c2838a89e9975038bba4adbfb029f9b8e01cf2813199/watchdog-5.0.2-py3-none-manylinux2014_i686.whl", hash = "sha256:29e4a2607bd407d9552c502d38b45a05ec26a8e40cc7e94db9bb48f861fa5abc", size = 78958 }, - { url = "https://files.pythonhosted.org/packages/f4/db/886241c6d02f165fbf633b633dc5ceddc6c145fec3704828606743ddb663/watchdog-5.0.2-py3-none-manylinux2014_ppc64.whl", hash = "sha256:b6dc8f1d770a8280997e4beae7b9a75a33b268c59e033e72c8a10990097e5fde", size = 78957 }, - { url = "https://files.pythonhosted.org/packages/a9/74/c255a2146280adcb2d1b5ccb7580e71114b253f356a6c4ea748b0eb7a7b5/watchdog-5.0.2-py3-none-manylinux2014_ppc64le.whl", hash = "sha256:d2ab34adc9bf1489452965cdb16a924e97d4452fcf88a50b21859068b50b5c3b", size = 78960 }, - { url = "https://files.pythonhosted.org/packages/8a/dc/4bdc31a35ffce526280c5a29b64b939624761f47e3fcdac34808589d0845/watchdog-5.0.2-py3-none-manylinux2014_s390x.whl", hash = "sha256:7d1aa7e4bb0f0c65a1a91ba37c10e19dabf7eaaa282c5787e51371f090748f4b", size = 78959 }, - { url = "https://files.pythonhosted.org/packages/9d/53/e71b01aa5737a21664b731de5f91c5b0721ff64d237e43efc56a99254fa1/watchdog-5.0.2-py3-none-manylinux2014_x86_64.whl", hash = "sha256:726eef8f8c634ac6584f86c9c53353a010d9f311f6c15a034f3800a7a891d941", size = 78959 }, - { url = "https://files.pythonhosted.org/packages/5d/0e/c37862900200436a554a4c411645f29887fe3fb4d4e465fbedcf1e0e383a/watchdog-5.0.2-py3-none-win32.whl", hash = "sha256:bda40c57115684d0216556671875e008279dea2dc00fcd3dde126ac8e0d7a2fb", size = 78947 }, - { url = "https://files.pythonhosted.org/packages/8f/ab/f1a3791be609e18596ce6a52c00274f1b244340b87379eb78c4df15f6b2b/watchdog-5.0.2-py3-none-win_amd64.whl", hash = "sha256:d010be060c996db725fbce7e3ef14687cdcc76f4ca0e4339a68cc4532c382a73", size = 78950 }, - { url = "https://files.pythonhosted.org/packages/53/99/f5065334d157518ec8c707aa790c93d639fac582be4f7caec5db8c6fa089/watchdog-5.0.2-py3-none-win_ia64.whl", hash = "sha256:3960136b2b619510569b90f0cd96408591d6c251a75c97690f4553ca88889769", size = 78948 }, +version = "5.0.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/a2/48/a86139aaeab2db0a2482676f64798d8ac4d2dbb457523f50ab37bf02ce2c/watchdog-5.0.3.tar.gz", hash = "sha256:108f42a7f0345042a854d4d0ad0834b741d421330d5f575b81cb27b883500176", size = 129556 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/70/34/946f08602f8b8e6af45bc725e4a8013975a34883ab5570bd0d827a4c9829/watchdog-5.0.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f01f4a3565a387080dc49bdd1fefe4ecc77f894991b88ef927edbfa45eb10818", size = 96650 }, + { url = "https://files.pythonhosted.org/packages/96/2b/b84e35d49e8b0bad77e5d086fc1e2c6c833bbfe74d53144cfe8b26117eff/watchdog-5.0.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:91b522adc25614cdeaf91f7897800b82c13b4b8ac68a42ca959f992f6990c490", size = 88653 }, + { url = "https://files.pythonhosted.org/packages/d5/3f/41b5d77c10f450b79921c17b7d0b416616048867bfe63acaa072a619a0cb/watchdog-5.0.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d52db5beb5e476e6853da2e2d24dbbbed6797b449c8bf7ea118a4ee0d2c9040e", size = 89286 }, + { url = "https://files.pythonhosted.org/packages/1c/9b/8b206a928c188fdeb7b12e1c795199534cd44bdef223b8470129016009dd/watchdog-5.0.3-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:94d11b07c64f63f49876e0ab8042ae034674c8653bfcdaa8c4b32e71cfff87e8", size = 96739 }, + { url = "https://files.pythonhosted.org/packages/e1/26/129ca9cd0f8016672f37000010c2fedc0b86816e894ebdc0af9bb04a6439/watchdog-5.0.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:349c9488e1d85d0a58e8cb14222d2c51cbc801ce11ac3936ab4c3af986536926", size = 88708 }, + { url = "https://files.pythonhosted.org/packages/8f/b3/5e10ec32f0c429cdb55b1369066d6e83faf9985b3a53a4e37bb5c5e29aa0/watchdog-5.0.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:53a3f10b62c2d569e260f96e8d966463dec1a50fa4f1b22aec69e3f91025060e", size = 89309 }, + { url = "https://files.pythonhosted.org/packages/54/c4/49af4ab00bcfb688e9962eace2edda07a2cf89b9699ea536da48e8585cff/watchdog-5.0.3-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:950f531ec6e03696a2414b6308f5c6ff9dab7821a768c9d5788b1314e9a46ca7", size = 96740 }, + { url = "https://files.pythonhosted.org/packages/96/a4/b24de77cc9ae424c1687c9d4fb15aa560d7d7b28ba559aca72f781d0202b/watchdog-5.0.3-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:ae6deb336cba5d71476caa029ceb6e88047fc1dc74b62b7c4012639c0b563906", size = 88711 }, + { url = "https://files.pythonhosted.org/packages/a4/71/3f2e9fe8403386b99d788868955b3a790f7a09721501a7e1eb58f514ffaa/watchdog-5.0.3-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:1021223c08ba8d2d38d71ec1704496471ffd7be42cfb26b87cd5059323a389a1", size = 89319 }, + { url = "https://files.pythonhosted.org/packages/60/33/7cb71c9df9a77b6927ee5f48d25e1de5562ce0fa7e0c56dcf2b0472e64a2/watchdog-5.0.3-py3-none-manylinux2014_aarch64.whl", hash = "sha256:dd021efa85970bd4824acacbb922066159d0f9e546389a4743d56919b6758b91", size = 79335 }, + { url = "https://files.pythonhosted.org/packages/f6/91/320bc1496cf951a3cf93a7ffd18a581f0792c304be963d943e0e608c2919/watchdog-5.0.3-py3-none-manylinux2014_armv7l.whl", hash = "sha256:78864cc8f23dbee55be34cc1494632a7ba30263951b5b2e8fc8286b95845f82c", size = 79334 }, + { url = "https://files.pythonhosted.org/packages/8b/2c/567c5e042ed667d3544c43d48a65cf853450a2d2a9089d9523a65f195e94/watchdog-5.0.3-py3-none-manylinux2014_i686.whl", hash = "sha256:1e9679245e3ea6498494b3028b90c7b25dbb2abe65c7d07423ecfc2d6218ff7c", size = 79333 }, + { url = "https://files.pythonhosted.org/packages/c3/f0/64059fe162ef3274662e67bbdea6c45b3cd53e846d5bd1365fcdc3dc1d15/watchdog-5.0.3-py3-none-manylinux2014_ppc64.whl", hash = "sha256:9413384f26b5d050b6978e6fcd0c1e7f0539be7a4f1a885061473c5deaa57221", size = 79334 }, + { url = "https://files.pythonhosted.org/packages/f6/d9/19b7d02965be2801e2d0f6f4bde23e4ae172620071b65430fa0c2f8441ac/watchdog-5.0.3-py3-none-manylinux2014_ppc64le.whl", hash = "sha256:294b7a598974b8e2c6123d19ef15de9abcd282b0fbbdbc4d23dfa812959a9e05", size = 79333 }, + { url = "https://files.pythonhosted.org/packages/cb/a1/5393ac6d0b095d3a44946b09258e9b5f22cb2fb67bcfa419dd868478826c/watchdog-5.0.3-py3-none-manylinux2014_s390x.whl", hash = "sha256:26dd201857d702bdf9d78c273cafcab5871dd29343748524695cecffa44a8d97", size = 79332 }, + { url = "https://files.pythonhosted.org/packages/a0/58/edec25190b6403caf4426dd418234f2358a106634b7d6aa4aec6939b104f/watchdog-5.0.3-py3-none-manylinux2014_x86_64.whl", hash = "sha256:0f9332243355643d567697c3e3fa07330a1d1abf981611654a1f2bf2175612b7", size = 79334 }, + { url = "https://files.pythonhosted.org/packages/97/69/cfb2d17ba8aabc73be2e2d03c8c319b1f32053a02c4b571852983aa24ff2/watchdog-5.0.3-py3-none-win32.whl", hash = "sha256:c66f80ee5b602a9c7ab66e3c9f36026590a0902db3aea414d59a2f55188c1f49", size = 79320 }, + { url = "https://files.pythonhosted.org/packages/91/b4/2b5b59358dadfa2c8676322f955b6c22cde4937602f40490e2f7403e548e/watchdog-5.0.3-py3-none-win_amd64.whl", hash = "sha256:f00b4cf737f568be9665563347a910f8bdc76f88c2970121c86243c8cfdf90e9", size = 79325 }, + { url = "https://files.pythonhosted.org/packages/38/b8/0aa69337651b3005f161f7f494e59188a1d8d94171666900d26d29d10f69/watchdog-5.0.3-py3-none-win_ia64.whl", hash = "sha256:49f4d36cb315c25ea0d946e018c01bb028048023b9e103d3d3943f58e109dd45", size = 79324 }, ] [[package]] @@ -5277,60 +5283,60 @@ wheels = [ [[package]] name = "yarl" -version = "1.11.1" +version = "1.13.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "idna" }, { name = "multidict" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/e4/3d/4924f9ed49698bac5f112bc9b40aa007bbdcd702462c1df3d2e1383fb158/yarl-1.11.1.tar.gz", hash = "sha256:1bb2d9e212fb7449b8fb73bc461b51eaa17cc8430b4a87d87be7b25052d92f53", size = 162095 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/af/f1/f3e6be722461cab1e7c6aea657685897956d6e4743940d685d167914e31c/yarl-1.11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:946eedc12895873891aaceb39bceb484b4977f70373e0122da483f6c38faaa68", size = 188410 }, - { url = "https://files.pythonhosted.org/packages/4b/c1/21cc66b263fdc2ec10b6459aed5b239f07eed91a77438d88f0e1bd70e202/yarl-1.11.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:21a7c12321436b066c11ec19c7e3cb9aec18884fe0d5b25d03d756a9e654edfe", size = 114293 }, - { url = "https://files.pythonhosted.org/packages/31/7a/0ecab63a166a22357772f4a2852c859e2d5a7b02a5c58803458dd516e6b4/yarl-1.11.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c35f493b867912f6fda721a59cc7c4766d382040bdf1ddaeeaa7fa4d072f4675", size = 112548 }, - { url = "https://files.pythonhosted.org/packages/57/5d/78152026864475e841fdae816499345364c8e364b45ea6accd0814a295f0/yarl-1.11.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:25861303e0be76b60fddc1250ec5986c42f0a5c0c50ff57cc30b1be199c00e63", size = 485002 }, - { url = "https://files.pythonhosted.org/packages/d3/70/2e880d74aeb4908d45c6403e46bbd4aa866ae31ddb432318d9b8042fe0f6/yarl-1.11.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e4b53f73077e839b3f89c992223f15b1d2ab314bdbdf502afdc7bb18e95eae27", size = 504850 }, - { url = "https://files.pythonhosted.org/packages/06/58/5676a47b6d2751853f89d1d68b6a54d725366da6a58482f2410fa7eb38af/yarl-1.11.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:327c724b01b8641a1bf1ab3b232fb638706e50f76c0b5bf16051ab65c868fac5", size = 499291 }, - { url = "https://files.pythonhosted.org/packages/4d/e5/b56d535703a63a8d86ac82059e630e5ba9c0d5626d9c5ac6af53eed815c2/yarl-1.11.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4307d9a3417eea87715c9736d050c83e8c1904e9b7aada6ce61b46361b733d92", size = 487818 }, - { url = "https://files.pythonhosted.org/packages/f3/b4/6b95e1e0983593f4145518980b07126a27e2a4938cb6afb8b592ce6fc2c9/yarl-1.11.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:48a28bed68ab8fb7e380775f0029a079f08a17799cb3387a65d14ace16c12e2b", size = 470447 }, - { url = "https://files.pythonhosted.org/packages/a8/e5/5d349b7b04ed4247d4f717f271fce601a79d10e2ac81166c13f97c4973a9/yarl-1.11.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:067b961853c8e62725ff2893226fef3d0da060656a9827f3f520fb1d19b2b68a", size = 484544 }, - { url = "https://files.pythonhosted.org/packages/fa/dc/ce90e9d85ef2233e81148a9658e4ea8372c6de070ce96c5c8bd3ff365144/yarl-1.11.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:8215f6f21394d1f46e222abeb06316e77ef328d628f593502d8fc2a9117bde83", size = 482409 }, - { url = "https://files.pythonhosted.org/packages/4c/a1/17c0a03615b0cd213aee2e318a0fbd3d07259c37976d85af9eec6184c589/yarl-1.11.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:498442e3af2a860a663baa14fbf23fb04b0dd758039c0e7c8f91cb9279799bff", size = 512970 }, - { url = "https://files.pythonhosted.org/packages/6c/ed/1e317799d54c79a3e4846db597510f5c84fb7643bb8703a3848136d40809/yarl-1.11.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:69721b8effdb588cb055cc22f7c5105ca6fdaa5aeb3ea09021d517882c4a904c", size = 515203 }, - { url = "https://files.pythonhosted.org/packages/7a/37/9a4e2d73953956fa686fa0f0c4a0881245f39423fa75875d981b4f680611/yarl-1.11.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1e969fa4c1e0b1a391f3fcbcb9ec31e84440253325b534519be0d28f4b6b533e", size = 497323 }, - { url = "https://files.pythonhosted.org/packages/a3/c3/a25ae9c85c0e50a8722aecc486ac5ba53b28d1384548df99b2145cb69862/yarl-1.11.1-cp311-cp311-win32.whl", hash = "sha256:7d51324a04fc4b0e097ff8a153e9276c2593106a811704025bbc1d6916f45ca6", size = 101226 }, - { url = "https://files.pythonhosted.org/packages/90/6d/c62ba0ae0232a0b0012706a7735a16b44a03216fedfb6ea0bcda79d1e12c/yarl-1.11.1-cp311-cp311-win_amd64.whl", hash = "sha256:15061ce6584ece023457fb8b7a7a69ec40bf7114d781a8c4f5dcd68e28b5c53b", size = 110471 }, - { url = "https://files.pythonhosted.org/packages/3b/05/379002019a0c9d5dc0c4cc6f71e324ea43461ae6f58e94ee87e07b8ffa90/yarl-1.11.1-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:a4264515f9117be204935cd230fb2a052dd3792789cc94c101c535d349b3dab0", size = 189044 }, - { url = "https://files.pythonhosted.org/packages/23/d5/e62cfba5ceaaf92ee4f9af6f9c9ab2f2b47d8ad48687fa69570a93b0872c/yarl-1.11.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:f41fa79114a1d2eddb5eea7b912d6160508f57440bd302ce96eaa384914cd265", size = 114867 }, - { url = "https://files.pythonhosted.org/packages/b1/10/6abc0bd7e7fe7c6b9b9e9ce0ff558912c9ecae65a798f5442020ef9e4177/yarl-1.11.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:02da8759b47d964f9173c8675710720b468aa1c1693be0c9c64abb9d8d9a4867", size = 112737 }, - { url = "https://files.pythonhosted.org/packages/37/a5/ad026afde5efe1849f4f55bd9f9a2cb5b006511b324db430ae5336104fb3/yarl-1.11.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9361628f28f48dcf8b2f528420d4d68102f593f9c2e592bfc842f5fb337e44fd", size = 482887 }, - { url = "https://files.pythonhosted.org/packages/f8/82/b8bee972617b800319b4364cfcd69bfaf7326db052e91a56e63986cc3e05/yarl-1.11.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b91044952da03b6f95fdba398d7993dd983b64d3c31c358a4c89e3c19b6f7aef", size = 498635 }, - { url = "https://files.pythonhosted.org/packages/af/ad/ac688503b134e02e8505415f0b8e94dc8e92a97e82abdd9736658389b5ae/yarl-1.11.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:74db2ef03b442276d25951749a803ddb6e270d02dda1d1c556f6ae595a0d76a8", size = 496198 }, - { url = "https://files.pythonhosted.org/packages/ce/f2/b6cae0ad1afed6e95f82ab2cb9eb5b63e41f1463ece2a80c39d80cf6167a/yarl-1.11.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7e975a2211952a8a083d1b9d9ba26472981ae338e720b419eb50535de3c02870", size = 489068 }, - { url = "https://files.pythonhosted.org/packages/c8/f4/355e69b5563154b40550233ffba8f6099eac0c99788600191967763046cf/yarl-1.11.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8aef97ba1dd2138112890ef848e17d8526fe80b21f743b4ee65947ea184f07a2", size = 468286 }, - { url = "https://files.pythonhosted.org/packages/26/3d/3c37f3f150faf87b086f7915724f2fcb9ff2f7c9d3f6c0f42b7722bd9b77/yarl-1.11.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:a7915ea49b0c113641dc4d9338efa9bd66b6a9a485ffe75b9907e8573ca94b84", size = 484568 }, - { url = "https://files.pythonhosted.org/packages/94/ee/d591abbaea3b14e0f68bdec5cbcb75f27107190c51889d518bafe5d8f120/yarl-1.11.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:504cf0d4c5e4579a51261d6091267f9fd997ef58558c4ffa7a3e1460bd2336fa", size = 484947 }, - { url = "https://files.pythonhosted.org/packages/57/70/ad1c65a13315f03ff0c63fd6359dd40d8198e2a42e61bf86507602a0364f/yarl-1.11.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:3de5292f9f0ee285e6bd168b2a77b2a00d74cbcfa420ed078456d3023d2f6dff", size = 505610 }, - { url = "https://files.pythonhosted.org/packages/4c/8c/6086dec0f8d7df16d136b38f373c49cf3d2fb94464e5a10bf788b36f3f54/yarl-1.11.1-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:a34e1e30f1774fa35d37202bbeae62423e9a79d78d0874e5556a593479fdf239", size = 515951 }, - { url = "https://files.pythonhosted.org/packages/49/79/e0479e9a3bbb7bdcb82779d89711b97cea30902a4bfe28d681463b7071ce/yarl-1.11.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:66b63c504d2ca43bf7221a1f72fbe981ff56ecb39004c70a94485d13e37ebf45", size = 501273 }, - { url = "https://files.pythonhosted.org/packages/8e/85/eab962453e81073276b22f3d1503dffe6bfc3eb9cd0f31899970de05d490/yarl-1.11.1-cp312-cp312-win32.whl", hash = "sha256:a28b70c9e2213de425d9cba5ab2e7f7a1c8ca23a99c4b5159bf77b9c31251447", size = 101139 }, - { url = "https://files.pythonhosted.org/packages/5d/de/618b3e5cab10af8a2ed3eb625dac61c1d16eb155d1f56f9fdb3500786c12/yarl-1.11.1-cp312-cp312-win_amd64.whl", hash = "sha256:17b5a386d0d36fb828e2fb3ef08c8829c1ebf977eef88e5367d1c8c94b454639", size = 110504 }, - { url = "https://files.pythonhosted.org/packages/07/b7/948e4f427817e0178f3737adf6712fea83f76921e11e2092f403a8a9dc4a/yarl-1.11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:1fa2e7a406fbd45b61b4433e3aa254a2c3e14c4b3186f6e952d08a730807fa0c", size = 185061 }, - { url = "https://files.pythonhosted.org/packages/f3/67/8d91ad79a3b907b4fef27fafa912350554443ba53364fff3c347b41105cb/yarl-1.11.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:750f656832d7d3cb0c76be137ee79405cc17e792f31e0a01eee390e383b2936e", size = 113056 }, - { url = "https://files.pythonhosted.org/packages/a1/77/6b2348a753702fa87f435cc33dcec21981aaca8ef98a46566a7b29940b4a/yarl-1.11.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:0b8486f322d8f6a38539136a22c55f94d269addb24db5cb6f61adc61eabc9d93", size = 110958 }, - { url = "https://files.pythonhosted.org/packages/8e/3e/6eadf32656741549041f549a392f3b15245d3a0a0b12a9bc22bd6b69621f/yarl-1.11.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3fce4da3703ee6048ad4138fe74619c50874afe98b1ad87b2698ef95bf92c96d", size = 470326 }, - { url = "https://files.pythonhosted.org/packages/3d/a4/1b641a8c7899eeaceec45ff105a2e7206ec0eb0fb9d86403963cc8521c5e/yarl-1.11.1-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8ed653638ef669e0efc6fe2acb792275cb419bf9cb5c5049399f3556995f23c7", size = 484778 }, - { url = "https://files.pythonhosted.org/packages/8a/f5/80c142f34779a5c26002b2bf1f73b9a9229aa9e019ee6f9fd9d3e9704e78/yarl-1.11.1-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:18ac56c9dd70941ecad42b5a906820824ca72ff84ad6fa18db33c2537ae2e089", size = 485568 }, - { url = "https://files.pythonhosted.org/packages/f8/f2/6b40ffea2d5d3a11f514ab23c30d14f52600c36a3210786f5974b6701bb8/yarl-1.11.1-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:688654f8507464745ab563b041d1fb7dab5d9912ca6b06e61d1c4708366832f5", size = 477801 }, - { url = "https://files.pythonhosted.org/packages/4c/1a/e60c116f3241e4842ed43c104eb2751abe02f6bac0301cdae69e4fda9c3a/yarl-1.11.1-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4973eac1e2ff63cf187073cd4e1f1148dcd119314ab79b88e1b3fad74a18c9d5", size = 455361 }, - { url = "https://files.pythonhosted.org/packages/b9/98/fe0aeee425a4bc5cd3ed86e867661d2bfa782544fa07a8e3dcd97d51ae3d/yarl-1.11.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:964a428132227edff96d6f3cf261573cb0f1a60c9a764ce28cda9525f18f7786", size = 473893 }, - { url = "https://files.pythonhosted.org/packages/6b/9b/677455d146bd3cecd350673f0e4bb28854af66726493ace3b640e9c5552b/yarl-1.11.1-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:6d23754b9939cbab02c63434776df1170e43b09c6a517585c7ce2b3d449b7318", size = 476407 }, - { url = "https://files.pythonhosted.org/packages/33/ca/ce85766247a9a9b56654428fb78a3e14ea6947a580a9c4e891b3aa7da322/yarl-1.11.1-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:c2dc4250fe94d8cd864d66018f8344d4af50e3758e9d725e94fecfa27588ff82", size = 490848 }, - { url = "https://files.pythonhosted.org/packages/6d/d6/717f0f19bcf2c4705ad95550b4b6319a0d8d1d4f137ea5e223207f00df50/yarl-1.11.1-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:09696438cb43ea6f9492ef237761b043f9179f455f405279e609f2bc9100212a", size = 501084 }, - { url = "https://files.pythonhosted.org/packages/14/b5/b93c70d9a462b802c8df65c64b85f49d86b4ba70c393fbad95cf7ec053cb/yarl-1.11.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:999bfee0a5b7385a0af5ffb606393509cfde70ecca4f01c36985be6d33e336da", size = 491776 }, - { url = "https://files.pythonhosted.org/packages/03/0f/5a52eaa402a6a93265ba82f42c6f6085ccbe483e1b058ad34207e75812b1/yarl-1.11.1-cp313-cp313-win32.whl", hash = "sha256:ce928c9c6409c79e10f39604a7e214b3cb69552952fbda8d836c052832e6a979", size = 485250 }, - { url = "https://files.pythonhosted.org/packages/dd/97/946d26a5d82706a6769399cabd472c59f9a3227ce1432afb4739b9c29572/yarl-1.11.1-cp313-cp313-win_amd64.whl", hash = "sha256:501c503eed2bb306638ccb60c174f856cc3246c861829ff40eaa80e2f0330367", size = 492590 }, - { url = "https://files.pythonhosted.org/packages/5b/b3/841f7d706137bdc8b741c6826106b6f703155076d58f1830f244da857451/yarl-1.11.1-py3-none-any.whl", hash = "sha256:72bf26f66456baa0584eff63e44545c9f0eaed9b73cb6601b647c91f14c11f38", size = 38648 }, +sdist = { url = "https://files.pythonhosted.org/packages/e0/11/2b8334f4192646677a2e7da435670d043f536088af943ec242f31453e5ba/yarl-1.13.1.tar.gz", hash = "sha256:ec8cfe2295f3e5e44c51f57272afbd69414ae629ec7c6b27f5a410efc78b70a0", size = 165912 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/37/64/1eaa5d080ceb8742b75a25eff4d510439459ff9c7fbe03e8e929a732ca07/yarl-1.13.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:216a6785f296169ed52cd7dcdc2612f82c20f8c9634bf7446327f50398732a51", size = 189609 }, + { url = "https://files.pythonhosted.org/packages/e2/49/7faf592dd5d4ae4b789988750739c327b81070aa6d428848ce71f6112c1b/yarl-1.13.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:40c6e73c03a6befb85b72da213638b8aaa80fe4136ec8691560cf98b11b8ae6e", size = 115504 }, + { url = "https://files.pythonhosted.org/packages/0c/02/6dd48672009bdf135a298a7250875321098b7cbbca5af8c49d8dae07b635/yarl-1.13.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:2430cf996113abe5aee387d39ee19529327205cda975d2b82c0e7e96e5fdabdc", size = 113754 }, + { url = "https://files.pythonhosted.org/packages/0e/4c/dd49a78833691ccdc15738eb814e37df47f0f25baeefb1cec64ecb4459eb/yarl-1.13.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9fb4134cc6e005b99fa29dbc86f1ea0a298440ab6b07c6b3ee09232a3b48f495", size = 486101 }, + { url = "https://files.pythonhosted.org/packages/36/ec/e5e6ed4344de34d3554a22d181df4d90a4d0f257575c28b767ad8c1add0b/yarl-1.13.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:309c104ecf67626c033845b860d31594a41343766a46fa58c3309c538a1e22b2", size = 505989 }, + { url = "https://files.pythonhosted.org/packages/7d/af/0318b0d03471207b3959e0e6ca2964b689744d8482fdbfdc2958854373b4/yarl-1.13.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f90575e9fe3aae2c1e686393a9689c724cd00045275407f71771ae5d690ccf38", size = 500428 }, + { url = "https://files.pythonhosted.org/packages/c4/09/5e47823e3abb26ddda447b500be28137971d246b0c771a02f855dd06b30b/yarl-1.13.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9d2e1626be8712333a9f71270366f4a132f476ffbe83b689dd6dc0d114796c74", size = 488954 }, + { url = "https://files.pythonhosted.org/packages/9a/c4/e26317d48bd6bf59dfbb6049d022582a376de01440e5c2bbe92009f8117a/yarl-1.13.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5b66c87da3c6da8f8e8b648878903ca54589038a0b1e08dde2c86d9cd92d4ac9", size = 471561 }, + { url = "https://files.pythonhosted.org/packages/93/c5/4dfb00b84fc6df79b3e42d8716ba8f747d7ebf0c14640c7e65d923f39ea7/yarl-1.13.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:cf1ad338620249f8dd6d4b6a91a69d1f265387df3697ad5dc996305cf6c26fb2", size = 485652 }, + { url = "https://files.pythonhosted.org/packages/9d/fb/bde1430c94d6e5de27d0031e3fb5d85467d975aecdc67e6c686f5c36bbfd/yarl-1.13.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:9915300fe5a0aa663c01363db37e4ae8e7c15996ebe2c6cce995e7033ff6457f", size = 483530 }, + { url = "https://files.pythonhosted.org/packages/5c/80/9f9c9d567ac5fb355e252dc27b75ccf92a3e4bea8b1c5610d5d1240c1b30/yarl-1.13.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:703b0f584fcf157ef87816a3c0ff868e8c9f3c370009a8b23b56255885528f10", size = 514085 }, + { url = "https://files.pythonhosted.org/packages/aa/9b/3aeb817a60bde4be6acb476a46bc6184c27b5c91f23ec726d9e6e46b89cf/yarl-1.13.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:1d8e3ca29f643dd121f264a7c89f329f0fcb2e4461833f02de6e39fef80f89da", size = 516342 }, + { url = "https://files.pythonhosted.org/packages/71/9d/d7aa4fd8b16e174c4c16b826f54a0e9e4533fb3ae09741906ccc811362d0/yarl-1.13.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:7055bbade838d68af73aea13f8c86588e4bcc00c2235b4b6d6edb0dbd174e246", size = 498430 }, + { url = "https://files.pythonhosted.org/packages/b0/3d/b46aad1725f8d043beee2d47ffddffb1939178bec6f9584b46215efe5a78/yarl-1.13.1-cp311-cp311-win32.whl", hash = "sha256:a3442c31c11088e462d44a644a454d48110f0588de830921fd201060ff19612a", size = 102436 }, + { url = "https://files.pythonhosted.org/packages/89/9e/bbbda05279230dc12d879dfcf971f77f9c932e457fbcd870efb4c3bdf10c/yarl-1.13.1-cp311-cp311-win_amd64.whl", hash = "sha256:81bad32c8f8b5897c909bf3468bf601f1b855d12f53b6af0271963ee67fff0d2", size = 111678 }, + { url = "https://files.pythonhosted.org/packages/64/de/1602352e5bb47c4b86921b004fe84d0646ef9abeda3dfc55f1d2271829e4/yarl-1.13.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f452cc1436151387d3d50533523291d5f77c6bc7913c116eb985304abdbd9ec9", size = 190253 }, + { url = "https://files.pythonhosted.org/packages/83/f0/2abc6f0af8f243c4a5190e687897e7684baea2c97f5f1be2321418163c7e/yarl-1.13.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:9cec42a20eae8bebf81e9ce23fb0d0c729fc54cf00643eb251ce7c0215ad49fe", size = 116079 }, + { url = "https://files.pythonhosted.org/packages/ad/eb/a578f935e2b6834a00b38156f81f3a6545e14a360ff8a296019116502a9c/yarl-1.13.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d959fe96e5c2712c1876d69af0507d98f0b0e8d81bee14cfb3f6737470205419", size = 113943 }, + { url = "https://files.pythonhosted.org/packages/da/ee/2bf5f8ffbea5b18fbca274dd04e300a033e43e92d261ac60722361b216ce/yarl-1.13.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b8c837ab90c455f3ea8e68bee143472ee87828bff19ba19776e16ff961425b57", size = 483984 }, + { url = "https://files.pythonhosted.org/packages/05/9f/20d07ed84cbac847b989ef61130f2cbec6dc60f273b81d51041c35740eb3/yarl-1.13.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:94a993f976cdcb2dc1b855d8b89b792893220db8862d1a619efa7451817c836b", size = 499723 }, + { url = "https://files.pythonhosted.org/packages/e5/90/cc6d3dab4fc33b6f80d498c6276995fcbe16db1005141be6133345b597c1/yarl-1.13.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2b2442a415a5f4c55ced0fade7b72123210d579f7d950e0b5527fc598866e62c", size = 497279 }, + { url = "https://files.pythonhosted.org/packages/47/a0/c1404aa8c7e025aa05a81f3a34c42131f8b11836e49450e1558bcd64a3bb/yarl-1.13.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3fdbf0418489525231723cdb6c79e7738b3cbacbaed2b750cb033e4ea208f220", size = 490188 }, + { url = "https://files.pythonhosted.org/packages/2e/8b/ebb195c4a4a5b5a84b0ade8469404609d68adf8f1dcf88e8b2b5297566cc/yarl-1.13.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6b7f6e699304717fdc265a7e1922561b02a93ceffdaefdc877acaf9b9f3080b8", size = 469378 }, + { url = "https://files.pythonhosted.org/packages/40/8f/6a00380c6653006ac0112ebbf0ff24eb7b2d71359ac2c410a98822d89bfa/yarl-1.13.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:bcd5bf4132e6a8d3eb54b8d56885f3d3a38ecd7ecae8426ecf7d9673b270de43", size = 485681 }, + { url = "https://files.pythonhosted.org/packages/2c/94/797d18a3b9ea125a24ba3c69cd71b3561d227d5bb61dbadf2cb2afd6c319/yarl-1.13.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:2a93a4557f7fc74a38ca5a404abb443a242217b91cd0c4840b1ebedaad8919d4", size = 486049 }, + { url = "https://files.pythonhosted.org/packages/75/b2/3573e18eb52ca204ee076a94c145edc80c3df21694648b35ae34c19ac9bb/yarl-1.13.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:22b739f99c7e4787922903f27a892744189482125cc7b95b747f04dd5c83aa9f", size = 506742 }, + { url = "https://files.pythonhosted.org/packages/1f/36/f6b5b0fb7c771d5c6c08b7d00a53cd523793454113d4c96460e3f49a1cdd/yarl-1.13.1-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:2db874dd1d22d4c2c657807562411ffdfabec38ce4c5ce48b4c654be552759dc", size = 517070 }, + { url = "https://files.pythonhosted.org/packages/8e/17/48637d4ddcb606f5591afee78d060eab70e172e14766e1fd23453bfed846/yarl-1.13.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:4feaaa4742517eaceafcbe74595ed335a494c84634d33961214b278126ec1485", size = 502397 }, + { url = "https://files.pythonhosted.org/packages/83/2c/7392645dc1c9eeb8a5485696302a33e3d59bea8a448c8e2f36f98a728e0a/yarl-1.13.1-cp312-cp312-win32.whl", hash = "sha256:bbf9c2a589be7414ac4a534d54e4517d03f1cbb142c0041191b729c2fa23f320", size = 102343 }, + { url = "https://files.pythonhosted.org/packages/9c/c0/7329799080d7e0bf7b10db417900701ba6810e78a249aef1f4bf3fc2cccb/yarl-1.13.1-cp312-cp312-win_amd64.whl", hash = "sha256:d07b52c8c450f9366c34aa205754355e933922c79135125541daae6cbf31c799", size = 111719 }, + { url = "https://files.pythonhosted.org/packages/d3/d2/9542e6207a6e64c32b14b2d9ca4fad6ff80310fc75e70cdbe31680a758c2/yarl-1.13.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:95c6737f28069153c399d875317f226bbdea939fd48a6349a3b03da6829fb550", size = 186266 }, + { url = "https://files.pythonhosted.org/packages/8b/68/4c6d1aacbc23a05e84c3fab7aaa68c5a7d4531290021c2370fa1e5524fb1/yarl-1.13.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:cd66152561632ed4b2a9192e7f8e5a1d41e28f58120b4761622e0355f0fe034c", size = 114268 }, + { url = "https://files.pythonhosted.org/packages/ed/87/6ad8e22c918d745092329ec427c0778b5c85ffd5b805e38750024b7464f2/yarl-1.13.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:6a2acde25be0cf9be23a8f6cbd31734536a264723fca860af3ae5e89d771cd71", size = 112164 }, + { url = "https://files.pythonhosted.org/packages/ca/5b/c6c4ac4be1edea6759f05ad74d87a1c61329737bdb90da5f66e188310461/yarl-1.13.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9a18595e6a2ee0826bf7dfdee823b6ab55c9b70e8f80f8b77c37e694288f5de1", size = 471437 }, + { url = "https://files.pythonhosted.org/packages/c1/5c/ec7f0121a5fa67ee76325e1aaa27470d5521d80a25aa1bad5dde773edbe1/yarl-1.13.1-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a31d21089894942f7d9a8df166b495101b7258ff11ae0abec58e32daf8088813", size = 485894 }, + { url = "https://files.pythonhosted.org/packages/d7/e8/624fc8082cbff62c537798ce837a6044f70e2e00472ab719deb376ff6e39/yarl-1.13.1-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:45f209fb4bbfe8630e3d2e2052535ca5b53d4ce2d2026bed4d0637b0416830da", size = 486702 }, + { url = "https://files.pythonhosted.org/packages/dc/18/013f7d2e3f0ff28b85299ed19164f899ea4f02da8812621a40937428bf48/yarl-1.13.1-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8f722f30366474a99745533cc4015b1781ee54b08de73260b2bbe13316079851", size = 478911 }, + { url = "https://files.pythonhosted.org/packages/d7/3c/5b628939e3a22fb9375df453188e97190d21f6244c49637e19799896cd41/yarl-1.13.1-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f3bf60444269345d712838bb11cc4eadaf51ff1a364ae39ce87a5ca8ad3bb2c8", size = 456488 }, + { url = "https://files.pythonhosted.org/packages/8b/2b/a3548db86510c1d95bff344c1c588b84582eeb3a55ea15a149a24d7069f0/yarl-1.13.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:942c80a832a79c3707cca46bd12ab8aa58fddb34b1626d42b05aa8f0bcefc206", size = 475016 }, + { url = "https://files.pythonhosted.org/packages/d8/e2/e2a540f18f849909e3ee594766bf7b0a7fde176ff0cfb2f95121033752e2/yarl-1.13.1-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:44b07e1690f010c3c01d353b5790ec73b2f59b4eae5b0000593199766b3f7a5c", size = 477521 }, + { url = "https://files.pythonhosted.org/packages/3a/df/4cda4052da48a57ce4f20a0849b7344902aa3e149a0b409525509fc43985/yarl-1.13.1-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:396e59b8de7e4d59ff5507fb4322d2329865b909f29a7ed7ca37e63ade7f835c", size = 492000 }, + { url = "https://files.pythonhosted.org/packages/bf/b6/180dbb0aa846cafb9ce89bd33c477e200dd00072c7775372f34651c20b9a/yarl-1.13.1-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:3bb83a0f12701c0b91112a11148b5217617982e1e466069d0555be9b372f2734", size = 502195 }, + { url = "https://files.pythonhosted.org/packages/ff/37/e97c280344342e326a1860a70054a0488c379e8937325f97f9a9fe6b453d/yarl-1.13.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:c92b89bffc660f1274779cb6fbb290ec1f90d6dfe14492523a0667f10170de26", size = 492892 }, + { url = "https://files.pythonhosted.org/packages/ed/97/cd35f39ba8183ef193a6709aa0b2fcaabebd6915202d6999b01fa630b2bb/yarl-1.13.1-cp313-cp313-win32.whl", hash = "sha256:269c201bbc01d2cbba5b86997a1e0f73ba5e2f471cfa6e226bcaa7fd664b598d", size = 486463 }, + { url = "https://files.pythonhosted.org/packages/05/33/bd9d33503a0f73d095b01ed438423b924e6786e90102ca4912e573cc5aa3/yarl-1.13.1-cp313-cp313-win_amd64.whl", hash = "sha256:1d0828e17fa701b557c6eaed5edbd9098eb62d8838344486248489ff233998b8", size = 493804 }, + { url = "https://files.pythonhosted.org/packages/74/81/419c24f7c94f56b96d04955482efb5b381635ad265b5b7fbab333a9dfde3/yarl-1.13.1-py3-none-any.whl", hash = "sha256:6a5185ad722ab4dd52d5fb1f30dcc73282eb1ed494906a92d1a228d3f89607b0", size = 39862 }, ] [[package]] From 7ebd7b8b4df29c5150ecbd296d9c8c74b153f801 Mon Sep 17 00:00:00 2001 From: garrettpall <76917194+garrettpall@users.noreply.github.com> Date: Mon, 30 Sep 2024 17:39:23 -0400 Subject: [PATCH 174/214] maneuversd: Add note about cars requiring resume button press to exit standstill (#33665) * maneuversd: Set active true when resume pressed * Revert "maneuversd: Set active true when resume pressed" This reverts commit 1165270c47c6a3fe4af5752f7779c36bd5e840c9. * Add note * Update README.md --------- Co-authored-by: Shane Smiskol --- tools/longitudinal_maneuvers/README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/tools/longitudinal_maneuvers/README.md b/tools/longitudinal_maneuvers/README.md index 66ec697912..643af7fd82 100644 --- a/tools/longitudinal_maneuvers/README.md +++ b/tools/longitudinal_maneuvers/README.md @@ -18,7 +18,9 @@ Test your vehicle's longitudinal control tuning with this tool. The tool will te ![videoframe_6652](https://github.com/user-attachments/assets/e9d4c95a-cd76-4ab7-933e-19937792fa0f) -5. Ensure the road ahead is clear, as openpilot will not brake for any obstructions in this mode. Once you are ready, press "Set" on your steering wheel to start the tests. The tests will run for about 4 minutes. If you need to pause the tests, press "Cancel" on your steering wheel. You can resume the tests by pressing "Resume" on your steering wheel. +5. Ensure the road ahead is clear, as openpilot will not brake for any obstructions in this mode. Once you are ready, press "Set" on your steering wheel to start the tests. The tests will run for about 4 minutes. If you need to pause the tests, press "Cancel" on your steering wheel. You can resume the tests by pressing "Resume" on your steering wheel. + + **Note:** For GM cars, it is recommended to hold down the resume button for all low-speed tests (starting, stopping and creep) to avoid the car entering standstill. ![cog-clip-00 01 11 250-00 01 22 250](https://github.com/user-attachments/assets/c312c1cc-76e8-46e1-a05e-bb9dfb58994f) From 47cc314b14baba530920e78ad1c31935acc71b8b Mon Sep 17 00:00:00 2001 From: Mitchell Goff Date: Mon, 30 Sep 2024 18:13:51 -0700 Subject: [PATCH 175/214] Gate acceleration on model gas press predictions (#33643) * no ui squash * already calibrated * Already calibrated * Add longitudinal maneuver tests * Fix linter errors * Added get_coast_accel function --------- Co-authored-by: Bruce Wayne --- .../controls/lib/longitudinal_planner.py | 27 +++++++++++-- .../test/longitudinal_maneuvers/maneuver.py | 16 ++++++-- .../test/longitudinal_maneuvers/plant.py | 12 ++++-- .../test_longitudinal.py | 38 +++++++++++++++++++ 4 files changed, 83 insertions(+), 10 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 0b65119383..54838924be 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -21,6 +21,8 @@ A_CRUISE_MIN = -1.2 A_CRUISE_MAX_VALS = [1.6, 1.2, 0.8, 0.6] A_CRUISE_MAX_BP = [0., 10.0, 25., 40.] CONTROL_N_T_IDX = ModelConstants.T_IDXS[:CONTROL_N] +ALLOW_THROTTLE_THRESHOLD = 0.5 +ACCEL_LIMIT_MARGIN = 0.05 # Lookup table for turns _A_TOTAL_MAX_V = [1.7, 3.2] @@ -30,6 +32,9 @@ _A_TOTAL_MAX_BP = [20., 40.] def get_max_accel(v_ego): return interp(v_ego, A_CRUISE_MAX_BP, A_CRUISE_MAX_VALS) +def get_coast_accel(pitch): + return np.sin(pitch) * -5.65 - 0.3 # fitted from data using xx/projects/allow_throttle/compute_coast_accel.py + def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): """ @@ -69,6 +74,7 @@ class LongitudinalPlanner: self.mpc = LongitudinalMpc(dt=dt) self.fcw = False self.dt = dt + self.allow_throttle = True self.a_desired = init_a self.v_desired_filter = FirstOrderFilter(init_v, 2.0, self.dt) @@ -93,11 +99,20 @@ class LongitudinalPlanner: v = np.zeros(len(T_IDXS_MPC)) a = np.zeros(len(T_IDXS_MPC)) j = np.zeros(len(T_IDXS_MPC)) - return x, v, a, j + if len(model_msg.meta.disengagePredictions.gasPressProbs) > 1: + throttle_prob = model_msg.meta.disengagePredictions.gasPressProbs[1] + else: + throttle_prob = 1.0 + return x, v, a, j, throttle_prob def update(self, sm): self.mpc.mode = 'blended' if sm['selfdriveState'].experimentalMode else 'acc' + if len(sm['carControl'].orientationNED) == 3: + accel_coast = get_coast_accel(sm['carControl'].orientationNED[1]) + else: + accel_coast = ACCEL_MAX + v_ego = sm['carState'].vEgo v_cruise_kph = min(sm['carState'].vCruise, V_CRUISE_MAX) v_cruise = v_cruise_kph * CV.KPH_TO_MS @@ -130,6 +145,13 @@ class LongitudinalPlanner: self.v_desired_filter.x = max(0.0, self.v_desired_filter.update(v_ego)) # Compute model v_ego error self.v_model_error = get_speed_error(sm['modelV2'], v_ego) + x, v, a, j, throttle_prob = self.parse_model(sm['modelV2'], self.v_model_error) + self.allow_throttle = throttle_prob > ALLOW_THROTTLE_THRESHOLD + + if not self.allow_throttle and v_ego > 5.0: # Don't clip at low speeds since throttle_prob doesn't account for creep + # MPC breaks when accel limits would cause negative velocity within the MPC horizon, so we clip the max accel limit at vEgo/T_MAX plus a bit of margin + clipped_accel_coast = max(accel_coast, accel_limits_turns[0], -v_ego / T_IDXS_MPC[-1] + ACCEL_LIMIT_MARGIN) + accel_limits_turns[1] = min(accel_limits_turns[1], clipped_accel_coast) if force_slow_decel: v_cruise = 0.0 @@ -140,7 +162,6 @@ class LongitudinalPlanner: self.mpc.set_weights(prev_accel_constraint, personality=sm['selfdriveState'].personality) self.mpc.set_accel_limits(accel_limits_turns[0], accel_limits_turns[1]) self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired) - x, v, a, j = self.parse_model(sm['modelV2'], self.v_model_error) self.mpc.update(sm['radarState'], v_cruise, x, v, a, j, personality=sm['selfdriveState'].personality) self.v_desired_trajectory = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC, self.mpc.v_solution) @@ -179,6 +200,6 @@ class LongitudinalPlanner: longitudinalPlan.aTarget = a_target longitudinalPlan.shouldStop = should_stop longitudinalPlan.allowBrake = True - longitudinalPlan.allowThrottle = True + longitudinalPlan.allowThrottle = self.allow_throttle pm.send('longitudinalPlan', plan_send) diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py index 6c8495cc3b..301f99dd56 100644 --- a/selfdrive/test/longitudinal_maneuvers/maneuver.py +++ b/selfdrive/test/longitudinal_maneuvers/maneuver.py @@ -12,11 +12,14 @@ class Maneuver: self.breakpoints = kwargs.get("breakpoints", [0.0, duration]) self.speed_lead_values = kwargs.get("speed_lead_values", [0.0 for i in range(len(self.breakpoints))]) self.prob_lead_values = kwargs.get("prob_lead_values", [1.0 for i in range(len(self.breakpoints))]) + self.prob_throttle_values = kwargs.get("prob_throttle_values", [1.0 for i in range(len(self.breakpoints))]) self.cruise_values = kwargs.get("cruise_values", [50.0 for i in range(len(self.breakpoints))]) + self.pitch_values = kwargs.get("pitch_values", [0.0 for i in range(len(self.breakpoints))]) self.only_lead2 = kwargs.get("only_lead2", False) self.only_radar = kwargs.get("only_radar", False) self.ensure_start = kwargs.get("ensure_start", False) + self.ensure_slowdown = kwargs.get("ensure_slowdown", False) self.enabled = kwargs.get("enabled", True) self.e2e = kwargs.get("e2e", False) self.personality = kwargs.get("personality", 0) @@ -42,9 +45,11 @@ class Maneuver: logs = [] while plant.current_time < self.duration: speed_lead = np.interp(plant.current_time, self.breakpoints, self.speed_lead_values) - prob = np.interp(plant.current_time, self.breakpoints, self.prob_lead_values) + prob_lead = np.interp(plant.current_time, self.breakpoints, self.prob_lead_values) cruise = np.interp(plant.current_time, self.breakpoints, self.cruise_values) - log = plant.step(speed_lead, prob, cruise) + pitch = np.interp(plant.current_time, self.breakpoints, self.pitch_values) + prob_throttle = np.interp(plant.current_time, self.breakpoints, self.prob_throttle_values) + log = plant.step(speed_lead, prob_lead, cruise, pitch, prob_throttle) d_rel = log['distance_lead'] - log['distance'] if self.lead_relevancy else 200. v_rel = speed_lead - log['speed'] if self.lead_relevancy else 0. @@ -57,13 +62,18 @@ class Maneuver: speed_lead, log['acceleration']])) - if d_rel < .4 and (self.only_radar or prob > 0.5): + if d_rel < .4 and (self.only_radar or prob_lead > 0.5): print("Crashed!!!!") valid = False if self.ensure_start and log['v_rel'] > 0 and log['speeds'][-1] <= 0.1: print('LongitudinalPlanner not starting!') valid = False + + if self.ensure_slowdown and log['speed'] > 5.5: + print('LongitudinalPlanner not slowing down!') + valid = False + if self.force_decel and log['speed'] > 1e-1 and log['acceleration'] > -0.04: print('Not stopping with force decel') valid = False diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index 21f2b3b57f..3c8c09d6be 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -57,13 +57,14 @@ class Plant: def current_time(self): return float(self.rk.frame) / self.rate - def step(self, v_lead=0.0, prob=1.0, v_cruise=50.): + def step(self, v_lead=0.0, prob_lead=1.0, v_cruise=50., pitch=0.0, prob_throttle=1.0): # ******** publish a fake model going straight and fake calibration ******** # note that this is worst case for MPC, since model will delay long mpc by one time step radar = messaging.new_message('radarState') control = messaging.new_message('controlsState') ss = messaging.new_message('selfdriveState') car_state = messaging.new_message('carState') + car_control = messaging.new_message('carControl') model = messaging.new_message('modelV2') a_lead = (v_lead - self.v_lead_prev)/self.ts self.v_lead_prev = v_lead @@ -73,14 +74,14 @@ class Plant: v_rel = v_lead - self.speed if self.only_radar: status = True - elif prob > .5: + elif prob_lead > .5: status = True else: status = False else: d_rel = 200. v_rel = 0. - prob = 0.0 + prob_lead = 0.0 status = False lead = log.RadarState.LeadData.new_message() @@ -94,7 +95,7 @@ class Plant: # TODO use real radard logic for this lead.aLeadTau = float(_LEAD_ACCEL_TAU) lead.status = status - lead.modelProb = float(prob) + lead.modelProb = float(prob_lead) if not self.only_lead2: radar.radarState.leadOne = lead radar.radarState.leadTwo = lead @@ -112,6 +113,7 @@ class Plant: acceleration = log.XYZTData.new_message() acceleration.x = [float(x) for x in np.zeros_like(ModelConstants.T_IDXS)] model.modelV2.acceleration = acceleration + model.modelV2.meta.disengagePredictions.gasPressProbs = [float(prob_throttle) for _ in range(6)] control.controlsState.longControlState = LongCtrlState.pid if self.enabled else LongCtrlState.off ss.selfdriveState.experimentalMode = self.e2e @@ -120,10 +122,12 @@ class Plant: car_state.carState.vEgo = float(self.speed) car_state.carState.standstill = self.speed < 0.01 car_state.carState.vCruise = float(v_cruise * 3.6) + car_control.carControl.orientationNED = [0., float(pitch), 0.] # ******** get controlsState messages for plotting *** sm = {'radarState': radar.radarState, 'carState': car_state.carState, + 'carControl': car_control.carControl, 'controlsState': control.controlsState, 'selfdriveState': ss.selfdriveState, 'modelV2': model.modelV2} diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py index 62a95babeb..7eea44aae6 100644 --- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py +++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py @@ -82,6 +82,44 @@ def create_maneuvers(kwargs): breakpoints=[0.0, 2., 2.01], **kwargs, ), + Maneuver( + "approach stopped car at 20m/s, with prob_throttle_values and pitch = -0.1", + duration=30., + initial_speed=20., + lead_relevancy=True, + initial_distance_lead=120., + speed_lead_values=[0.0, 0., 0.], + prob_throttle_values=[1., 0., 0.], + cruise_values=[20., 20., 20.], + pitch_values=[0., -0.1, -0.1], + breakpoints=[0.0, 2., 2.01], + **kwargs, + ), + Maneuver( + "approach stopped car at 20m/s, with prob_throttle_values and pitch = +0.1", + duration=30., + initial_speed=20., + lead_relevancy=True, + initial_distance_lead=120., + speed_lead_values=[0.0, 0., 0.], + prob_throttle_values=[1., 0., 0.], + cruise_values=[20., 20., 20.], + pitch_values=[0., 0.1, 0.1], + breakpoints=[0.0, 2., 2.01], + **kwargs, + ), + Maneuver( + "slow to 5m/s with allow_throttle = False and pitch = +0.1", + duration=25., + initial_speed=20., + lead_relevancy=False, + prob_throttle_values=[1., 0., 0.], + cruise_values=[20., 20., 20.], + pitch_values=[0., 0.1, 0.1], + breakpoints=[0.0, 2., 2.01], + ensure_slowdown=True, + **kwargs, + ), Maneuver( "approach slower cut-in car at 20m/s", duration=20., From 216145d4bc035e2bd7f10d9f3968631db8535578 Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Mon, 30 Sep 2024 18:30:03 -0700 Subject: [PATCH 176/214] re-enable time to onroad test (#33680) re-add test --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index eb39781cb8..799b4fbbeb 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -147,7 +147,7 @@ node { ["build openpilot", "cd system/manager && ./build.py"], ["check dirty", "release/check-dirty.sh"], ["onroad tests", "pytest selfdrive/test/test_onroad.py -s"], - //["time to onroad", "pytest selfdrive/test/test_time_to_onroad.py"], + ["time to onroad", "pytest selfdrive/test/test_time_to_onroad.py"], ]) }, 'HW + Unit Tests': { From d826b08369555f7e39d03511efa4ddea62701517 Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Mon, 30 Sep 2024 18:59:46 -0700 Subject: [PATCH 177/214] ci: lower `soundd` CPU budget (#33684) tr --- selfdrive/test/test_onroad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index b99662df78..2f7fa00a32 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -53,7 +53,7 @@ PROCS = { "selfdrive.locationd.calibrationd": 2.0, "selfdrive.locationd.torqued": 5.0, "selfdrive.locationd.locationd": 25.0, - "selfdrive.ui.soundd": 3.5, + "selfdrive.ui.soundd": 3.38, "selfdrive.monitoring.dmonitoringd": 4.0, "./proclogd": 1.54, "system.logmessaged": 0.2, From b0e4d6ee7a313e9db08c86758c6c7188b23f9b67 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Mon, 30 Sep 2024 19:15:29 -0700 Subject: [PATCH 178/214] Model replay needs speed (#33683) * Model replay needs speed * Model replay needs speed * Revert "Model replay needs speed" This reverts commit 6d6a4993dd163c02d84465868e85b290d4fc6bbd. * Update model_replay_ref_commit --- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- selfdrive/test/process_replay/process_replay.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 182a17c7b7..5fb62db139 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -76b8121429ad69d6548f744a39680ade324947e2 +56743d36006d4312544ace7f53491727aa7ac302 diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index af33b0458b..b6d5ba6afd 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -569,7 +569,7 @@ CONFIGS = [ ), ProcessConfig( proc_name="modeld", - pubs=["deviceState", "roadCameraState", "wideRoadCameraState", "liveCalibration", "driverMonitoringState"], + pubs=["deviceState", "roadCameraState", "wideRoadCameraState", "liveCalibration", "driverMonitoringState", "carState"], subs=["modelV2", "drivingModelData", "cameraOdometry"], ignore=["logMonoTime", "modelV2.frameDropPerc", "modelV2.modelExecutionTime", "drivingModelData.frameDropPerc", "drivingModelData.modelExecutionTime"], should_recv_callback=ModeldCameraSyncRcvCallback(), From 6c227a66a2a91b6c9f91d9f76c5ec268145184ca Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Kacper=20R=C4=85czy?= Date: Mon, 30 Sep 2024 20:42:51 -0700 Subject: [PATCH 179/214] process_replay: drivingModelData migration (#33686) * Migrate modelV2 to drivingModelData * Add if statements * Fix --- selfdrive/modeld/fill_model_msg.py | 11 ++++++---- selfdrive/test/process_replay/migration.py | 25 ++++++++++++++++++++++ 2 files changed, 32 insertions(+), 4 deletions(-) diff --git a/selfdrive/modeld/fill_model_msg.py b/selfdrive/modeld/fill_model_msg.py index 10a1860b58..115ec94f88 100644 --- a/selfdrive/modeld/fill_model_msg.py +++ b/selfdrive/modeld/fill_model_msg.py @@ -48,6 +48,12 @@ def fill_xyz_poly(builder, degree, x, y, z): builder.yCoefficients = coeffs[:, 1].tolist() builder.zCoefficients = coeffs[:, 2].tolist() +def fill_lane_line_meta(builder, lane_lines, lane_line_probs): + builder.leftY = lane_lines[1].y[0] + builder.leftProb = lane_line_probs[1] + builder.rightY = lane_lines[2].y[0] + builder.rightProb = lane_line_probs[2] + def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._DynamicStructBuilder, net_output_data: dict[str, np.ndarray], publish_state: PublishState, vipc_frame_id: int, vipc_frame_id_extra: int, frame_id: int, frame_drop: float, @@ -130,10 +136,7 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D modelV2.laneLineProbs = net_output_data['lane_lines_prob'][0,1::2].tolist() lane_line_meta = driving_model_data.laneLineMeta - lane_line_meta.leftY = modelV2.laneLines[1].y[0] - lane_line_meta.leftProb = modelV2.laneLineProbs[1] - lane_line_meta.rightY = modelV2.laneLines[2].y[0] - lane_line_meta.rightProb = modelV2.laneLineProbs[2] + fill_lane_line_meta(lane_line_meta, modelV2.laneLines, modelV2.laneLineProbs) # road edges modelV2.init('roadEdges', 2) diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index 9c680ada9a..c0696f2181 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -3,6 +3,8 @@ from collections import defaultdict from cereal import messaging, car from opendbc.car.fingerprints import MIGRATION from opendbc.car.toyota.values import EPS_SCALE +from openpilot.selfdrive.modeld.constants import ModelConstants +from openpilot.selfdrive.modeld.fill_model_msg import fill_xyz_poly, fill_lane_line_meta from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_encode_index from openpilot.system.manager.process_config import managed_processes from panda import Panda @@ -19,6 +21,7 @@ def migrate_all(lr, manager_states=False, panda_states=False, camera_states=Fals msgs = migrate_liveLocationKalman(msgs) msgs = migrate_liveTracks(msgs) msgs = migrate_driverAssistance(msgs) + msgs = migrate_drivingModelData(msgs) if manager_states: msgs = migrate_managerState(msgs) if panda_states: @@ -29,6 +32,7 @@ def migrate_all(lr, manager_states=False, panda_states=False, camera_states=Fals return msgs + def migrate_driverAssistance(lr): all_msgs = [] for msg in lr: @@ -39,6 +43,27 @@ def migrate_driverAssistance(lr): return lr return all_msgs + +def migrate_drivingModelData(lr): + all_msgs = [] + for msg in lr: + all_msgs.append(msg) + if msg.which() == "modelV2": + dmd = messaging.new_message('drivingModelData', valid=msg.valid, logMonoTime=msg.logMonoTime) + for field in ["frameId", "frameIdExtra", "frameDropPerc", "modelExecutionTime", "action"]: + setattr(dmd.drivingModelData, field, getattr(msg.modelV2, field)) + for meta_field in ["laneChangeState", "laneChangeState"]: + setattr(dmd.drivingModelData.meta, meta_field, getattr(msg.modelV2.meta, meta_field)) + if len(msg.modelV2.laneLines) and len(msg.modelV2.laneLineProbs): + fill_lane_line_meta(dmd.drivingModelData.laneLineMeta, msg.modelV2.laneLines, msg.modelV2.laneLineProbs) + if all(len(a) for a in [msg.modelV2.position.x, msg.modelV2.position.y, msg.modelV2.position.z]): + fill_xyz_poly(dmd.drivingModelData.path, ModelConstants.POLY_PATH_DEGREE, msg.modelV2.position.x, msg.modelV2.position.y, msg.modelV2.position.z) + all_msgs.append(dmd.as_reader()) + elif msg.which() == "drivingModelData": + return lr + return all_msgs + + def migrate_liveTracks(lr): all_msgs = [] for msg in lr: From e442425c9d32774e50802cd5455313090060f4ad Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Tue, 1 Oct 2024 02:58:20 -0700 Subject: [PATCH 180/214] MLSIM trained model V0 (#33676) * squash f7343ba0-3f7d-4776-9819-2219b8d2d667/270 * fix broken ref * Model replay ref commit --- selfdrive/modeld/constants.py | 3 +- selfdrive/modeld/modeld.py | 29 ++++++++++++++----- selfdrive/modeld/models/commonmodel.cc | 21 +++++++++----- selfdrive/modeld/models/commonmodel.h | 5 ++-- selfdrive/modeld/models/supercombo.onnx | 4 +-- .../process_replay/model_replay_ref_commit | 2 +- 6 files changed, 43 insertions(+), 21 deletions(-) diff --git a/selfdrive/modeld/constants.py b/selfdrive/modeld/constants.py index 82161a5b67..bf74c2d1a0 100644 --- a/selfdrive/modeld/constants.py +++ b/selfdrive/modeld/constants.py @@ -15,7 +15,8 @@ class ModelConstants: # model inputs constants MODEL_FREQ = 20 FEATURE_LEN = 512 - HISTORY_BUFFER_LEN = 99 + FULL_HISTORY_BUFFER_LEN = 99 + HISTORY_BUFFER_LEN = 24 DESIRE_LEN = 8 TRAFFIC_CONVENTION_LEN = 2 LAT_PLANNER_STATE_LEN = 4 diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index abaaf299f7..f8a4b7fe0d 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -34,6 +34,7 @@ MODEL_PATHS = { METADATA_PATH = Path(__file__).parent / 'models/supercombo_metadata.pkl' + class FrameMeta: frame_id: int = 0 timestamp_sof: int = 0 @@ -55,6 +56,11 @@ class ModelState: self.frame = ModelFrame(context) self.wide_frame = ModelFrame(context) self.prev_desire = np.zeros(ModelConstants.DESIRE_LEN, dtype=np.float32) + self.full_features_20Hz = np.zeros((ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32) + self.desire_20Hz = np.zeros((ModelConstants.FULL_HISTORY_BUFFER_LEN + 1, ModelConstants.DESIRE_LEN), dtype=np.float32) + self.prev_desired_curv_20hz = np.zeros((ModelConstants.FULL_HISTORY_BUFFER_LEN + 1, ModelConstants.PREV_DESIRED_CURV_LEN), dtype=np.float32) + + # img buffers are managed in openCL transform code self.inputs = { 'desire': np.zeros(ModelConstants.DESIRE_LEN * (ModelConstants.HISTORY_BUFFER_LEN+1), dtype=np.float32), 'traffic_convention': np.zeros(ModelConstants.TRAFFIC_CONVENTION_LEN, dtype=np.float32), @@ -87,14 +93,16 @@ class ModelState: inputs: dict[str, np.ndarray], prepare_only: bool) -> dict[str, np.ndarray] | None: # Model decides when action is completed, so desire input is just a pulse triggered on rising edge inputs['desire'][0] = 0 - self.inputs['desire'][:-ModelConstants.DESIRE_LEN] = self.inputs['desire'][ModelConstants.DESIRE_LEN:] - self.inputs['desire'][-ModelConstants.DESIRE_LEN:] = np.where(inputs['desire'] - self.prev_desire > .99, inputs['desire'], 0) + new_desire = np.where(inputs['desire'] - self.prev_desire > .99, inputs['desire'], 0) self.prev_desire[:] = inputs['desire'] + self.desire_20Hz[:-1] = self.desire_20Hz[1:] + self.desire_20Hz[-1] = new_desire + self.inputs['desire'][:] = self.desire_20Hz.reshape((25,4,-1)).max(axis=1).flatten() + self.inputs['traffic_convention'][:] = inputs['traffic_convention'] self.inputs['lateral_control_params'][:] = inputs['lateral_control_params'] - # if getCLBuffer is not None, frame will be None self.model.setInputBuffer("input_imgs", self.frame.prepare(buf, transform.flatten(), self.model.getCLBuffer("input_imgs"))) self.model.setInputBuffer("big_input_imgs", self.wide_frame.prepare(wbuf, transform_wide.flatten(), self.model.getCLBuffer("big_input_imgs"))) @@ -104,10 +112,16 @@ class ModelState: self.model.execute() outputs = self.parser.parse_outputs(self.slice_outputs(self.output)) - self.inputs['features_buffer'][:-ModelConstants.FEATURE_LEN] = self.inputs['features_buffer'][ModelConstants.FEATURE_LEN:] - self.inputs['features_buffer'][-ModelConstants.FEATURE_LEN:] = outputs['hidden_state'][0, :] - self.inputs['prev_desired_curv'][:-ModelConstants.PREV_DESIRED_CURV_LEN] = self.inputs['prev_desired_curv'][ModelConstants.PREV_DESIRED_CURV_LEN:] - self.inputs['prev_desired_curv'][-ModelConstants.PREV_DESIRED_CURV_LEN:] = outputs['desired_curvature'][0, :] + self.full_features_20Hz[:-1] = self.full_features_20Hz[1:] + self.full_features_20Hz[-1] = outputs['hidden_state'][0, :] + + self.prev_desired_curv_20hz[:-1] = self.prev_desired_curv_20hz[1:] + self.prev_desired_curv_20hz[-1] = outputs['desired_curvature'][0, :] + + idxs = np.arange(-4,-100,-4)[::-1] + self.inputs['features_buffer'][:] = self.full_features_20Hz[idxs].flatten() + # TODO model only uses last value now, once that changes we need to input strided action history buffer + self.inputs['prev_desired_curv'][-ModelConstants.PREV_DESIRED_CURV_LEN:] = 0. * self.prev_desired_curv_20hz[-4, :] return outputs @@ -173,7 +187,6 @@ def main(demo=False): CP = convert_to_capnp(get_demo_car_params()) else: CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) - cloudlog.info("modeld got CarParams: %s", CP.carName) # TODO this needs more thought, use .2s extra for now to estimate other delays diff --git a/selfdrive/modeld/models/commonmodel.cc b/selfdrive/modeld/models/commonmodel.cc index a188a4ebd3..e8a5a7ed52 100644 --- a/selfdrive/modeld/models/commonmodel.cc +++ b/selfdrive/modeld/models/commonmodel.cc @@ -13,7 +13,10 @@ ModelFrame::ModelFrame(cl_device_id device_id, cl_context context) { y_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_WIDTH * MODEL_HEIGHT, NULL, &err)); u_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); v_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); - net_input_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, frame_size_bytes, NULL, &err)); + img_buffer_20hz_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, 5*frame_size_bytes, NULL, &err)); + region.origin = 4 * frame_size_bytes; + region.size = frame_size_bytes; + last_img_cl = CL_CHECK_ERR(clCreateSubBuffer(img_buffer_20hz_cl, CL_MEM_READ_WRITE, CL_BUFFER_CREATE_TYPE_REGION, ®ion, &err)); transform_init(&transform, context, device_id); loadyuv_init(&loadyuv, context, device_id, MODEL_WIDTH, MODEL_HEIGHT); @@ -24,15 +27,18 @@ uint8_t* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, i yuv_cl, frame_width, frame_height, frame_stride, frame_uv_offset, y_cl, u_cl, v_cl, MODEL_WIDTH, MODEL_HEIGHT, projection); - loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, net_input_cl); + for (int i = 0; i < 4; i++) { + CL_CHECK(clEnqueueCopyBuffer(q, img_buffer_20hz_cl, img_buffer_20hz_cl, (i+1)*frame_size_bytes, i*frame_size_bytes, frame_size_bytes, 0, nullptr, nullptr)); + } + loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, last_img_cl); if (output == NULL) { - std::memmove(&input_frames[0], &input_frames[MODEL_FRAME_SIZE], frame_size_bytes); - CL_CHECK(clEnqueueReadBuffer(q, net_input_cl, CL_TRUE, 0, frame_size_bytes, &input_frames[MODEL_FRAME_SIZE], 0, nullptr, nullptr)); + CL_CHECK(clEnqueueReadBuffer(q, img_buffer_20hz_cl, CL_TRUE, 0, frame_size_bytes, &input_frames[0], 0, nullptr, nullptr)); + CL_CHECK(clEnqueueReadBuffer(q, last_img_cl, CL_TRUE, 0, frame_size_bytes, &input_frames[MODEL_FRAME_SIZE], 0, nullptr, nullptr)); clFinish(q); return &input_frames[0]; } else { - copy_queue(&loadyuv, q, *output, *output, frame_size_bytes, 0, frame_size_bytes); - copy_queue(&loadyuv, q, net_input_cl, *output, 0, frame_size_bytes, frame_size_bytes); + copy_queue(&loadyuv, q, img_buffer_20hz_cl, *output, 0, 0, frame_size_bytes); + copy_queue(&loadyuv, q, last_img_cl, *output, 0, frame_size_bytes, frame_size_bytes); // NOTE: Since thneed is using a different command queue, this clFinish is needed to ensure the image is ready. clFinish(q); @@ -43,7 +49,8 @@ uint8_t* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, i ModelFrame::~ModelFrame() { transform_destroy(&transform); loadyuv_destroy(&loadyuv); - CL_CHECK(clReleaseMemObject(net_input_cl)); + CL_CHECK(clReleaseMemObject(img_buffer_20hz_cl)); + CL_CHECK(clReleaseMemObject(last_img_cl)); CL_CHECK(clReleaseMemObject(v_cl)); CL_CHECK(clReleaseMemObject(u_cl)); CL_CHECK(clReleaseMemObject(y_cl)); diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h index fb527fc7a1..1c7360f159 100644 --- a/selfdrive/modeld/models/commonmodel.h +++ b/selfdrive/modeld/models/commonmodel.h @@ -32,6 +32,7 @@ private: Transform transform; LoadYUVState loadyuv; cl_command_queue q; - cl_mem y_cl, u_cl, v_cl, net_input_cl; + cl_mem y_cl, u_cl, v_cl, img_buffer_20hz_cl, last_img_cl; + cl_buffer_region region; std::unique_ptr input_frames; -}; +}; \ No newline at end of file diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 100fd14c98..49b51c182e 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:21c88ca8a3de59fb11dc3e5888476f6bb627f3647eb0d199680d598e8bf31c0c -size 62486469 +oid sha256:dd55319c8e3e9ac120f2b1bb1131cb67018669dfc0f7ebd31c27cc6de3e9f959 +size 50309976 diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 5fb62db139..f8fd517548 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -56743d36006d4312544ace7f53491727aa7ac302 +05b1cb87e32f280e46e0f45bbd6d76d5fd3f57a7 From 3b6f7c9a6c602c0ceb4907eb9ca4e96c9ba41352 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 1 Oct 2024 13:19:26 -0700 Subject: [PATCH 181/214] sgo shipped! --- RELEASES.md | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index d69d9f8dcc..1435809d84 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,6 +1,10 @@ Version 0.9.8 (2024-XX-XX) ======================== -* New Tomb Raider driving model +* New driving model + * Trained in brand new ML simulator + * Model now gates applying positive accel in Chill mode +* New driving monitoring model + * Reduced false positives related to passengers * Added toggle to enable driver monitoring even when openpilot is not engaged * New Toyota TSS2 longitudinal tune From ba350aac4cb8f996e4c0e22cc77b2b1e99e5ff8c Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Tue, 1 Oct 2024 16:48:19 -0700 Subject: [PATCH 182/214] merge Tesla without a replay route (#33691) * bump opendbc * no Tesla replay route for now * bump opendbc to head --- opendbc_repo | 2 +- selfdrive/test/process_replay/test_processes.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index 6a35629a6b..7b63ff21e9 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 6a35629a6b5f55167ed9d9923411ce9e49e6a76f +Subproject commit 7b63ff21e9652242255b408840d0ebc5a7d0e768 diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 50c34a190f..78090372a6 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -60,7 +60,7 @@ segments = [ ] # dashcamOnly makes don't need to be tested until a full port is done -excluded_interfaces = ["mock"] +excluded_interfaces = ["mock", "tesla"] BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" REF_COMMIT_FN = os.path.join(PROC_REPLAY_DIR, "ref_commit") From 999c86e8a204e8e392c96907756b369790ba66d5 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 1 Oct 2024 17:17:09 -0700 Subject: [PATCH 183/214] Remove VW steer time limit alert (#33692) * rm * remove argument * and more --- selfdrive/car/car_specific.py | 9 +++++---- selfdrive/car/card.py | 2 +- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index 3984b66c63..db46a75ccc 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -1,7 +1,7 @@ from cereal import car import cereal.messaging as messaging from opendbc.car import DT_CTRL, structs -from opendbc.car.interfaces import MAX_CTRL_SPEED, CarStateBase, CarControllerBase +from opendbc.car.interfaces import MAX_CTRL_SPEED, CarStateBase from opendbc.car.volkswagen.values import CarControllerParams as VWCarControllerParams from opendbc.car.hyundai.interface import ENABLE_BUTTONS as HYUNDAI_ENABLE_BUTTONS @@ -37,7 +37,7 @@ class CarSpecificEvents: self.no_steer_warning = False self.silent_steer_warning = True - def update(self, CS: CarStateBase, CS_prev: car.CarState, CC: CarControllerBase, CC_prev: car.CarControl): + def update(self, CS: CarStateBase, CS_prev: car.CarState, CC_prev: car.CarControl): if self.CP.carName in ('body', 'mock'): events = Events() @@ -149,8 +149,9 @@ class CarSpecificEvents: if CC_prev.enabled and CS.out.vEgo < self.CP.minEnableSpeed: events.add(EventName.speedTooLow) - if CC.eps_timer_soft_disable_alert: # type: ignore[attr-defined] - events.add(EventName.steerTimeLimit) + # TODO: this needs to be implemented generically in carState struct + # if CC.eps_timer_soft_disable_alert: # type: ignore[attr-defined] + # events.add(EventName.steerTimeLimit) elif self.CP.carName == 'hyundai': # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 62569f64f5..8829c2e91f 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -187,7 +187,7 @@ class Car: def update_events(self, CS: car.CarState, RD: structs.RadarData | None): self.events.clear() - CS.events = self.car_events.update(self.CI.CS, self.CS_prev, self.CI.CC, self.CC_prev).to_msg() + CS.events = self.car_events.update(self.CI.CS, self.CS_prev, self.CC_prev).to_msg() self.events.add_from_msg(CS.events) From 17edc5f66092bcc79db919eebb7ecb1e3108be10 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Tue, 1 Oct 2024 17:22:46 -0700 Subject: [PATCH 184/214] support for SecOC cars (#33689) * bump opendbc * support for SecOC cars * missed this * bump opendbc * un-nest SecOC params * gate saved key retrieval on IsReleaseBranch false * bump opendbc * bump opendbc * bump opendbc to point of SecOC merge * bump opendbc --- cereal/car.capnp | 4 ++++ common/params.cc | 1 + opendbc_repo | 2 +- selfdrive/car/card.py | 12 ++++++++++++ selfdrive/selfdrived/events.py | 6 ++++++ selfdrive/selfdrived/selfdrived.py | 2 ++ 6 files changed, 26 insertions(+), 1 deletion(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index 6af474c0ee..34f2ac37e3 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -87,6 +87,7 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { startup @75; startupNoCar @76; startupNoControl @77; + startupNoSecOcKey @125; startupMaster @78; fcw @79; steerSaturated @80; @@ -515,6 +516,9 @@ struct CarParams { wheelSpeedFactor @63 :Float32; # Multiplier on wheels speeds to computer actual speeds + secOcRequired @75 :Bool; # Car requires SecOC message authentication to operate + secOcKeyAvailable @76 :Bool; # Stored SecOC key loaded from params + struct SafetyConfig { safetyModel @0 :SafetyModel; safetyParam @3 :UInt16; diff --git a/common/params.cc b/common/params.cc index c75a09e28b..9e62ed582c 100644 --- a/common/params.cc +++ b/common/params.cc @@ -182,6 +182,7 @@ std::unordered_map keys = { {"PrimeType", PERSISTENT}, {"RecordFront", PERSISTENT}, {"RecordFrontLock", PERSISTENT}, // for the internal fleet + {"SecOCKey", PERSISTENT | DONT_LOG}, {"RouteCount", PERSISTENT}, {"SnoozeUpdate", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"SshEnabled", PERSISTENT}, diff --git a/opendbc_repo b/opendbc_repo index 7b63ff21e9..bed4c18a95 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 7b63ff21e9652242255b408840d0ebc5a7d0e768 +Subproject commit bed4c18a959475251e48c28fadfa6bc207f20ec6 diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 8829c2e91f..7f57edf866 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -127,6 +127,18 @@ class Car: safety_config.safetyModel = structs.CarParams.SafetyModel.noOutput self.CP.safetyConfigs = [safety_config] + if self.CP.secOcRequired and not self.params.get_bool("IsReleaseBranch"): + secoc_key = self.params.get("SecOCKey", encoding='utf8') + if secoc_key is not None: + saved_secoc_key = bytes.fromhex(secoc_key.strip()) + if len(saved_secoc_key) == 16: + self.CP.secOcKeyAvailable = True + self.CI.CS.secoc_key = saved_secoc_key + if controller_available: + self.CI.CC.secoc_key = saved_secoc_key + else: + cloudlog.warning("Saved SecOC key is invalid") + # Write previous route's CarParams prev_cp = self.params.get("CarParamsPersistent") if prev_cp is not None: diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index 9ed1b454f0..29b1933701 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -382,6 +382,12 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.PERMANENT: StartupAlert("Dashcam mode for unsupported car"), }, + EventName.startupNoSecOcKey: { + ET.PERMANENT: NormalPermanentAlert("Dashcam Mode", + "Security Key Not Available", + priority=Priority.HIGH), + }, + EventName.dashcamMode: { ET.PERMANENT: NormalPermanentAlert("Dashcam Mode", priority=Priority.LOWEST), diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 18ac61dec8..9e6ac90219 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -118,6 +118,8 @@ class SelfdriveD: self.startup_event = EventName.startupNoCar elif car_recognized and self.CP.passive: self.startup_event = EventName.startupNoControl + elif self.CP.secOcRequired and not self.CP.secOcKeyAvailable: + self.startup_event = EventName.startupNoSecOcKey if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) From 516aa59ee6293e5fcf49dc370520b22ba46bcf8c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 1 Oct 2024 20:16:25 -0700 Subject: [PATCH 185/214] Deprecate lowSpeedLockout alert (#33696) * is an accFault * bump * bump to master * remove from car specific --- cereal/car.capnp | 2 +- opendbc_repo | 2 +- selfdrive/car/car_specific.py | 2 -- selfdrive/selfdrived/events.py | 5 ----- 4 files changed, 2 insertions(+), 9 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index 34f2ac37e3..73f9ca9dc4 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -52,7 +52,6 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { brakeHold @28; parkBrake @29; manualRestart @30; - lowSpeedLockout @31; joystickDebug @34; longitudinalManeuver @124; steerTempUnavailableSilent @35; @@ -150,6 +149,7 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { wideRoadCameraErrorDEPRECATED @102; highCpuUsageDEPRECATED @105; startupNoFwDEPRECATED @104; + lowSpeedLockoutDEPRECATED @31; } } diff --git a/opendbc_repo b/opendbc_repo index bed4c18a95..01f47ff1a3 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit bed4c18a959475251e48c28fadfa6bc207f20ec6 +Subproject commit 01f47ff1a324ade77d99f79c7ea0f4e87110147d diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index db46a75ccc..9602400250 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -99,8 +99,6 @@ class CarSpecificEvents: if self.CP.openpilotLongitudinalControl: if CS.out.cruiseState.standstill and not CS.out.brakePressed: events.add(EventName.resumeRequired) - if CS.low_speed_lockout: # type: ignore[attr-defined] - events.add(EventName.lowSpeedLockout) if CS.out.vEgo < self.CP.minEnableSpeed: events.add(EventName.belowEngageSpeed) if CC_prev.actuators.accel > 0.3: diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index 29b1933701..cb71126627 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -945,11 +945,6 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.NO_ENTRY: NoEntryAlert("Slow down to engage"), }, - EventName.lowSpeedLockout: { - ET.PERMANENT: NormalPermanentAlert("Cruise Fault: Restart the car to engage"), - ET.NO_ENTRY: NoEntryAlert("Cruise Fault: Restart the Car"), - }, - EventName.lkasDisabled: { ET.PERMANENT: NormalPermanentAlert("LKAS Disabled: Enable LKAS to engage"), ET.NO_ENTRY: NoEntryAlert("LKAS Disabled"), From 521c702a1ef87f035e1a36f53bcd823ec57e77ae Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 1 Oct 2024 20:34:21 -0700 Subject: [PATCH 186/214] jenkins: set device time --- Jenkinsfile | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Jenkinsfile b/Jenkinsfile index 799b4fbbeb..84514948c7 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -84,6 +84,8 @@ def deviceStage(String stageName, String deviceType, List extra_env, def steps) docker.image('ghcr.io/commaai/alpine-ssh').inside('--user=root') { timeout(time: 35, unit: 'MINUTES') { retry (3) { + def date = sh(script: 'date', returnStdout: true).trim(); + device(device_ip, "set time", "date -s '" + date + "'") device(device_ip, "git checkout", extra + "\n" + readFile("selfdrive/test/setup_device_ci.sh")) } steps.each { item -> From 9cbd34158f6fa264b86493c1c5bdb2a1bbc0dd4f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 1 Oct 2024 21:17:24 -0700 Subject: [PATCH 187/214] GM: signed wheel speeds (#33697) * signed wheel speeds * clean up * bump to master * bump to master again * did a sanity check for negative vego * bump --- opendbc_repo | 2 +- selfdrive/car/car_specific.py | 5 ++--- selfdrive/controls/controlsd.py | 2 +- selfdrive/selfdrived/selfdrived.py | 2 +- 4 files changed, 5 insertions(+), 6 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index 01f47ff1a3..ea87b4fa3b 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 01f47ff1a324ade77d99f79c7ea0f4e87110147d +Subproject commit ea87b4fa3ba98a71c2c8e93c97788fb0fa960d55 diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index 9602400250..1053588001 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -119,9 +119,8 @@ class CarSpecificEvents: # Enabling at a standstill with brake is allowed # TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs - below_min_enable_speed = CS.out.vEgo < self.CP.minEnableSpeed or CS.moving_backward # type: ignore[attr-defined] - if below_min_enable_speed and not (CS.out.standstill and CS.out.brake >= 20 and - self.CP.networkLocation == NetworkLocation.fwdCamera): + if CS.out.vEgo < self.CP.minEnableSpeed and not (CS.out.standstill and CS.out.brake >= 20 and + self.CP.networkLocation == NetworkLocation.fwdCamera): events.add(EventName.belowEngageSpeed) if CS.out.cruiseState.standstill: events.add(EventName.resumeRequired) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 80331c6ee7..c97a06a0cf 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -87,7 +87,7 @@ class Controls: CC.enabled = self.sm['selfdriveState'].enabled # Check which actuators can be enabled - standstill = CS.vEgo <= max(self.CP.minSteerSpeed, MIN_LATERAL_CONTROL_SPEED) or CS.standstill + standstill = abs(CS.vEgo) <= max(self.CP.minSteerSpeed, MIN_LATERAL_CONTROL_SPEED) or CS.standstill CC.latActive = self.sm['selfdriveState'].active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and not standstill CC.longActive = CC.enabled and not any(e.overrideLongitudinal for e in self.sm['onroadEvents']) and self.CP.openpilotLongitudinalControl diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 9e6ac90219..63e078e6d7 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -334,7 +334,7 @@ class SelfdriveD: self.events.add(EventName.noGps) if gps_ok: self.distance_traveled = 0 - self.distance_traveled += CS.vEgo * DT_CTRL + self.distance_traveled += abs(CS.vEgo) * DT_CTRL if self.sm['modelV2'].frameDropPerc > 20: self.events.add(EventName.modeldLagging) From 48bd5b9f6b0400a09d8af87442ad3616fedc6724 Mon Sep 17 00:00:00 2001 From: YassineYousfi Date: Tue, 1 Oct 2024 21:33:46 -0700 Subject: [PATCH 188/214] modeld: clip vego (#33699) --- selfdrive/modeld/modeld.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index f8a4b7fe0d..ec258f42f0 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -231,7 +231,8 @@ def main(demo=False): desire = DH.desire is_rhd = sm["driverMonitoringState"].isRHD frame_id = sm["roadCameraState"].frameId - lateral_control_params = np.array([sm["carState"].vEgo, steer_delay], dtype=np.float32) + v_ego = max(sm["carState"].vEgo, 0.) + lateral_control_params = np.array([v_ego, steer_delay], dtype=np.float32) if sm.updated["liveCalibration"] and sm.seen['roadCameraState'] and sm.seen['deviceState']: device_from_calib_euler = np.array(sm["liveCalibration"].rpyCalib, dtype=np.float32) dc = DEVICE_CAMERAS[(str(sm['deviceState'].deviceType), str(sm['roadCameraState'].sensor))] From aea6790e3c3d1456305c52213965a6799c42074a Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 1 Oct 2024 21:30:16 -0700 Subject: [PATCH 189/214] ButtonEvent: rename altButton3 to mainCruise --- cereal/car.capnp | 2 +- opendbc_repo | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index 73f9ca9dc4..3ef78973e3 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -281,7 +281,7 @@ struct CarState { cancel @5; altButton1 @6; altButton2 @7; - altButton3 @8; + mainCruise @8; setCruise @9; resumeCruise @10; gapAdjustCruise @11; diff --git a/opendbc_repo b/opendbc_repo index ea87b4fa3b..117ed6de67 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit ea87b4fa3ba98a71c2c8e93c97788fb0fa960d55 +Subproject commit 117ed6de6788c90c097d426e88ac97aaa36d0621 From c19c18cfdb875aa9cf02e3ea813e3385dfab8ff7 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 1 Oct 2024 22:46:24 -0700 Subject: [PATCH 190/214] Hyundai: always publish cruise and main buttons (#33701) * bump * update refs --- opendbc_repo | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index 117ed6de67..2b91038bf7 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 117ed6de6788c90c097d426e88ac97aaa36d0621 +Subproject commit 2b91038bf7f1c2287f1d32c98cd84e45cc0e243e diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index e154284e3d..8e012f79c3 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -d8a02c23f530dd236553b47ff7f0355929fe15fc +2384c1fdb2db449fb6b09f5dc47b3314f4b1cfcf \ No newline at end of file From 98e1d840de3cb8cf801e7b23cafc5fc605550344 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 1 Oct 2024 23:06:57 -0700 Subject: [PATCH 191/214] CarState: add invalidLkasSetting (#33700) * invalidLkasSetting * clean up car specific a bit * clean this up * deprecate! * bump * this was just broken lol * updaterefs --- cereal/car.capnp | 3 ++- opendbc_repo | 2 +- selfdrive/car/car_specific.py | 9 +++------ selfdrive/selfdrived/events.py | 10 +++------- selfdrive/test/process_replay/ref_commit | 2 +- 5 files changed, 10 insertions(+), 16 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index 3ef78973e3..e53f3ce25c 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -103,7 +103,6 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { selfdriveInitializing @98; usbError @99; cruiseMismatch @106; - lkasDisabled @107; canBusMissing @111; selfdrivedLagging @112; resumeBlocked @113; @@ -150,6 +149,7 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { highCpuUsageDEPRECATED @105; startupNoFwDEPRECATED @104; lowSpeedLockoutDEPRECATED @31; + lkasDisabledDEPRECATED @107; } } @@ -199,6 +199,7 @@ struct CarState { steeringPressed @9 :Bool; # if the user is using the steering wheel steerFaultTemporary @35 :Bool; # temporary EPS fault steerFaultPermanent @36 :Bool; # permanent EPS fault + invalidLkasSetting @55 :Bool; # stock LKAS is incorrectly configured (i.e. on or off) stockAeb @30 :Bool; stockFcw @31 :Bool; espDisabled @32 :Bool; diff --git a/opendbc_repo b/opendbc_repo index 2b91038bf7..0cdc684e09 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 2b91038bf7f1c2287f1d32c98cd84e45cc0e243e +Subproject commit 0cdc684e097f386554bbc1a6946a4efe8bc7cfd6 diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index 1053588001..83927a6b04 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -50,15 +50,10 @@ class CarSpecificEvents: elif self.CP.carName == 'nissan': events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.brake]) - if CS.lkas_enabled: # type: ignore[attr-defined] - events.add(EventName.invalidLkasSetting) - elif self.CP.carName == 'mazda': events = self.create_common_events(CS.out, CS_prev) - if CS.lkas_disabled: # type: ignore[attr-defined] - events.add(EventName.lkasDisabled) - elif CS.low_speed_alert: # type: ignore[attr-defined] + if CS.low_speed_alert: # type: ignore[attr-defined] events.add(EventName.belowSteerSpeed) elif self.CP.carName == 'chrysler': @@ -211,6 +206,8 @@ class CarSpecificEvents: events.add(EventName.gasPressedOverride) if CS.vehicleSensorsInvalid: events.add(EventName.vehicleSensorsInvalid) + if CS.invalidLkasSetting: + events.add(EventName.invalidLkasSetting) # Handle button presses for b in CS.buttonEvents: diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index cb71126627..070ca60ca2 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -394,8 +394,9 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { }, EventName.invalidLkasSetting: { - ET.PERMANENT: NormalPermanentAlert("Stock LKAS is on", - "Turn off stock LKAS to engage"), + ET.PERMANENT: NormalPermanentAlert("Invalid LKAS setting", + "Toggle stock LKAS on or off to engage"), + ET.NO_ENTRY: NoEntryAlert("Invalid LKAS setting"), }, EventName.cruiseMismatch: { @@ -945,11 +946,6 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.NO_ENTRY: NoEntryAlert("Slow down to engage"), }, - EventName.lkasDisabled: { - ET.PERMANENT: NormalPermanentAlert("LKAS Disabled: Enable LKAS to engage"), - ET.NO_ENTRY: NoEntryAlert("LKAS Disabled"), - }, - EventName.vehicleSensorsInvalid: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Vehicle Sensors Invalid"), ET.PERMANENT: NormalPermanentAlert("Vehicle Sensors Calibrating", "Drive to Calibrate"), diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 8e012f79c3..30daa6e265 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -2384c1fdb2db449fb6b09f5dc47b3314f4b1cfcf \ No newline at end of file +1b4480f5ebf5a4003dde22f19bbcf989294bc724 \ No newline at end of file From c87f953396d1fe719337132940cab9473a8054b4 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 1 Oct 2024 23:21:33 -0700 Subject: [PATCH 192/214] test_onroad: bump up hevc size --- selfdrive/test/test_onroad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 2f7fa00a32..fc51d7a2cc 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -214,7 +214,7 @@ class TestOnroad: elif f.name == "rlog": assert 5 < sz < 50 elif f.name.endswith('.hevc'): - assert 70 < sz < 77 + assert 70 < sz < 80 else: raise NotImplementedError From af609212f7be5a60c5987b00dd7047e8bfdd5f04 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 2 Oct 2024 10:10:11 -0700 Subject: [PATCH 193/214] bump qcamera too --- selfdrive/test/test_onroad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index fc51d7a2cc..f2afad82ee 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -208,7 +208,7 @@ class TestOnroad: def test_log_sizes(self): for f, sz in self.log_sizes.items(): if f.name == "qcamera.ts": - assert 2.15 < sz < 2.35 + assert 2.15 < sz < 2.6 elif f.name == "qlog": assert 0.4 < sz < 0.55 elif f.name == "rlog": From 7fa8e3d8a65682a00d8ee6d5dba2b58292921dfc Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 3 Oct 2024 01:10:26 +0800 Subject: [PATCH 194/214] sensord: fix redundant assignment (#33707) fix redundant assignment --- system/sensord/sensors/lsm6ds3_gyro.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/sensord/sensors/lsm6ds3_gyro.cc b/system/sensord/sensors/lsm6ds3_gyro.cc index 0459b6ad64..bb560edeab 100644 --- a/system/sensord/sensors/lsm6ds3_gyro.cc +++ b/system/sensord/sensors/lsm6ds3_gyro.cc @@ -110,7 +110,7 @@ int LSM6DS3_Gyro::init() { uint8_t value = 0; bool do_self_test = false; - const char* env_lsm_selftest =env_lsm_selftest = std::getenv("LSM_SELF_TEST"); + const char* env_lsm_selftest = std::getenv("LSM_SELF_TEST"); if (env_lsm_selftest != nullptr && strncmp(env_lsm_selftest, "1", 1) == 0) { do_self_test = true; } From 6aebec7b347a2b40e1bf1c495fe0f1eb360d26fc Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 3 Oct 2024 04:03:46 +0800 Subject: [PATCH 195/214] cleanup .gitignore (#33704) --- .gitignore | 3 --- 1 file changed, 3 deletions(-) diff --git a/.gitignore b/.gitignore index d66823bb50..919e011fe3 100644 --- a/.gitignore +++ b/.gitignore @@ -55,9 +55,6 @@ selfdrive/test/longitudinal_maneuvers/out selfdrive/car/tests/cars_dump system/camerad/camerad system/camerad/test/ae_gray_test -selfdrive/modeld/_modeld -selfdrive/modeld/_dmonitoringmodeld -/src/ notebooks hyperthneed From 06f2ca117915ea7fa6490a6f3c3dac61da25fb19 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 2 Oct 2024 14:38:00 -0700 Subject: [PATCH 196/214] cars: generic interaction detection (#33710) * works * clean up * bump * clean up * it used to consider an action hold down the button, so shouldn't only consider rising edge * bump --- opendbc_repo | 2 +- selfdrive/car/car_specific.py | 8 ++++++-- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index 0cdc684e09..900246ddb3 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 0cdc684e097f386554bbc1a6946a4efe8bc7cfd6 +Subproject commit 900246ddb3ff107f55aab1c8e0d96713a6f4a770 diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index 83927a6b04..b43a4c4fc7 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -1,9 +1,11 @@ +from collections import deque from cereal import car import cereal.messaging as messaging from opendbc.car import DT_CTRL, structs from opendbc.car.interfaces import MAX_CTRL_SPEED, CarStateBase from opendbc.car.volkswagen.values import CarControllerParams as VWCarControllerParams from opendbc.car.hyundai.interface import ENABLE_BUTTONS as HYUNDAI_ENABLE_BUTTONS +from opendbc.car.hyundai.carstate import PREV_BUTTON_SAMPLES as HYUNDAI_PREV_BUTTON_SAMPLES from openpilot.selfdrive.selfdrived.events import Events @@ -37,6 +39,8 @@ class CarSpecificEvents: self.no_steer_warning = False self.silent_steer_warning = True + self.cruise_buttons: deque = deque([], maxlen=HYUNDAI_PREV_BUTTON_SAMPLES) + def update(self, CS: CarStateBase, CS_prev: car.CarState, CC_prev: car.CarControl): if self.CP.carName in ('body', 'mock'): events = Events() @@ -149,8 +153,8 @@ class CarSpecificEvents: # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons # Main button also can trigger an engagement on these cars - allow_enable = any(btn in HYUNDAI_ENABLE_BUTTONS for btn in CS.cruise_buttons) or any(CS.main_buttons) # type: ignore[attr-defined] - events = self.create_common_events(CS.out, CS_prev, pcm_enable=self.CP.pcmCruise, allow_enable=allow_enable) + self.cruise_buttons.append(any(ev.type in HYUNDAI_ENABLE_BUTTONS for ev in CS.out.buttonEvents)) + events = self.create_common_events(CS.out, CS_prev, pcm_enable=self.CP.pcmCruise, allow_enable=any(self.cruise_buttons)) # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) if CS.out.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: From 2b486b15c6718d076ef40098998971a5874abd1b Mon Sep 17 00:00:00 2001 From: YassineYousfi Date: Wed, 2 Oct 2024 14:47:09 -0700 Subject: [PATCH 197/214] MLSIM trained model V1 (#33698) * 87c86ea8-9766-43e9-b72f-185496800301/400 * update ref --- selfdrive/modeld/models/supercombo.onnx | 2 +- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 49b51c182e..89042dbe47 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:dd55319c8e3e9ac120f2b1bb1131cb67018669dfc0f7ebd31c27cc6de3e9f959 +oid sha256:2431f40b8ca9926629e461e06316f9bbba984c821ebbc11e6449ca0c96c42d95 size 50309976 diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index f8fd517548..f14eef06b9 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -05b1cb87e32f280e46e0f45bbd6d76d5fd3f57a7 +c4d60dfe4b677f9230eebb47614501ea8d0b99a3 From 6f0927011cd1ffa94784b42ea5cda72a1ae624d7 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 2 Oct 2024 15:10:33 -0700 Subject: [PATCH 198/214] CarState: add low speed alert field (#33712) * clean up mazda steer speed alert * bump --- cereal/car.capnp | 1 + opendbc_repo | 2 +- selfdrive/car/car_specific.py | 10 +++------- 3 files changed, 5 insertions(+), 8 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index e53f3ce25c..6eff704ecb 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -207,6 +207,7 @@ struct CarState { carFaultedNonCritical @47 :Bool; # some ECU is faulted, but car remains controllable espActive @51 :Bool; vehicleSensorsInvalid @52 :Bool; # invalid steering angle readings, etc. + lowSpeedAlert @56 :Bool; # lost steering control due to a dynamic min steering speed # cruise state cruiseState @10 :CruiseState; diff --git a/opendbc_repo b/opendbc_repo index 900246ddb3..a363ce1ff4 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 900246ddb3ff107f55aab1c8e0d96713a6f4a770 +Subproject commit a363ce1ff452e63f2e49938508d97aece4ba6a3e diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index b43a4c4fc7..ee2dee77de 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -45,7 +45,7 @@ class CarSpecificEvents: if self.CP.carName in ('body', 'mock'): events = Events() - elif self.CP.carName == 'subaru': + elif self.CP.carName in ('subaru', 'mazda'): events = self.create_common_events(CS.out, CS_prev) elif self.CP.carName == 'ford': @@ -54,12 +54,6 @@ class CarSpecificEvents: elif self.CP.carName == 'nissan': events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.brake]) - elif self.CP.carName == 'mazda': - events = self.create_common_events(CS.out, CS_prev) - - if CS.low_speed_alert: # type: ignore[attr-defined] - events.add(EventName.belowSteerSpeed) - elif self.CP.carName == 'chrysler': events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.low]) @@ -212,6 +206,8 @@ class CarSpecificEvents: events.add(EventName.vehicleSensorsInvalid) if CS.invalidLkasSetting: events.add(EventName.invalidLkasSetting) + if CS.lowSpeedAlert: + events.add(EventName.belowSteerSpeed) # Handle button presses for b in CS.buttonEvents: From b2791a8e07fad139f7eb2d46a160f14ac08456a8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Kacper=20R=C4=85czy?= Date: Wed, 2 Oct 2024 20:47:16 -0700 Subject: [PATCH 199/214] process_replay: in-place modification for message migration (#33695) * Inplace modification of lr * Replace the original function * Add comment * Change the return type * Fix carParams retrieval * Remove the newline * Include carState migration * Remove TODO * Comment * List instead of gen * Fix deletion * Delete camera state if not valid * Update ref commit * Remove sorting at the end * Use migrate_all in ui report * Allow more control in what to migrate * Add type annotations * Static analysis * Improve type annot * Fix linter issues * Remove f-string * Migrate carState too in test_ui * Fix peripheralState migration * Sort at the end * Fix regen issue * Fix comments --- selfdrive/test/process_replay/migration.py | 406 +++++++++++---------- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/ui/tests/test_ui/run.py | 4 +- 3 files changed, 217 insertions(+), 195 deletions(-) diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index c0696f2181..9241a3d493 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -1,4 +1,7 @@ from collections import defaultdict +from collections.abc import Callable +import functools +import capnp from cereal import messaging, car from opendbc.car.fingerprints import MIGRATION @@ -7,70 +10,115 @@ from openpilot.selfdrive.modeld.constants import ModelConstants from openpilot.selfdrive.modeld.fill_model_msg import fill_xyz_poly, fill_lane_line_meta from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_encode_index from openpilot.system.manager.process_config import managed_processes +from openpilot.tools.lib.logreader import LogIterable from panda import Panda - -# TODO: message migration should happen in-place -def migrate_all(lr, manager_states=False, panda_states=False, camera_states=False): - msgs = migrate_sensorEvents(lr) - msgs = migrate_carParams(msgs) - msgs = migrate_gpsLocation(msgs) - msgs = migrate_deviceState(msgs) - msgs = migrate_carOutput(msgs) - msgs = migrate_controlsState(msgs) - msgs = migrate_liveLocationKalman(msgs) - msgs = migrate_liveTracks(msgs) - msgs = migrate_driverAssistance(msgs) - msgs = migrate_drivingModelData(msgs) +MessageWithIndex = tuple[int, capnp.lib.capnp._DynamicStructReader] +MigrationOps = tuple[list[tuple[int, capnp.lib.capnp._DynamicStructReader]], list[capnp.lib.capnp._DynamicStructReader], list[int]] +MigrationFunc = Callable[[list[MessageWithIndex]], MigrationOps] + + +## rules for migration functions +## 1. must use the decorator @migration(inputs=[...], product="...") and MigrationFunc signature +## 2. it only gets the messages that are in the inputs list +## 3. product is the message type created by the migration function, and the function will be skipped if product type already exists in lr +## 4. it must return a list of operations to be applied to the logreader (replace, add, delete) +## 5. all migration functions must be independent of each other +def migrate_all(lr: LogIterable, manager_states: bool = False, panda_states: bool = False, camera_states: bool = False): + migrations = [ + migrate_sensorEvents, + migrate_carParams, + migrate_gpsLocation, + migrate_deviceState, + migrate_carOutput, + migrate_controlsState, + migrate_carState, + migrate_liveLocationKalman, + migrate_liveTracks, + migrate_driverAssistance, + migrate_drivingModelData, + ] if manager_states: - msgs = migrate_managerState(msgs) + migrations.append(migrate_managerState) if panda_states: - msgs = migrate_pandaStates(msgs) - msgs = migrate_peripheralState(msgs) + migrations.extend([migrate_pandaStates, migrate_peripheralState]) if camera_states: - msgs = migrate_cameraStates(msgs) - - return msgs - - -def migrate_driverAssistance(lr): - all_msgs = [] - for msg in lr: - all_msgs.append(msg) - if msg.which() == 'longitudinalPlan': - all_msgs.append(messaging.new_message('driverAssistance', valid=True, logMonoTime=msg.logMonoTime).as_reader()) - if msg.which() == 'driverAssistance': - return lr - return all_msgs - - -def migrate_drivingModelData(lr): - all_msgs = [] - for msg in lr: - all_msgs.append(msg) - if msg.which() == "modelV2": - dmd = messaging.new_message('drivingModelData', valid=msg.valid, logMonoTime=msg.logMonoTime) - for field in ["frameId", "frameIdExtra", "frameDropPerc", "modelExecutionTime", "action"]: - setattr(dmd.drivingModelData, field, getattr(msg.modelV2, field)) - for meta_field in ["laneChangeState", "laneChangeState"]: - setattr(dmd.drivingModelData.meta, meta_field, getattr(msg.modelV2.meta, meta_field)) - if len(msg.modelV2.laneLines) and len(msg.modelV2.laneLineProbs): - fill_lane_line_meta(dmd.drivingModelData.laneLineMeta, msg.modelV2.laneLines, msg.modelV2.laneLineProbs) - if all(len(a) for a in [msg.modelV2.position.x, msg.modelV2.position.y, msg.modelV2.position.z]): - fill_xyz_poly(dmd.drivingModelData.path, ModelConstants.POLY_PATH_DEGREE, msg.modelV2.position.x, msg.modelV2.position.y, msg.modelV2.position.z) - all_msgs.append(dmd.as_reader()) - elif msg.which() == "drivingModelData": - return lr - return all_msgs - - -def migrate_liveTracks(lr): - all_msgs = [] - for msg in lr: - if msg.which() != "liveTracksDEPRECATED": - all_msgs.append(msg) + migrations.append(migrate_cameraStates) + + return migrate(lr, migrations) + + +def migrate(lr: LogIterable, migration_funcs: list[MigrationFunc]): + lr = list(lr) + grouped = defaultdict(list) + for i, msg in enumerate(lr): + grouped[msg.which()].append(i) + + replace_ops, add_ops, del_ops = [], [], [] + for migration in migration_funcs: + assert hasattr(migration, "inputs") and hasattr(migration, "product"), "Migration functions must use @migration decorator" + if migration.product in grouped: # skip if product already exists continue + sorted_indices = sorted(ii for i in migration.inputs for ii in grouped[i]) + msg_gen = [(i, lr[i]) for i in sorted_indices] + r_ops, a_ops, d_ops = migration(msg_gen) + replace_ops.extend(r_ops) + add_ops.extend(a_ops) + del_ops.extend(d_ops) + + for index, msg in replace_ops: + lr[index] = msg + for index in sorted(del_ops, reverse=True): + del lr[index] + for msg in add_ops: + lr.append(msg) + lr = sorted(lr, key=lambda x: x.logMonoTime) + + return lr + + +def migration(inputs: list[str], product: str|None=None): + def decorator(func): + @functools.wraps(func) + def wrapper(*args, **kwargs): + return func(*args, **kwargs) + wrapper.inputs = inputs + wrapper.product = product + return wrapper + return decorator + + +@migration(inputs=["longitudinalPlan"], product="driverAssistance") +def migrate_driverAssistance(msgs): + add_ops = [] + for _, msg in msgs: + new_msg = messaging.new_message('driverAssistance', valid=True, logMonoTime=msg.logMonoTime) + add_ops.append(new_msg.as_reader()) + return [], add_ops, [] + + +@migration(inputs=["modelV2"], product="drivingModelData") +def migrate_drivingModelData(msgs): + add_ops = [] + for _, msg in msgs: + dmd = messaging.new_message('drivingModelData', valid=msg.valid, logMonoTime=msg.logMonoTime) + for field in ["frameId", "frameIdExtra", "frameDropPerc", "modelExecutionTime", "action"]: + setattr(dmd.drivingModelData, field, getattr(msg.modelV2, field)) + for meta_field in ["laneChangeState", "laneChangeState"]: + setattr(dmd.drivingModelData.meta, meta_field, getattr(msg.modelV2.meta, meta_field)) + if len(msg.modelV2.laneLines) and len(msg.modelV2.laneLineProbs): + fill_lane_line_meta(dmd.drivingModelData.laneLineMeta, msg.modelV2.laneLines, msg.modelV2.laneLineProbs) + if all(len(a) for a in [msg.modelV2.position.x, msg.modelV2.position.y, msg.modelV2.position.z]): + fill_xyz_poly(dmd.drivingModelData.path, ModelConstants.POLY_PATH_DEGREE, msg.modelV2.position.x, msg.modelV2.position.y, msg.modelV2.position.z) + add_ops.append( dmd.as_reader()) + return [], add_ops, [] + + +@migration(inputs=["liveTracksDEPRECATED"], product="liveTracks") +def migrate_liveTracks(msgs): + ops = [] + for index, msg in msgs: new_msg = messaging.new_message('liveTracks') new_msg.valid = msg.valid new_msg.logMonoTime = msg.logMonoTime @@ -88,22 +136,14 @@ def migrate_liveTracks(lr): pts.append(pt) new_msg.liveTracks.points = pts - all_msgs.append(new_msg.as_reader()) + ops.append((index, new_msg.as_reader())) + return ops, [], [] - return all_msgs - - -def migrate_liveLocationKalman(lr): - # migration needed only for routes before livePose - if any(msg.which() == 'livePose' for msg in lr): - return lr - - all_msgs = [] - for msg in lr: - if msg.which() != 'liveLocationKalmanDEPRECATED': - all_msgs.append(msg) - continue +@migration(inputs=["liveLocationKalmanDEPRECATED"], product="livePose") +def migrate_liveLocationKalman(msgs): + ops = [] + for index, msg in msgs: m = messaging.new_message('livePose') m.valid = msg.valid m.logMonoTime = msg.logMonoTime @@ -114,102 +154,93 @@ def migrate_liveLocationKalman(lr): lp_field.valid = llk_field.valid for flag in ["inputsOK", "posenetOK", "sensorsOK"]: setattr(m.livePose, flag, getattr(msg.liveLocationKalmanDEPRECATED, flag)) + ops.append((index, m.as_reader())) + return ops, [], [] - all_msgs.append(m.as_reader()) - return all_msgs - - -def migrate_controlsState(lr): - ret = [] +@migration(inputs=["controlsState"], product="selfdriveState") +def migrate_controlsState(msgs): + add_ops = [] + for _, msg in msgs: + m = messaging.new_message('selfdriveState') + m.valid = msg.valid + m.logMonoTime = msg.logMonoTime + ss = m.selfdriveState + for field in ("enabled", "active", "state", "engageable", "alertText1", "alertText2", + "alertStatus", "alertSize", "alertType", "experimentalMode", + "personality"): + setattr(ss, field, getattr(msg.controlsState, field+"DEPRECATED")) + add_ops.append(m.as_reader()) + return [], add_ops, [] + + +@migration(inputs=["carState", "controlsState"]) +def migrate_carState(msgs): + ops = [] last_cs = None - for msg in lr: + for index, msg in msgs: if msg.which() == 'controlsState': last_cs = msg - - m = messaging.new_message('selfdriveState') - m.valid = msg.valid - m.logMonoTime = msg.logMonoTime - ss = m.selfdriveState - for field in ("enabled", "active", "state", "engageable", "alertText1", "alertText2", - "alertStatus", "alertSize", "alertType", "experimentalMode", - "personality"): - setattr(ss, field, getattr(msg.controlsState, field+"DEPRECATED")) - ret.append(m.as_reader()) elif msg.which() == 'carState' and last_cs is not None: if last_cs.controlsState.vCruiseDEPRECATED - msg.carState.vCruise > 0.1: msg = msg.as_builder() msg.carState.vCruise = last_cs.controlsState.vCruiseDEPRECATED msg.carState.vCruiseCluster = last_cs.controlsState.vCruiseClusterDEPRECATED - msg = msg.as_reader() + ops.append((index, msg.as_reader())) + return ops, [], [] - ret.append(msg) - return ret - - -def migrate_managerState(lr): - all_msgs = [] - for msg in lr: - if msg.which() != "managerState": - all_msgs.append(msg) - continue +@migration(inputs=["managerState"]) +def migrate_managerState(msgs): + ops = [] + for index, msg in msgs: new_msg = msg.as_builder() new_msg.managerState.processes = [{'name': name, 'running': True} for name in managed_processes] - all_msgs.append(new_msg.as_reader()) - - return all_msgs + ops.append((index, new_msg.as_reader())) + return ops, [], [] -def migrate_gpsLocation(lr): - all_msgs = [] - for msg in lr: - if msg.which() in ('gpsLocation', 'gpsLocationExternal'): - new_msg = msg.as_builder() - g = getattr(new_msg, new_msg.which()) - # hasFix is a newer field - if not g.hasFix and g.flags == 1: - g.hasFix = True - all_msgs.append(new_msg.as_reader()) - else: - all_msgs.append(msg) - return all_msgs +@migration(inputs=["gpsLocation", "gpsLocationExternal"]) +def migrate_gpsLocation(msgs): + ops = [] + for index, msg in msgs: + new_msg = msg.as_builder() + g = getattr(new_msg, new_msg.which()) + # hasFix is a newer field + if not g.hasFix and g.flags == 1: + g.hasFix = True + ops.append((index, new_msg.as_reader())) + return ops, [], [] -def migrate_deviceState(lr): - all_msgs = [] +@migration(inputs=["deviceState", "initData"]) +def migrate_deviceState(msgs): + ops = [] dt = None - for msg in lr: + for i, msg in msgs: if msg.which() == 'initData': dt = msg.initData.deviceType if msg.which() == 'deviceState': n = msg.as_builder() n.deviceState.deviceType = dt - all_msgs.append(n.as_reader()) - else: - all_msgs.append(msg) - return all_msgs + ops.append((i, n.as_reader())) + return ops, [], [] -def migrate_carOutput(lr): - # migration needed only for routes before carOutput - if any(msg.which() == 'carOutput' for msg in lr): - return lr +@migration(inputs=["carControl"], product="carOutput") +def migrate_carOutput(msgs): + add_ops = [] + for _, msg in msgs: + co = messaging.new_message('carOutput') + co.valid = msg.valid + co.logMonoTime = msg.logMonoTime + co.carOutput.actuatorsOutput = msg.carControl.actuatorsOutputDEPRECATED + add_ops.append(co.as_reader()) + return [], add_ops, [] - all_msgs = [] - for msg in lr: - if msg.which() == 'carControl': - co = messaging.new_message('carOutput') - co.valid = msg.valid - co.logMonoTime = msg.logMonoTime - co.carOutput.actuatorsOutput = msg.carControl.actuatorsOutputDEPRECATED - all_msgs.append(co.as_reader()) - all_msgs.append(msg) - return all_msgs - -def migrate_pandaStates(lr): - all_msgs = [] +@migration(inputs=["pandaStates", "pandaStateDEPRECATED", "carParams"]) +def migrate_pandaStates(msgs): # TODO: safety param migration should be handled automatically safety_param_migration = { "TOYOTA_PRIUS": EPS_SCALE["TOYOTA_PRIUS"] | Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL, @@ -217,11 +248,12 @@ def migrate_pandaStates(lr): "KIA_EV6": Panda.FLAG_HYUNDAI_EV_GAS | Panda.FLAG_HYUNDAI_CANFD_HDA2, } - # Migrate safety param base on carState - CP = next((m.carParams for m in lr if m.which() == 'carParams'), None) + # Migrate safety param base on carParams + CP = next((m.carParams for _, m in msgs if m.which() == 'carParams'), None) assert CP is not None, "carParams message not found" - if CP.carFingerprint in safety_param_migration: - safety_param = safety_param_migration[CP.carFingerprint] + fingerprint = MIGRATION.get(CP.carFingerprint, CP.carFingerprint) + if fingerprint in safety_param_migration: + safety_param = safety_param_migration[fingerprint] elif len(CP.safetyConfigs): safety_param = CP.safetyConfigs[0].safetyParam if CP.safetyConfigs[0].safetyParamDEPRECATED != 0: @@ -229,49 +261,45 @@ def migrate_pandaStates(lr): else: safety_param = CP.safetyParamDEPRECATED - for msg in lr: + ops = [] + for index, msg in msgs: if msg.which() == 'pandaStateDEPRECATED': new_msg = messaging.new_message('pandaStates', 1) new_msg.valid = msg.valid new_msg.logMonoTime = msg.logMonoTime new_msg.pandaStates[0] = msg.pandaStateDEPRECATED new_msg.pandaStates[0].safetyParam = safety_param - all_msgs.append(new_msg.as_reader()) + ops.append((index, new_msg.as_reader())) elif msg.which() == 'pandaStates': new_msg = msg.as_builder() new_msg.pandaStates[-1].safetyParam = safety_param - all_msgs.append(new_msg.as_reader()) - else: - all_msgs.append(msg) + ops.append((index, new_msg.as_reader())) + return ops, [], [] - return all_msgs +@migration(inputs=["pandaStates", "pandaStateDEPRECATED"], product="peripheralState") +def migrate_peripheralState(msgs): + add_ops = [] -def migrate_peripheralState(lr): - if any(msg.which() == "peripheralState" for msg in lr): - return lr - - all_msg = [] - for msg in lr: - all_msg.append(msg) - if msg.which() not in ["pandaStates", "pandaStateDEPRECATED"]: + which = "pandaStates" if any(msg.which() == "pandaStates" for _, msg in msgs) else "pandaStateDEPRECATED" + for _, msg in msgs: + if msg.which() != which: continue - new_msg = messaging.new_message("peripheralState") new_msg.valid = msg.valid new_msg.logMonoTime = msg.logMonoTime - all_msg.append(new_msg.as_reader()) + add_ops.append(new_msg.as_reader()) + return [], add_ops, [] - return all_msg - -def migrate_cameraStates(lr): - all_msgs = [] +@migration(inputs=["roadEncodeIdx", "wideRoadEncodeIdx", "driverEncodeIdx", "roadCameraState", "wideRoadCameraState", "driverCameraState"]) +def migrate_cameraStates(msgs): + add_ops, del_ops = [], [] frame_to_encode_id = defaultdict(dict) # just for encodeId fallback mechanism min_frame_id = defaultdict(lambda: float('inf')) - for msg in lr: + for _, msg in msgs: if msg.which() not in ["roadEncodeIdx", "wideRoadEncodeIdx", "driverEncodeIdx"]: continue @@ -281,9 +309,8 @@ def migrate_cameraStates(lr): assert encode_index.segmentId < 1200, f"Encoder index segmentId greater that 1200: {msg.which()} {encode_index.segmentId}" frame_to_encode_id[meta.camera_state][encode_index.frameId] = encode_index.segmentId - for msg in lr: + for index, msg in msgs: if msg.which() not in ["roadCameraState", "wideRoadCameraState", "driverCameraState"]: - all_msgs.append(msg) continue camera_state = getattr(msg, msg.which()) @@ -293,6 +320,7 @@ def migrate_cameraStates(lr): if encode_id is None: print(f"Missing encoded frame for camera feed {msg.which()} with frameId: {camera_state.frameId}") if len(frame_to_encode_id[msg.which()]) != 0: + del_ops.append(index) continue # fallback mechanism for logs without encodeIdx (e.g. logs from before 2022 with dcamera recording disabled) @@ -313,33 +341,27 @@ def migrate_cameraStates(lr): new_msg.logMonoTime = msg.logMonoTime new_msg.valid = msg.valid - all_msgs.append(new_msg.as_reader()) - - return all_msgs + del_ops.append(index) + add_ops.append(new_msg.as_reader()) + return [], add_ops, del_ops -def migrate_carParams(lr): - all_msgs = [] - for msg in lr: - if msg.which() == 'carParams': - CP = msg.as_builder() - CP.carParams.carFingerprint = MIGRATION.get(CP.carParams.carFingerprint, CP.carParams.carFingerprint) - for car_fw in CP.carParams.carFw: - car_fw.brand = CP.carParams.carName - CP.logMonoTime = msg.logMonoTime - msg = CP.as_reader() - all_msgs.append(msg) +@migration(inputs=["carParams"]) +def migrate_carParams(msgs): + ops = [] + for index, msg in msgs: + CP = msg.as_builder() + CP.carParams.carFingerprint = MIGRATION.get(CP.carParams.carFingerprint, CP.carParams.carFingerprint) + for car_fw in CP.carParams.carFw: + car_fw.brand = CP.carParams.carName + ops.append((index, CP.as_reader())) + return ops, [], [] - return all_msgs - - -def migrate_sensorEvents(lr): - all_msgs = [] - for msg in lr: - if msg.which() != 'sensorEventsDEPRECATED': - all_msgs.append(msg) - continue +@migration(inputs=["sensorEventsDEPRECATED"], product="sensorEvents") +def migrate_sensorEvents(msgs): + add_ops, del_ops = [], [] + for index, msg in msgs: # migrate to split sensor events for evt in msg.sensorEventsDEPRECATED: # build new message for each sensor type @@ -367,6 +389,6 @@ def migrate_sensorEvents(lr): m_dat.timestamp = evt.timestamp setattr(m_dat, evt.which(), getattr(evt, evt.which())) - all_msgs.append(m.as_reader()) - - return all_msgs + add_ops.append(m.as_reader()) + del_ops.append(index) + return [], add_ops, del_ops diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 30daa6e265..32609b0a8f 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -1b4480f5ebf5a4003dde22f19bbcf989294bc724 \ No newline at end of file +f9f1fd736c6bbef3aa2d3aea8e4f8e1c892234de \ No newline at end of file diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 8c9db5a3f3..a918a57364 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -19,7 +19,7 @@ from openpilot.common.prefix import OpenpilotPrefix from openpilot.common.transformations.camera import CameraConfig, DEVICE_CAMERAS from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.selfdrive.test.helpers import with_processes -from openpilot.selfdrive.test.process_replay.migration import migrate_controlsState +from openpilot.selfdrive.test.process_replay.migration import migrate, migrate_controlsState, migrate_carState from openpilot.tools.lib.logreader import LogReader from openpilot.tools.lib.framereader import FrameReader from openpilot.tools.lib.route import Route @@ -263,7 +263,7 @@ def create_screenshots(): segnum = 2 lr = LogReader(route.qlog_paths()[segnum]) DATA['carParams'] = next((event.as_builder() for event in lr if event.which() == 'carParams'), None) - for event in migrate_controlsState(lr): + for event in migrate(lr, [migrate_controlsState, migrate_carState]): if event.which() in DATA: DATA[event.which()] = event.as_builder() From 3ca158ad3e820488c507006c960226d4db2e53cf Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 3 Oct 2024 12:14:37 +0800 Subject: [PATCH 200/214] camerad: remove Hardware::PC() check (#33713) remove check for hardware::PC --- system/camerad/main.cc | 6 ------ 1 file changed, 6 deletions(-) diff --git a/system/camerad/main.cc b/system/camerad/main.cc index b86b4f57ff..d55bd495ad 100644 --- a/system/camerad/main.cc +++ b/system/camerad/main.cc @@ -4,14 +4,8 @@ #include "common/params.h" #include "common/util.h" -#include "system/hardware/hw.h" int main(int argc, char *argv[]) { - if (Hardware::PC()) { - printf("exiting, camerad is not meant to run on PC\n"); - return 0; - } - int ret = util::set_realtime_priority(53); assert(ret == 0); ret = util::set_core_affinity({6}); From aed1eaede5a8035a3b882096acf461cdd962b68c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 2 Oct 2024 21:32:56 -0700 Subject: [PATCH 201/214] Deprecate carState.events (#33693) * add lkas bools * switch these two over * bump * deprecate low speed lockout * add lowSpeedAlert bool bump * GM vehicle speed is now signed! * reimagine * rm * do event * bump * STASH * comment * bump * no out! * format * move almost everything to selfdrived * add back CC_prev for cruise initialization * ok * errors are passed to radarState as well as freq check * deprecate! * use selfdrived for test models events * we only want noEntry from car events, not system, have to check pedalPressed * no more events * regen with buttonEvents set properly * update refs --- cereal/car.capnp | 3 +- selfdrive/car/car_specific.py | 70 +++++++++---------- selfdrive/car/card.py | 38 ++-------- selfdrive/car/tests/test_models.py | 15 ++-- selfdrive/selfdrived/selfdrived.py | 31 ++++++-- selfdrive/test/process_replay/README.md | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- .../test/process_replay/test_processes.py | 4 +- 8 files changed, 79 insertions(+), 86 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index 6eff704ecb..326f1eeef8 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -157,8 +157,6 @@ struct OnroadEvent @0x9b1657f34caf3ad3 { # all speeds in m/s struct CarState { - events @13 :List(OnroadEvent); - # CAN health canValid @26 :Bool; # invalid counter/checksums canTimeout @40 :Bool; # CAN bus dropped out @@ -296,6 +294,7 @@ struct CarState { steeringRateLimitedDEPRECATED @29 :Bool; canMonoTimesDEPRECATED @12: List(UInt64); canRcvTimeoutDEPRECATED @49 :Bool; + eventsDEPRECATED @13 :List(OnroadEvent); } # ******* radar state @ 20hz ******* diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index ee2dee77de..23719a8c4f 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -2,7 +2,7 @@ from collections import deque from cereal import car import cereal.messaging as messaging from opendbc.car import DT_CTRL, structs -from opendbc.car.interfaces import MAX_CTRL_SPEED, CarStateBase +from opendbc.car.interfaces import MAX_CTRL_SPEED from opendbc.car.volkswagen.values import CarControllerParams as VWCarControllerParams from opendbc.car.hyundai.interface import ENABLE_BUTTONS as HYUNDAI_ENABLE_BUTTONS from opendbc.car.hyundai.carstate import PREV_BUTTON_SAMPLES as HYUNDAI_PREV_BUTTON_SAMPLES @@ -41,102 +41,102 @@ class CarSpecificEvents: self.cruise_buttons: deque = deque([], maxlen=HYUNDAI_PREV_BUTTON_SAMPLES) - def update(self, CS: CarStateBase, CS_prev: car.CarState, CC_prev: car.CarControl): + def update(self, CS: car.CarState, CS_prev: car.CarState, CC: car.CarControl): if self.CP.carName in ('body', 'mock'): events = Events() elif self.CP.carName in ('subaru', 'mazda'): - events = self.create_common_events(CS.out, CS_prev) + events = self.create_common_events(CS, CS_prev) elif self.CP.carName == 'ford': - events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.manumatic]) + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.manumatic]) elif self.CP.carName == 'nissan': - events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.brake]) + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.brake]) elif self.CP.carName == 'chrysler': - events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.low]) + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.low]) # Low speed steer alert hysteresis logic - if self.CP.minSteerSpeed > 0. and CS.out.vEgo < (self.CP.minSteerSpeed + 0.5): + if self.CP.minSteerSpeed > 0. and CS.vEgo < (self.CP.minSteerSpeed + 0.5): self.low_speed_alert = True - elif CS.out.vEgo > (self.CP.minSteerSpeed + 1.): + elif CS.vEgo > (self.CP.minSteerSpeed + 1.): self.low_speed_alert = False if self.low_speed_alert: events.add(EventName.belowSteerSpeed) elif self.CP.carName == 'honda': - events = self.create_common_events(CS.out, CS_prev, pcm_enable=False) + events = self.create_common_events(CS, CS_prev, pcm_enable=False) - if self.CP.pcmCruise and CS.out.vEgo < self.CP.minEnableSpeed: + if self.CP.pcmCruise and CS.vEgo < self.CP.minEnableSpeed: events.add(EventName.belowEngageSpeed) if self.CP.pcmCruise: # we engage when pcm is active (rising edge) - if CS.out.cruiseState.enabled and not CS_prev.cruiseState.enabled: + if CS.cruiseState.enabled and not CS_prev.cruiseState.enabled: events.add(EventName.pcmEnable) - elif not CS.out.cruiseState.enabled and (CC_prev.actuators.accel >= 0. or not self.CP.openpilotLongitudinalControl): + elif not CS.cruiseState.enabled and (CC.actuators.accel >= 0. or not self.CP.openpilotLongitudinalControl): # it can happen that car cruise disables while comma system is enabled: need to # keep braking if needed or if the speed is very low - if CS.out.vEgo < self.CP.minEnableSpeed + 2.: + if CS.vEgo < self.CP.minEnableSpeed + 2.: # non loud alert if cruise disables below 25mph as expected (+ a little margin) events.add(EventName.speedTooLow) else: events.add(EventName.cruiseDisabled) - if self.CP.minEnableSpeed > 0 and CS.out.vEgo < 0.001: + if self.CP.minEnableSpeed > 0 and CS.vEgo < 0.001: events.add(EventName.manualRestart) elif self.CP.carName == 'toyota': - events = self.create_common_events(CS.out, CS_prev) + events = self.create_common_events(CS, CS_prev) if self.CP.openpilotLongitudinalControl: - if CS.out.cruiseState.standstill and not CS.out.brakePressed: + if CS.cruiseState.standstill and not CS.brakePressed: events.add(EventName.resumeRequired) - if CS.out.vEgo < self.CP.minEnableSpeed: + if CS.vEgo < self.CP.minEnableSpeed: events.add(EventName.belowEngageSpeed) - if CC_prev.actuators.accel > 0.3: + if CC.actuators.accel > 0.3: # some margin on the actuator to not false trigger cancellation while stopping events.add(EventName.speedTooLow) - if CS.out.vEgo < 0.001: + if CS.vEgo < 0.001: # while in standstill, send a user alert events.add(EventName.manualRestart) elif self.CP.carName == 'gm': # The ECM allows enabling on falling edge of set, but only rising edge of resume - events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.sport, GearShifter.low, - GearShifter.eco, GearShifter.manumatic], + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.sport, GearShifter.low, + GearShifter.eco, GearShifter.manumatic], pcm_enable=self.CP.pcmCruise, enable_buttons=(ButtonType.decelCruise,)) if not self.CP.pcmCruise: - if any(b.type == ButtonType.accelCruise and b.pressed for b in CS.out.buttonEvents): + if any(b.type == ButtonType.accelCruise and b.pressed for b in CS.buttonEvents): events.add(EventName.buttonEnable) # Enabling at a standstill with brake is allowed # TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs - if CS.out.vEgo < self.CP.minEnableSpeed and not (CS.out.standstill and CS.out.brake >= 20 and - self.CP.networkLocation == NetworkLocation.fwdCamera): + if CS.vEgo < self.CP.minEnableSpeed and not (CS.standstill and CS.brake >= 20 and + self.CP.networkLocation == NetworkLocation.fwdCamera): events.add(EventName.belowEngageSpeed) - if CS.out.cruiseState.standstill: + if CS.cruiseState.standstill: events.add(EventName.resumeRequired) - if CS.out.vEgo < self.CP.minSteerSpeed: + if CS.vEgo < self.CP.minSteerSpeed: events.add(EventName.belowSteerSpeed) elif self.CP.carName == 'volkswagen': - events = self.create_common_events(CS.out, CS_prev, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic], + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic], pcm_enable=not self.CP.openpilotLongitudinalControl, enable_buttons=(ButtonType.setCruise, ButtonType.resumeCruise)) # Low speed steer alert hysteresis logic - if (self.CP.minSteerSpeed - 1e-3) > VWCarControllerParams.DEFAULT_MIN_STEER_SPEED and CS.out.vEgo < (self.CP.minSteerSpeed + 1.): + if (self.CP.minSteerSpeed - 1e-3) > VWCarControllerParams.DEFAULT_MIN_STEER_SPEED and CS.vEgo < (self.CP.minSteerSpeed + 1.): self.low_speed_alert = True - elif CS.out.vEgo > (self.CP.minSteerSpeed + 2.): + elif CS.vEgo > (self.CP.minSteerSpeed + 2.): self.low_speed_alert = False if self.low_speed_alert: events.add(EventName.belowSteerSpeed) if self.CP.openpilotLongitudinalControl: - if CS.out.vEgo < self.CP.minEnableSpeed + 0.5: + if CS.vEgo < self.CP.minEnableSpeed + 0.5: events.add(EventName.belowEngageSpeed) - if CC_prev.enabled and CS.out.vEgo < self.CP.minEnableSpeed: + if CC.enabled and CS.vEgo < self.CP.minEnableSpeed: events.add(EventName.speedTooLow) # TODO: this needs to be implemented generically in carState struct @@ -147,13 +147,13 @@ class CarSpecificEvents: # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons # Main button also can trigger an engagement on these cars - self.cruise_buttons.append(any(ev.type in HYUNDAI_ENABLE_BUTTONS for ev in CS.out.buttonEvents)) - events = self.create_common_events(CS.out, CS_prev, pcm_enable=self.CP.pcmCruise, allow_enable=any(self.cruise_buttons)) + self.cruise_buttons.append(any(ev.type in HYUNDAI_ENABLE_BUTTONS for ev in CS.buttonEvents)) + events = self.create_common_events(CS, CS_prev, pcm_enable=self.CP.pcmCruise, allow_enable=any(self.cruise_buttons)) # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) - if CS.out.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: + if CS.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: self.low_speed_alert = True - if CS.out.vEgo > (self.CP.minSteerSpeed + 4.): + if CS.vEgo > (self.CP.minSteerSpeed + 4.): self.low_speed_alert = False if self.low_speed_alert: events.add(EventName.belowSteerSpeed) diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 7f57edf866..380d5df431 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -20,9 +20,8 @@ from opendbc.car.car_helpers import get_car, get_radar_interface from opendbc.car.interfaces import CarInterfaceBase, RadarInterfaceBase from openpilot.selfdrive.pandad import can_capnp_to_list, can_list_to_can_capnp from openpilot.selfdrive.car.cruise import VCruiseHelper -from openpilot.selfdrive.car.car_specific import CarSpecificEvents, MockCarState +from openpilot.selfdrive.car.car_specific import MockCarState from openpilot.selfdrive.car.helpers import convert_carControl, convert_to_capnp -from openpilot.selfdrive.selfdrived.events import Events, ET REPLAY = "REPLAY" in os.environ @@ -112,9 +111,9 @@ class Car: self.RI = RI # set alternative experiences from parameters - self.disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") + disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") self.CP.alternativeExperience = 0 - if not self.disengage_on_accelerator: + if not disengage_on_accelerator: self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS openpilot_enabled_toggle = self.params.get_bool("OpenpilotEnabledToggle") @@ -152,9 +151,6 @@ class Car: self.params.put_nonblocking("CarParamsCache", cp_bytes) self.params.put_nonblocking("CarParamsPersistent", cp_bytes) - self.events = Events() - - self.car_events = CarSpecificEvents(self.CP) self.mock_carstate = MockCarState() self.v_cruise_helper = VCruiseHelper(self.CP) @@ -196,30 +192,6 @@ class Car: return CS, RD - def update_events(self, CS: car.CarState, RD: structs.RadarData | None): - self.events.clear() - - CS.events = self.car_events.update(self.CI.CS, self.CS_prev, self.CC_prev).to_msg() - - self.events.add_from_msg(CS.events) - - if self.CP.notCar: - # wait for everything to init first - if self.sm.frame > int(5. / DT_CTRL) and self.initialized_prev: - # body always wants to enable - self.events.add(EventName.pcmEnable) - - # Disable on rising edge of accelerator or brake. Also disable on brake when speed > 0 - if (CS.gasPressed and not self.CS_prev.gasPressed and self.disengage_on_accelerator) or \ - (CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)) or \ - (CS.regenBraking and (not self.CS_prev.regenBraking or not CS.standstill)): - self.events.add(EventName.pedalPressed) - - if RD is not None and len(RD.errors): - self.events.add(EventName.radarFault) - - CS.events = self.events.to_msg() - def state_publish(self, CS: car.CarState, RD: structs.RadarData | None): """carState and carParams publish loop""" @@ -271,9 +243,7 @@ class Car: def step(self): CS, RD = self.state_update() - self.update_events(CS, RD) - - if not self.sm['carControl'].enabled and self.events.contains(ET.ENABLE): + if self.sm['carControl'].enabled and not self.CC_prev.enabled: self.v_cruise_helper.initialize_v_cruise(CS, self.experimental_mode) self.state_publish(CS, RD) diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 460b9f196d..10620c146f 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -20,7 +20,9 @@ from opendbc.car.car_helpers import FRAME_FINGERPRINT, interfaces from opendbc.car.honda.values import CAR as HONDA, HondaFlags from opendbc.car.values import Platform from opendbc.car.tests.routes import non_tested_cars, routes, CarTestRoute -from openpilot.selfdrive.car.card import Car, convert_to_capnp +from openpilot.selfdrive.car.card import convert_to_capnp +from openpilot.selfdrive.selfdrived.events import ET +from openpilot.selfdrive.selfdrived.selfdrived import SelfdriveD from openpilot.selfdrive.pandad import can_capnp_to_list from openpilot.selfdrive.test.helpers import read_segment_list from openpilot.system.hardware.hw import DEFAULT_DOWNLOAD_CACHE_ROOT @@ -404,7 +406,8 @@ class TestCarModelBase(unittest.TestCase): controls_allowed_prev = False CS_prev = car.CarState.new_message() checks = defaultdict(int) - card = Car(CI=self.CI) + selfdrived = SelfdriveD(CP=self.CP) + selfdrived.initialized = True for idx, can in enumerate(self.can_msgs): CS = convert_to_capnp(self.CI.update(can_capnp_to_list((can.as_builder().to_bytes(), )))) for msg in filter(lambda m: m.src in range(64), can.can): @@ -449,10 +452,10 @@ class TestCarModelBase(unittest.TestCase): checks['cruiseState'] += CS.cruiseState.enabled != self.safety.get_cruise_engaged_prev() else: # Check for enable events on rising edge of controls allowed - card.update_events(CS, None) - card.CS_prev = CS - button_enable = (any(evt.enable for evt in CS.events) and - not any(evt == EventName.pedalPressed for evt in card.events.names)) + selfdrived.update_events(CS) + selfdrived.CS_prev = CS + button_enable = (selfdrived.events.contains(ET.ENABLE) and + EventName.pedalPressed not in selfdrived.events.names) mismatch = button_enable != (self.safety.get_controls_allowed() and not controls_allowed_prev) checks['controlsAllowed'] += mismatch controls_allowed_prev = self.safety.get_controls_allowed() diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 63e078e6d7..160117faa8 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -7,6 +7,7 @@ import cereal.messaging as messaging from cereal import car, log from msgq.visionipc import VisionIpcClient, VisionStreamType +from panda import ALTERNATIVE_EXPERIENCE from openpilot.common.params import Params @@ -14,6 +15,7 @@ from openpilot.common.realtime import config_realtime_process, Priority, Ratekee from openpilot.common.swaglog import cloudlog from openpilot.common.gps import get_gps_location_service +from openpilot.selfdrive.car.car_specific import CarSpecificEvents from openpilot.selfdrive.selfdrived.events import Events, ET from openpilot.selfdrive.selfdrived.state import StateMachine from openpilot.selfdrive.selfdrived.alertmanager import AlertManager, set_offroad_alert @@ -41,15 +43,21 @@ IGNORED_SAFETY_MODES = (SafetyModel.silent, SafetyModel.noOutput) class SelfdriveD: - def __init__(self): + def __init__(self, CP=None): self.params = Params() # Ensure the current branch is cached, otherwise the first cycle lags build_metadata = get_build_metadata() - cloudlog.info("selfdrived is waiting for CarParams") - self.CP = messaging.log_from_bytes(self.params.get("CarParams", block=True), car.CarParams) - cloudlog.info("selfdrived got CarParams") + if CP is None: + cloudlog.info("selfdrived is waiting for CarParams") + self.CP = messaging.log_from_bytes(self.params.get("CarParams", block=True), car.CarParams) + cloudlog.info("selfdrived got CarParams") + else: + self.CP = CP + + self.car_events = CarSpecificEvents(self.CP) + self.disengage_on_accelerator = not (self.CP.alternativeExperience & ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS) # Setup sockets self.pm = messaging.PubMaster(['selfdriveState', 'onroadEvents']) @@ -166,7 +174,20 @@ class SelfdriveD: # Add car events, ignore if CAN isn't valid if CS.canValid: - self.events.add_from_msg(CS.events) + car_events = self.car_events.update(CS, self.CS_prev, self.sm['carControl']).to_msg() + self.events.add_from_msg(car_events) + + if self.CP.notCar: + # wait for everything to init first + if self.sm.frame > int(5. / DT_CTRL) and self.initialized: + # body always wants to enable + self.events.add(EventName.pcmEnable) + + # Disable on rising edge of accelerator or brake. Also disable on brake when speed > 0 + if (CS.gasPressed and not self.CS_prev.gasPressed and self.disengage_on_accelerator) or \ + (CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)) or \ + (CS.regenBraking and (not self.CS_prev.regenBraking or not CS.standstill)): + self.events.add(EventName.pedalPressed) # Create events for temperature, disk space, and memory if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: diff --git a/selfdrive/test/process_replay/README.md b/selfdrive/test/process_replay/README.md index 008a901010..381e4dcb7f 100644 --- a/selfdrive/test/process_replay/README.md +++ b/selfdrive/test/process_replay/README.md @@ -30,7 +30,7 @@ optional arguments: --whitelist-cars WHITELIST_CARS Whitelist given cars from the test (e.g. HONDA) --blacklist-procs BLACKLIST_PROCS Blacklist given processes from the test (e.g. controlsd) --blacklist-cars BLACKLIST_CARS Blacklist given cars from the test (e.g. HONDA) - --ignore-fields IGNORE_FIELDS Extra fields or msgs to ignore (e.g. carState.events) + --ignore-fields IGNORE_FIELDS Extra fields or msgs to ignore (e.g. driverMonitoringState.events) --ignore-msgs IGNORE_MSGS Msgs to ignore (e.g. onroadEvents) --update-refs Updates reference logs using current commit --upload-only Skips testing processes and uploads logs from previous test run diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 32609b0a8f..9aa61ab9c4 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -f9f1fd736c6bbef3aa2d3aea8e4f8e1c892234de \ No newline at end of file +fbf16d1e9b056830a12fcf29a5137e1fc0b01354 \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 78090372a6..ec84f37d1f 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -42,7 +42,7 @@ source_segments = [ segments = [ ("BODY", "regenA67A128BCD8|2024-08-30--02-36-22--0"), ("HYUNDAI", "regen9CBD921E93E|2024-08-30--02-38-51--0"), - ("HYUNDAI2", "regen12E0C4EA1A7|2024-08-30--02-42-40--0"), + ("HYUNDAI2", "regen306779F6870|2024-10-03--04-03-23--0"), ("TOYOTA", "regen1CA7A48E6F7|2024-08-30--02-45-08--0"), ("TOYOTA2", "regen6E484EDAB96|2024-08-30--02-47-37--0"), ("TOYOTA3", "regen4CE950B0267|2024-08-30--02-51-30--0"), @@ -135,7 +135,7 @@ if __name__ == "__main__": parser.add_argument("--blacklist-cars", type=str, nargs="*", default=[], help="Blacklist given cars from the test (e.g. HONDA)") parser.add_argument("--ignore-fields", type=str, nargs="*", default=[], - help="Extra fields or msgs to ignore (e.g. carState.events)") + help="Extra fields or msgs to ignore (e.g. driverMonitoringState.events)") parser.add_argument("--ignore-msgs", type=str, nargs="*", default=[], help="Msgs to ignore (e.g. carEvents)") parser.add_argument("--update-refs", action="store_true", From 6baa541501739775de0fb6e5956606cad8ba1227 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 4 Oct 2024 01:46:05 +0800 Subject: [PATCH 202/214] ui: refactor model updating and rendering into ModelRenderer class (#33702) refactor model update Co-authored-by: Maxime Desroches --- selfdrive/ui/SConscript | 2 +- selfdrive/ui/qt/onroad/annotated_camera.cc | 120 +----------- selfdrive/ui/qt/onroad/annotated_camera.h | 5 +- selfdrive/ui/qt/onroad/model.cc | 208 +++++++++++++++++++++ selfdrive/ui/qt/onroad/model.h | 34 ++++ selfdrive/ui/ui.cc | 93 --------- selfdrive/ui/ui.h | 27 +-- 7 files changed, 249 insertions(+), 240 deletions(-) create mode 100644 selfdrive/ui/qt/onroad/model.cc create mode 100644 selfdrive/ui/qt/onroad/model.h diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index da652f7bfd..643951fff3 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -30,7 +30,7 @@ qt_src = ["main.cc", "ui.cc", "qt/sidebar.cc", "qt/body.cc", "qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc", "qt/offroad/software_settings.cc", "qt/offroad/onboarding.cc", "qt/offroad/driverview.cc", "qt/offroad/experimental_mode.cc", - "qt/onroad/onroad_home.cc", "qt/onroad/annotated_camera.cc", + "qt/onroad/onroad_home.cc", "qt/onroad/annotated_camera.cc", "qt/onroad/model.cc", "qt/onroad/buttons.cc", "qt/onroad/alerts.cc", "qt/onroad/driver_monitoring.cc", "qt/onroad/hud.cc"] # build translation files diff --git a/selfdrive/ui/qt/onroad/annotated_camera.cc b/selfdrive/ui/qt/onroad/annotated_camera.cc index fd8ad19c2e..f504ad69f1 100644 --- a/selfdrive/ui/qt/onroad/annotated_camera.cc +++ b/selfdrive/ui/qt/onroad/annotated_camera.cc @@ -75,8 +75,7 @@ mat4 AnnotatedCameraWidget::calcFrameMatrix() { 0.0f, zoom, (h / 2 - y_offset) - (center_y * zoom), 0.0f, 0.0f, 1.0f).finished(); - s->car_space_transform = video_transform * calib_transform; - s->clip_region = rect().adjusted(-500, -500, 500, 500); + model.setTransform(video_transform * calib_transform); float zx = zoom * 2 * center_x / w; float zy = zoom * 2 * center_y / h; @@ -88,106 +87,10 @@ mat4 AnnotatedCameraWidget::calcFrameMatrix() { }}; } -void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) { - painter.save(); - - const UIScene &scene = s->scene; - SubMaster &sm = *(s->sm); - - // lanelines - for (int i = 0; i < std::size(scene.lane_line_vertices); ++i) { - painter.setBrush(QColor::fromRgbF(1.0, 1.0, 1.0, std::clamp(scene.lane_line_probs[i], 0.0, 0.7))); - painter.drawPolygon(scene.lane_line_vertices[i]); - } - - // road edges - for (int i = 0; i < std::size(scene.road_edge_vertices); ++i) { - painter.setBrush(QColor::fromRgbF(1.0, 0, 0, std::clamp(1.0 - scene.road_edge_stds[i], 0.0, 1.0))); - painter.drawPolygon(scene.road_edge_vertices[i]); - } - - // paint path - QLinearGradient bg(0, height(), 0, 0); - if (sm["selfdriveState"].getSelfdriveState().getExperimentalMode()) { - // The first half of track_vertices are the points for the right side of the path - const auto &acceleration = sm["modelV2"].getModelV2().getAcceleration().getX(); - const int max_len = std::min(scene.track_vertices.length() / 2, acceleration.size()); - - for (int i = 0; i < max_len; ++i) { - // Some points are out of frame - int track_idx = max_len - i - 1; // flip idx to start from bottom right - if (scene.track_vertices[track_idx].y() < 0 || scene.track_vertices[track_idx].y() > height()) continue; - - // Flip so 0 is bottom of frame - float lin_grad_point = (height() - scene.track_vertices[track_idx].y()) / height(); - - // speed up: 120, slow down: 0 - float path_hue = fmax(fmin(60 + acceleration[i] * 35, 120), 0); - // FIXME: painter.drawPolygon can be slow if hue is not rounded - path_hue = int(path_hue * 100 + 0.5) / 100; - - float saturation = fmin(fabs(acceleration[i] * 1.5), 1); - float lightness = util::map_val(saturation, 0.0f, 1.0f, 0.95f, 0.62f); // lighter when grey - float alpha = util::map_val(lin_grad_point, 0.75f / 2.f, 0.75f, 0.4f, 0.0f); // matches previous alpha fade - bg.setColorAt(lin_grad_point, QColor::fromHslF(path_hue / 360., saturation, lightness, alpha)); - - // Skip a point, unless next is last - i += (i + 2) < max_len ? 1 : 0; - } - - } else { - bg.setColorAt(0.0, QColor::fromHslF(148 / 360., 0.94, 0.51, 0.4)); - bg.setColorAt(0.5, QColor::fromHslF(112 / 360., 1.0, 0.68, 0.35)); - bg.setColorAt(1.0, QColor::fromHslF(112 / 360., 1.0, 0.68, 0.0)); - } - - painter.setBrush(bg); - painter.drawPolygon(scene.track_vertices); - - painter.restore(); -} - -void AnnotatedCameraWidget::drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd) { - painter.save(); - - const float speedBuff = 10.; - const float leadBuff = 40.; - const float d_rel = lead_data.getDRel(); - const float v_rel = lead_data.getVRel(); - - float fillAlpha = 0; - if (d_rel < leadBuff) { - fillAlpha = 255 * (1.0 - (d_rel / leadBuff)); - if (v_rel < 0) { - fillAlpha += 255 * (-1 * (v_rel / speedBuff)); - } - fillAlpha = (int)(fmin(fillAlpha, 255)); - } - - float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * 2.35; - float x = std::clamp((float)vd.x(), 0.f, width() - sz / 2); - float y = std::fmin(height() - sz * .6, (float)vd.y()); - - float g_xo = sz / 5; - float g_yo = sz / 10; - - QPointF glow[] = {{x + (sz * 1.35) + g_xo, y + sz + g_yo}, {x, y - g_yo}, {x - (sz * 1.35) - g_xo, y + sz + g_yo}}; - painter.setBrush(QColor(218, 202, 37, 255)); - painter.drawPolygon(glow, std::size(glow)); - - // chevron - QPointF chevron[] = {{x + (sz * 1.25), y + sz}, {x, y}, {x - (sz * 1.25), y + sz}}; - painter.setBrush(redColor(fillAlpha)); - painter.drawPolygon(chevron, std::size(chevron)); - - painter.restore(); -} - void AnnotatedCameraWidget::paintGL() { UIState *s = uiState(); SubMaster &sm = *(s->sm); const double start_draw_t = millis_since_boot(); - const cereal::ModelDataV2::Reader &model = sm["modelV2"].getModelV2(); // draw camera frame { @@ -218,7 +121,7 @@ void AnnotatedCameraWidget::paintGL() { wide_cam_requested = wide_cam_requested && sm["selfdriveState"].getSelfdriveState().getExperimentalMode(); } CameraWidget::setStreamType(wide_cam_requested ? VISION_STREAM_WIDE_ROAD : VISION_STREAM_ROAD); - CameraWidget::setFrameId(model.getFrameId()); + CameraWidget::setFrameId(sm["modelV2"].getModelV2().getFrameId()); CameraWidget::paintGL(); } @@ -226,24 +129,7 @@ void AnnotatedCameraWidget::paintGL() { painter.setRenderHint(QPainter::Antialiasing); painter.setPen(Qt::NoPen); - if (s->scene.world_objects_visible) { - update_model(s, model); - drawLaneLines(painter, s); - - if (s->scene.longitudinal_control && sm.rcv_frame("radarState") > s->scene.started_frame) { - auto radar_state = sm["radarState"].getRadarState(); - update_leads(s, radar_state, model.getPosition()); - auto lead_one = radar_state.getLeadOne(); - auto lead_two = radar_state.getLeadTwo(); - if (lead_one.getStatus()) { - drawLead(painter, lead_one, s->scene.lead_vertices[0]); - } - if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) { - drawLead(painter, lead_two, s->scene.lead_vertices[1]); - } - } - } - + model.draw(painter, rect()); dmon.draw(painter, rect()); hud.updateState(*s); hud.draw(painter, rect()); diff --git a/selfdrive/ui/qt/onroad/annotated_camera.h b/selfdrive/ui/qt/onroad/annotated_camera.h index 324a6d7458..d205579f6c 100644 --- a/selfdrive/ui/qt/onroad/annotated_camera.h +++ b/selfdrive/ui/qt/onroad/annotated_camera.h @@ -5,6 +5,7 @@ #include "selfdrive/ui/qt/onroad/hud.h" #include "selfdrive/ui/qt/onroad/buttons.h" #include "selfdrive/ui/qt/onroad/driver_monitoring.h" +#include "selfdrive/ui/qt/onroad/model.h" #include "selfdrive/ui/qt/widgets/cameraview.h" class AnnotatedCameraWidget : public CameraWidget { @@ -19,6 +20,7 @@ private: ExperimentalButton *experimental_btn; DriverMonitorRenderer dmon; HudRenderer hud; + ModelRenderer model; std::unique_ptr pm; int skip_frame_count = 0; @@ -29,9 +31,6 @@ protected: void initializeGL() override; void showEvent(QShowEvent *event) override; mat4 calcFrameMatrix() override; - void drawLaneLines(QPainter &painter, const UIState *s); - void drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd); - inline QColor redColor(int alpha = 255) { return QColor(201, 34, 49, alpha); } double prev_draw_t = 0; FirstOrderFilter fps_filter; diff --git a/selfdrive/ui/qt/onroad/model.cc b/selfdrive/ui/qt/onroad/model.cc new file mode 100644 index 0000000000..9a2c989b26 --- /dev/null +++ b/selfdrive/ui/qt/onroad/model.cc @@ -0,0 +1,208 @@ +#include "selfdrive/ui/qt/onroad/model.h" + +constexpr int CLIP_MARGIN = 500; +constexpr float MIN_DRAW_DISTANCE = 10.0; +constexpr float MAX_DRAW_DISTANCE = 100.0; + +static int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height) { + const auto &line_x = line.getX(); + int max_idx = 0; + for (int i = 1; i < line_x.size() && line_x[i] <= path_height; ++i) { + max_idx = i; + } + return max_idx; +} + +void ModelRenderer::draw(QPainter &painter, const QRect &surface_rect) { + auto &sm = *(uiState()->sm); + if (sm.updated("carParams")) { + longitudinal_control = sm["carParams"].getCarParams().getOpenpilotLongitudinalControl(); + } + + // Check if data is up-to-date + if (!(sm.alive("liveCalibration") && sm.alive("modelV2"))) { + return; + } + + clip_region = surface_rect.adjusted(-CLIP_MARGIN, -CLIP_MARGIN, CLIP_MARGIN, CLIP_MARGIN); + experimental_model = sm["selfdriveState"].getSelfdriveState().getExperimentalMode(); + + painter.save(); + + const auto &model = sm["modelV2"].getModelV2(); + const auto &radar_state = sm["radarState"].getRadarState(); + const auto &lead_one = radar_state.getLeadOne(); + + update_model(model, lead_one); + drawLaneLines(painter); + drawPath(painter, model, surface_rect.height()); + + if (longitudinal_control && sm.alive("radarState")) { + update_leads(radar_state, model.getPosition()); + const auto &lead_two = radar_state.getLeadTwo(); + if (lead_one.getStatus()) { + drawLead(painter, lead_one, lead_vertices[0], surface_rect); + } + if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) { + drawLead(painter, lead_two, lead_vertices[1], surface_rect); + } + } + + painter.restore(); +} + +void ModelRenderer::update_leads(const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line) { + for (int i = 0; i < 2; ++i) { + const auto &lead_data = (i == 0) ? radar_state.getLeadOne() : radar_state.getLeadTwo(); + if (lead_data.getStatus()) { + float z = line.getZ()[get_path_length_idx(line, lead_data.getDRel())]; + mapToScreen(lead_data.getDRel(), -lead_data.getYRel(), z + 1.22, &lead_vertices[i]); + } + } +} + +void ModelRenderer::update_model(const cereal::ModelDataV2::Reader &model, const cereal::RadarState::LeadData::Reader &lead) { + const auto &model_position = model.getPosition(); + float max_distance = std::clamp(*(model_position.getX().end() - 1), MIN_DRAW_DISTANCE, MAX_DRAW_DISTANCE); + + // update lane lines + const auto &lane_lines = model.getLaneLines(); + const auto &line_probs = model.getLaneLineProbs(); + int max_idx = get_path_length_idx(lane_lines[0], max_distance); + for (int i = 0; i < std::size(lane_line_vertices); i++) { + lane_line_probs[i] = line_probs[i]; + mapLineToPolygon(lane_lines[i], 0.025 * lane_line_probs[i], 0, &lane_line_vertices[i], max_idx); + } + + // update road edges + const auto &road_edges = model.getRoadEdges(); + const auto &edge_stds = model.getRoadEdgeStds(); + for (int i = 0; i < std::size(road_edge_vertices); i++) { + road_edge_stds[i] = edge_stds[i]; + mapLineToPolygon(road_edges[i], 0.025, 0, &road_edge_vertices[i], max_idx); + } + + // update path + if (lead.getStatus()) { + const float lead_d = lead.getDRel() * 2.; + max_distance = std::clamp((float)(lead_d - fmin(lead_d * 0.35, 10.)), 0.0f, max_distance); + } + max_idx = get_path_length_idx(model_position, max_distance); + mapLineToPolygon(model_position, 0.9, 1.22, &track_vertices, max_idx, false); +} + +void ModelRenderer::drawLaneLines(QPainter &painter) { + // lanelines + for (int i = 0; i < std::size(lane_line_vertices); ++i) { + painter.setBrush(QColor::fromRgbF(1.0, 1.0, 1.0, std::clamp(lane_line_probs[i], 0.0, 0.7))); + painter.drawPolygon(lane_line_vertices[i]); + } + + // road edges + for (int i = 0; i < std::size(road_edge_vertices); ++i) { + painter.setBrush(QColor::fromRgbF(1.0, 0, 0, std::clamp(1.0 - road_edge_stds[i], 0.0, 1.0))); + painter.drawPolygon(road_edge_vertices[i]); + } +} + +void ModelRenderer::drawPath(QPainter &painter, const cereal::ModelDataV2::Reader &model, int height) { + QLinearGradient bg(0, height, 0, 0); + if (experimental_model) { + // The first half of track_vertices are the points for the right side of the path + const auto &acceleration = model.getAcceleration().getX(); + const int max_len = std::min(track_vertices.length() / 2, acceleration.size()); + + for (int i = 0; i < max_len; ++i) { + // Some points are out of frame + int track_idx = max_len - i - 1; // flip idx to start from bottom right + if (track_vertices[track_idx].y() < 0 || track_vertices[track_idx].y() > height) continue; + + // Flip so 0 is bottom of frame + float lin_grad_point = (height - track_vertices[track_idx].y()) / height; + + // speed up: 120, slow down: 0 + float path_hue = fmax(fmin(60 + acceleration[i] * 35, 120), 0); + // FIXME: painter.drawPolygon can be slow if hue is not rounded + path_hue = int(path_hue * 100 + 0.5) / 100; + + float saturation = fmin(fabs(acceleration[i] * 1.5), 1); + float lightness = util::map_val(saturation, 0.0f, 1.0f, 0.95f, 0.62f); // lighter when grey + float alpha = util::map_val(lin_grad_point, 0.75f / 2.f, 0.75f, 0.4f, 0.0f); // matches previous alpha fade + bg.setColorAt(lin_grad_point, QColor::fromHslF(path_hue / 360., saturation, lightness, alpha)); + + // Skip a point, unless next is last + i += (i + 2) < max_len ? 1 : 0; + } + + } else { + bg.setColorAt(0.0, QColor::fromHslF(148 / 360., 0.94, 0.51, 0.4)); + bg.setColorAt(0.5, QColor::fromHslF(112 / 360., 1.0, 0.68, 0.35)); + bg.setColorAt(1.0, QColor::fromHslF(112 / 360., 1.0, 0.68, 0.0)); + } + + painter.setBrush(bg); + painter.drawPolygon(track_vertices); +} + +void ModelRenderer::drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, + const QPointF &vd, const QRect &surface_rect) { + const float speedBuff = 10.; + const float leadBuff = 40.; + const float d_rel = lead_data.getDRel(); + const float v_rel = lead_data.getVRel(); + + float fillAlpha = 0; + if (d_rel < leadBuff) { + fillAlpha = 255 * (1.0 - (d_rel / leadBuff)); + if (v_rel < 0) { + fillAlpha += 255 * (-1 * (v_rel / speedBuff)); + } + fillAlpha = (int)(fmin(fillAlpha, 255)); + } + + float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * 2.35; + float x = std::clamp(vd.x(), 0.f, surface_rect.width() - sz / 2); + float y = std::min(vd.y(), surface_rect.height() - sz * 0.6); + + float g_xo = sz / 5; + float g_yo = sz / 10; + + QPointF glow[] = {{x + (sz * 1.35) + g_xo, y + sz + g_yo}, {x, y - g_yo}, {x - (sz * 1.35) - g_xo, y + sz + g_yo}}; + painter.setBrush(QColor(218, 202, 37, 255)); + painter.drawPolygon(glow, std::size(glow)); + + // chevron + QPointF chevron[] = {{x + (sz * 1.25), y + sz}, {x, y}, {x - (sz * 1.25), y + sz}}; + painter.setBrush(QColor(201, 34, 49, fillAlpha)); + painter.drawPolygon(chevron, std::size(chevron)); +} + +// Projects a point in car to space to the corresponding point in full frame image space. +bool ModelRenderer::mapToScreen(float in_x, float in_y, float in_z, QPointF *out) { + Eigen::Vector3f input(in_x, in_y, in_z); + auto pt = car_space_transform * input; + *out = QPointF(pt.x() / pt.z(), pt.y() / pt.z()); + return clip_region.contains(*out); +} + +void ModelRenderer::mapLineToPolygon(const cereal::XYZTData::Reader &line, float y_off, float z_off, + QPolygonF *pvd, int max_idx, bool allow_invert) { + const auto line_x = line.getX(), line_y = line.getY(), line_z = line.getZ(); + QPointF left, right; + pvd->clear(); + for (int i = 0; i <= max_idx; i++) { + // highly negative x positions are drawn above the frame and cause flickering, clip to zy plane of camera + if (line_x[i] < 0) continue; + + bool l = mapToScreen(line_x[i], line_y[i] - y_off, line_z[i] + z_off, &left); + bool r = mapToScreen(line_x[i], line_y[i] + y_off, line_z[i] + z_off, &right); + if (l && r) { + // For wider lines the drawn polygon will "invert" when going over a hill and cause artifacts + if (!allow_invert && pvd->size() && left.y() > pvd->back().y()) { + continue; + } + pvd->push_back(left); + pvd->push_front(right); + } + } +} diff --git a/selfdrive/ui/qt/onroad/model.h b/selfdrive/ui/qt/onroad/model.h new file mode 100644 index 0000000000..358fce53f4 --- /dev/null +++ b/selfdrive/ui/qt/onroad/model.h @@ -0,0 +1,34 @@ +#pragma once + +#include +#include + +#include "selfdrive/ui/ui.h" + +class ModelRenderer { +public: + ModelRenderer() {} + void setTransform(const Eigen::Matrix3f &transform) { car_space_transform = transform; } + void draw(QPainter &painter, const QRect &surface_rect); + +private: + bool mapToScreen(float in_x, float in_y, float in_z, QPointF *out); + void mapLineToPolygon(const cereal::XYZTData::Reader &line, float y_off, float z_off, + QPolygonF *pvd, int max_idx, bool allow_invert = true); + void drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd, const QRect &surface_rect); + void update_leads(const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line); + void update_model(const cereal::ModelDataV2::Reader &model, const cereal::RadarState::LeadData::Reader &lead); + void drawLaneLines(QPainter &painter); + void drawPath(QPainter &painter, const cereal::ModelDataV2::Reader &model, int height); + + bool longitudinal_control = false; + bool experimental_model = false; + float lane_line_probs[4] = {}; + float road_edge_stds[2] = {}; + QPolygonF track_vertices; + QPolygonF lane_line_vertices[4] = {}; + QPolygonF road_edge_vertices[2] = {}; + QPointF lead_vertices[2] = {}; + Eigen::Matrix3f car_space_transform = Eigen::Matrix3f::Zero(); + QRectF clip_region; +}; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 852980d54e..a9206b59bb 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -14,90 +14,6 @@ #define BACKLIGHT_DT 0.05 #define BACKLIGHT_TS 10.00 -// Projects a point in car to space to the corresponding point in full frame -// image space. -static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y, float in_z, QPointF *out) { - Eigen::Vector3f input(in_x, in_y, in_z); - auto transformed = s->car_space_transform * input; - *out = QPointF(transformed.x() / transformed.z(), transformed.y() / transformed.z()); - return s->clip_region.contains(*out); -} - -int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height) { - const auto line_x = line.getX(); - int max_idx = 0; - for (int i = 1; i < line_x.size() && line_x[i] <= path_height; ++i) { - max_idx = i; - } - return max_idx; -} - -void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line) { - for (int i = 0; i < 2; ++i) { - auto lead_data = (i == 0) ? radar_state.getLeadOne() : radar_state.getLeadTwo(); - if (lead_data.getStatus()) { - float z = line.getZ()[get_path_length_idx(line, lead_data.getDRel())]; - calib_frame_to_full_frame(s, lead_data.getDRel(), -lead_data.getYRel(), z + 1.22, &s->scene.lead_vertices[i]); - } - } -} - -void update_line_data(const UIState *s, const cereal::XYZTData::Reader &line, - float y_off, float z_off, QPolygonF *pvd, int max_idx, bool allow_invert=true) { - const auto line_x = line.getX(), line_y = line.getY(), line_z = line.getZ(); - QPointF left, right; - pvd->clear(); - for (int i = 0; i <= max_idx; i++) { - // highly negative x positions are drawn above the frame and cause flickering, clip to zy plane of camera - if (line_x[i] < 0) continue; - - bool l = calib_frame_to_full_frame(s, line_x[i], line_y[i] - y_off, line_z[i] + z_off, &left); - bool r = calib_frame_to_full_frame(s, line_x[i], line_y[i] + y_off, line_z[i] + z_off, &right); - if (l && r) { - // For wider lines the drawn polygon will "invert" when going over a hill and cause artifacts - if (!allow_invert && pvd->size() && left.y() > pvd->back().y()) { - continue; - } - pvd->push_back(left); - pvd->push_front(right); - } - } -} - -void update_model(UIState *s, - const cereal::ModelDataV2::Reader &model) { - UIScene &scene = s->scene; - auto model_position = model.getPosition(); - float max_distance = std::clamp(*(model_position.getX().end() - 1), - MIN_DRAW_DISTANCE, MAX_DRAW_DISTANCE); - - // update lane lines - const auto lane_lines = model.getLaneLines(); - const auto lane_line_probs = model.getLaneLineProbs(); - int max_idx = get_path_length_idx(lane_lines[0], max_distance); - for (int i = 0; i < std::size(scene.lane_line_vertices); i++) { - scene.lane_line_probs[i] = lane_line_probs[i]; - update_line_data(s, lane_lines[i], 0.025 * scene.lane_line_probs[i], 0, &scene.lane_line_vertices[i], max_idx); - } - - // update road edges - const auto road_edges = model.getRoadEdges(); - const auto road_edge_stds = model.getRoadEdgeStds(); - for (int i = 0; i < std::size(scene.road_edge_vertices); i++) { - scene.road_edge_stds[i] = road_edge_stds[i]; - update_line_data(s, road_edges[i], 0.025, 0, &scene.road_edge_vertices[i], max_idx); - } - - // update path - auto lead_one = (*s->sm)["radarState"].getRadarState().getLeadOne(); - if (lead_one.getStatus()) { - const float lead_d = lead_one.getDRel() * 2.; - max_distance = std::clamp((float)(lead_d - fmin(lead_d * 0.35, 10.)), 0.0f, max_distance); - } - max_idx = get_path_length_idx(model_position, max_distance); - update_line_data(s, model_position, 0.9, 1.22, &scene.track_vertices, max_idx, false); -} - static void update_sockets(UIState *s) { s->sm->update(0); } @@ -136,9 +52,6 @@ static void update_state(UIState *s) { } else if ((s->sm->frame - s->sm->rcv_frame("pandaStates")) > 5*UI_FREQ) { scene.pandaType = cereal::PandaState::PandaType::UNKNOWN; } - if (sm.updated("carParams")) { - scene.longitudinal_control = sm["carParams"].getCarParams().getOpenpilotLongitudinalControl(); - } if (sm.updated("wideRoadCameraState")) { auto cam_state = sm["wideRoadCameraState"].getWideRoadCameraState(); float scale = (cam_state.getSensor() == cereal::FrameData::ImageSensor::AR0231) ? 6.0f : 1.0f; @@ -147,11 +60,6 @@ static void update_state(UIState *s) { scene.light_sensor = -1; } scene.started = sm["deviceState"].getDeviceState().getStarted() && scene.ignition; - - scene.world_objects_visible = scene.world_objects_visible || - (scene.started && - sm.rcv_frame("liveCalibration") > scene.started_frame && - sm.rcv_frame("modelV2") > scene.started_frame); } void ui_update_params(UIState *s) { @@ -177,7 +85,6 @@ void UIState::updateStatus() { scene.started_frame = sm->frame; } started_prev = scene.started; - scene.world_objects_visible = false; emit offroadTransition(!scene.started); } } diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 8a06a4cccb..6ff67cacde 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -7,7 +7,6 @@ #include #include #include -#include #include "cereal/messaging/messaging.h" #include "common/mat.h" @@ -22,8 +21,6 @@ const int UI_HEADER_HEIGHT = 420; const int UI_FREQ = 20; // Hz const int BACKLIGHT_OFFROAD = 50; -const float MIN_DRAW_DISTANCE = 10.0; -const float MAX_DRAW_DISTANCE = 100.0; const Eigen::Matrix3f VIEW_FROM_DEVICE = (Eigen::Matrix3f() << 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, @@ -58,21 +55,10 @@ typedef struct UIScene { Eigen::Matrix3f view_from_wide_calib = VIEW_FROM_DEVICE; cereal::PandaState::PandaType pandaType; - // modelV2 - float lane_line_probs[4]; - float road_edge_stds[2]; - QPolygonF track_vertices; - QPolygonF lane_line_vertices[4]; - QPolygonF road_edge_vertices[2]; - - // lead - QPointF lead_vertices[2]; - cereal::LongitudinalPersonality personality; float light_sensor = -1; - bool started, ignition, is_metric, longitudinal_control; - bool world_objects_visible = false; + bool started, ignition, is_metric; uint64_t started_frame; } UIScene; @@ -89,13 +75,9 @@ public: std::unique_ptr sm; UIStatus status; UIScene scene = {}; - QString language; PrimeState *prime_state; - Eigen::Matrix3f car_space_transform = Eigen::Matrix3f::Zero(); - QRectF clip_region; - signals: void uiUpdate(const UIState &s); void offroadTransition(bool offroad); @@ -145,11 +127,4 @@ public slots: }; Device *device(); - void ui_update_params(UIState *s); -int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height); -void update_model(UIState *s, - const cereal::ModelDataV2::Reader &model); -void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line); -void update_line_data(const UIState *s, const cereal::XYZTData::Reader &line, - float y_off, float z_off, QPolygonF *pvd, int max_idx, bool allow_invert); From f7c4aad8bda187e05d24ceac307384aa5e610cb9 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 4 Oct 2024 01:53:05 +0800 Subject: [PATCH 203/214] cameread: remove outdated 'm' and 'atomic' libraries (#33714) remove unused libs --- system/camerad/SConscript | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/camerad/SConscript b/system/camerad/SConscript index 8bafd83f08..1820d21b3d 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -1,6 +1,6 @@ Import('env', 'arch', 'messaging', 'common', 'gpucommon', 'visionipc') -libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', messaging, visionipc, gpucommon, 'atomic'] +libs = ['pthread', common, 'jpeg', 'OpenCL', messaging, visionipc, gpucommon] camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/spectra.cc', 'sensors/ar0231.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc']) From b7a388773159f29ef5a8864918cf155ea8e5c0af Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Kacper=20R=C4=85czy?= Date: Thu, 3 Oct 2024 13:13:19 -0700 Subject: [PATCH 204/214] process_replay: fix llk migration (#33717) * If field is empty put nans * Move import out --- selfdrive/test/process_replay/migration.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index 9241a3d493..c4f1d19d9d 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -142,6 +142,7 @@ def migrate_liveTracks(msgs): @migration(inputs=["liveLocationKalmanDEPRECATED"], product="livePose") def migrate_liveLocationKalman(msgs): + nans = [float('nan')] * 3 ops = [] for index, msg in msgs: m = messaging.new_message('livePose') @@ -149,8 +150,8 @@ def migrate_liveLocationKalman(msgs): m.logMonoTime = msg.logMonoTime for field in ["orientationNED", "velocityDevice", "accelerationDevice", "angularVelocityDevice"]: lp_field, llk_field = getattr(m.livePose, field), getattr(msg.liveLocationKalmanDEPRECATED, field) - lp_field.x, lp_field.y, lp_field.z = llk_field.value - lp_field.xStd, lp_field.yStd, lp_field.zStd = llk_field.std + lp_field.x, lp_field.y, lp_field.z = llk_field.value or nans + lp_field.xStd, lp_field.yStd, lp_field.zStd = llk_field.std or nans lp_field.valid = llk_field.valid for flag in ["inputsOK", "posenetOK", "sensorsOK"]: setattr(m.livePose, flag, getattr(msg.liveLocationKalmanDEPRECATED, flag)) From 72e19ccfc6de0a145bf778fdc701878f969347bb Mon Sep 17 00:00:00 2001 From: Maxime Desroches Date: Thu, 3 Oct 2024 14:25:48 -0700 Subject: [PATCH 205/214] jenkins: disable time to onroad (#33719) comment --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 84514948c7..7137b8bf36 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -149,7 +149,7 @@ node { ["build openpilot", "cd system/manager && ./build.py"], ["check dirty", "release/check-dirty.sh"], ["onroad tests", "pytest selfdrive/test/test_onroad.py -s"], - ["time to onroad", "pytest selfdrive/test/test_time_to_onroad.py"], + //["time to onroad", "pytest selfdrive/test/test_time_to_onroad.py"], ]) }, 'HW + Unit Tests': { From af774d894e6698f832c1d813587e3d7dabad0ea7 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 3 Oct 2024 15:20:58 -0700 Subject: [PATCH 206/214] Deprecate car onroadEvents (#33687) * new OnroadEvent struct * and migrate python * more forgotten * re-index new OnroadEvent struct * fix! * more missing * migrate onroadEvents migrate onroadEvents * migrate dm events * hacks to get proc replay to say succeeded * Revert "hacks to get proc replay to say succeeded" This reverts commit 0bb8803e5755d606ae9f09da5395d9f50678c7c7. * update refs --- cereal/car.capnp | 9 +- cereal/log.capnp | 120 ++++++++++++++++++++- selfdrive/car/car_specific.py | 4 +- selfdrive/car/card.py | 4 +- selfdrive/car/tests/test_models.py | 2 +- selfdrive/debug/cycle_alerts.py | 2 +- selfdrive/monitoring/helpers.py | 4 +- selfdrive/monitoring/test_monitoring.py | 4 +- selfdrive/selfdrived/events.py | 4 +- selfdrive/selfdrived/selfdrived.py | 2 +- selfdrive/selfdrived/tests/test_alerts.py | 2 +- selfdrive/test/process_replay/migration.py | 32 +++++- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/test_onroad.py | 4 +- selfdrive/test/test_time_to_onroad.py | 4 +- 15 files changed, 171 insertions(+), 28 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index 326f1eeef8..c8474f431b 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -5,9 +5,8 @@ $Cxx.namespace("cereal"); # ******* events causing controls state machine transition ******* -# FIXME: OnroadEvent shouldn't be in car.capnp, but can't immediately -# move due to being referenced by structs in this file -struct OnroadEvent @0x9b1657f34caf3ad3 { +# IMPORTANT: This struct is to not be modified so old logs can be parsed +struct OnroadEventDEPRECATED @0x9b1657f34caf3ad3 { name @0 :EventName; # event types @@ -289,12 +288,12 @@ struct CarState { } # deprecated - errorsDEPRECATED @0 :List(OnroadEvent.EventName); + errorsDEPRECATED @0 :List(OnroadEventDEPRECATED.EventName); brakeLightsDEPRECATED @19 :Bool; steeringRateLimitedDEPRECATED @29 :Bool; canMonoTimesDEPRECATED @12: List(UInt64); canRcvTimeoutDEPRECATED @49 :Bool; - eventsDEPRECATED @13 :List(OnroadEvent); + eventsDEPRECATED @13 :List(OnroadEventDEPRECATED); } # ******* radar state @ 20hz ******* diff --git a/cereal/log.capnp b/cereal/log.capnp index 3d5f7d9d7f..c35219b3ac 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -17,6 +17,118 @@ struct Map(Key, Value) { } } +struct OnroadEvent @0xc4fa6047f024e718 { + name @0 :EventName; + + # event types + enable @1 :Bool; + noEntry @2 :Bool; + warning @3 :Bool; # alerts presented only when enabled or soft disabling + userDisable @4 :Bool; + softDisable @5 :Bool; + immediateDisable @6 :Bool; + preEnable @7 :Bool; + permanent @8 :Bool; # alerts presented regardless of openpilot state + overrideLateral @10 :Bool; + overrideLongitudinal @9 :Bool; + + enum EventName @0x91f1992a1f77fb03 { + canError @0; + steerUnavailable @1; + wrongGear @2; + doorOpen @3; + seatbeltNotLatched @4; + espDisabled @5; + wrongCarMode @6; + steerTempUnavailable @7; + reverseGear @8; + buttonCancel @9; + buttonEnable @10; + pedalPressed @11; # exits active state + preEnableStandstill @12; # added during pre-enable state with brake + gasPressedOverride @13; # added when user is pressing gas with no disengage on gas + steerOverride @14; + cruiseDisabled @15; + speedTooLow @16; + outOfSpace @17; + overheat @18; + calibrationIncomplete @19; + calibrationInvalid @20; + calibrationRecalibrating @21; + controlsMismatch @22; + pcmEnable @23; + pcmDisable @24; + radarFault @25; + brakeHold @26; + parkBrake @27; + manualRestart @28; + joystickDebug @29; + longitudinalManeuver @30; + steerTempUnavailableSilent @31; + resumeRequired @32; + preDriverDistracted @33; + promptDriverDistracted @34; + driverDistracted @35; + preDriverUnresponsive @36; + promptDriverUnresponsive @37; + driverUnresponsive @38; + belowSteerSpeed @39; + lowBattery @40; + accFaulted @41; + sensorDataInvalid @42; + commIssue @43; + commIssueAvgFreq @44; + tooDistracted @45; + posenetInvalid @46; + soundsUnavailable @47; + preLaneChangeLeft @48; + preLaneChangeRight @49; + laneChange @50; + lowMemory @51; + stockAeb @52; + ldw @53; + carUnrecognized @54; + invalidLkasSetting @55; + speedTooHigh @56; + laneChangeBlocked @57; + relayMalfunction @58; + stockFcw @59; + startup @60; + startupNoCar @61; + startupNoControl @62; + startupNoSecOcKey @63; + startupMaster @64; + fcw @65; + steerSaturated @66; + belowEngageSpeed @67; + noGps @68; + wrongCruiseMode @69; + modeldLagging @70; + deviceFalling @71; + fanMalfunction @72; + cameraMalfunction @73; + cameraFrameRate @74; + processNotRunning @75; + dashcamMode @76; + selfdriveInitializing @77; + usbError @78; + cruiseMismatch @79; + canBusMissing @80; + selfdrivedLagging @81; + resumeBlocked @82; + steerTimeLimit @83; + vehicleSensorsInvalid @84; + locationdTemporaryError @85; + locationdPermanentError @86; + paramsdTemporaryError @87; + paramsdPermanentError @88; + actuatorsApiUnavailable @89; + espActive @90; + personalityChanged @91; + aeb @92; + } +} + enum LongitudinalPersonality { aggressive @0; standard @1; @@ -1157,7 +1269,7 @@ struct LongitudinalPlan @0xe00b5b3eba12876c { radarValidDEPRECATED @28 :Bool; radarCanErrorDEPRECATED @30 :Bool; commIssueDEPRECATED @31 :Bool; - eventsDEPRECATED @13 :List(Car.OnroadEvent); + eventsDEPRECATED @13 :List(Car.OnroadEventDEPRECATED); gpsTrajectoryDEPRECATED @12 :GpsTrajectory; gpsPlannerActiveDEPRECATED @19 :Bool; personalityDEPRECATED @36 :LongitudinalPersonality; @@ -2072,7 +2184,7 @@ struct DriverStateDEPRECATED @0xb83c6cc593ed0a00 { } struct DriverMonitoringState @0xb83cda094a1da284 { - events @0 :List(Car.OnroadEvent); + events @18 :List(OnroadEvent); faceDetected @1 :Bool; isDistracted @2 :Bool; distractedType @17 :UInt32; @@ -2091,6 +2203,7 @@ struct DriverMonitoringState @0xb83cda094a1da284 { isPreviewDEPRECATED @15 :Bool; rhdCheckedDEPRECATED @5 :Bool; + eventsDEPRECATED @0 :List(Car.OnroadEventDEPRECATED); } struct Boot { @@ -2369,7 +2482,7 @@ struct Event { liveTorqueParameters @94 :LiveTorqueParametersData; cameraOdometry @63 :CameraOdometry; thumbnail @66: Thumbnail; - onroadEvents @68: List(Car.OnroadEvent); + onroadEvents @134: List(OnroadEvent); carParams @69: Car.CarParams; driverMonitoringState @71: DriverMonitoringState; livePose @129 :LivePose; @@ -2484,5 +2597,6 @@ struct Event { uiPlanDEPRECATED @106 :UiPlan; liveLocationKalmanDEPRECATED @72 :LiveLocationKalman; liveTracksDEPRECATED @16 :List(LiveTracksDEPRECATED); + onroadEventsDEPRECATED @68: List(Car.OnroadEventDEPRECATED); } } diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py index 23719a8c4f..94afec50e2 100644 --- a/selfdrive/car/car_specific.py +++ b/selfdrive/car/car_specific.py @@ -1,5 +1,5 @@ from collections import deque -from cereal import car +from cereal import car, log import cereal.messaging as messaging from opendbc.car import DT_CTRL, structs from opendbc.car.interfaces import MAX_CTRL_SPEED @@ -11,7 +11,7 @@ from openpilot.selfdrive.selfdrived.events import Events ButtonType = structs.CarState.ButtonEvent.Type GearShifter = structs.CarState.GearShifter -EventName = car.OnroadEvent.EventName +EventName = log.OnroadEvent.EventName NetworkLocation = structs.CarParams.NetworkLocation diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 380d5df431..0afd0e7323 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -5,7 +5,7 @@ import threading import cereal.messaging as messaging -from cereal import car +from cereal import car, log from panda import ALTERNATIVE_EXPERIENCE @@ -25,7 +25,7 @@ from openpilot.selfdrive.car.helpers import convert_carControl, convert_to_capnp REPLAY = "REPLAY" in os.environ -EventName = car.OnroadEvent.EventName +EventName = log.OnroadEvent.EventName # forward carlog.addHandler(ForwardingHandler(cloudlog)) diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 10620c146f..ef54631e54 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -31,7 +31,7 @@ from openpilot.tools.lib.route import SegmentName from panda.tests.libpanda import libpanda_py -EventName = car.OnroadEvent.EventName +EventName = log.OnroadEvent.EventName PandaType = log.PandaState.PandaType SafetyModel = car.CarParams.SafetyModel diff --git a/selfdrive/debug/cycle_alerts.py b/selfdrive/debug/cycle_alerts.py index ec32306436..11e75a7a8e 100755 --- a/selfdrive/debug/cycle_alerts.py +++ b/selfdrive/debug/cycle_alerts.py @@ -10,7 +10,7 @@ from openpilot.selfdrive.selfdrived.events import ET, Events from openpilot.selfdrive.selfdrived.alertmanager import AlertManager from openpilot.system.manager.process_config import managed_processes -EventName = car.OnroadEvent.EventName +EventName = log.OnroadEvent.EventName def randperc() -> float: return 100. * random.random() diff --git a/selfdrive/monitoring/helpers.py b/selfdrive/monitoring/helpers.py index 72df724532..88665778a2 100644 --- a/selfdrive/monitoring/helpers.py +++ b/selfdrive/monitoring/helpers.py @@ -1,6 +1,6 @@ from math import atan2 -from cereal import car +from cereal import car, log import cereal.messaging as messaging from openpilot.selfdrive.selfdrived.events import Events from openpilot.common.numpy_fast import interp @@ -9,7 +9,7 @@ from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.stat_live import RunningStatFilter from openpilot.common.transformations.camera import DEVICE_CAMERAS -EventName = car.OnroadEvent.EventName +EventName = log.OnroadEvent.EventName # ****************************************************************************************** # NOTE: To fork maintainers. diff --git a/selfdrive/monitoring/test_monitoring.py b/selfdrive/monitoring/test_monitoring.py index 31ae98c638..2a20b20dc1 100644 --- a/selfdrive/monitoring/test_monitoring.py +++ b/selfdrive/monitoring/test_monitoring.py @@ -1,10 +1,10 @@ import numpy as np -from cereal import car, log +from cereal import log from openpilot.common.realtime import DT_DMON from openpilot.selfdrive.monitoring.helpers import DriverMonitoring, DRIVER_MONITOR_SETTINGS -EventName = car.OnroadEvent.EventName +EventName = log.OnroadEvent.EventName dm_settings = DRIVER_MONITOR_SETTINGS() TEST_TIMESPAN = 120 # seconds diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index 070ca60ca2..7be514e350 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -16,7 +16,7 @@ AlertSize = log.SelfdriveState.AlertSize AlertStatus = log.SelfdriveState.AlertStatus VisualAlert = car.CarControl.HUDControl.VisualAlert AudibleAlert = car.CarControl.HUDControl.AudibleAlert -EventName = car.OnroadEvent.EventName +EventName = log.OnroadEvent.EventName # Alert priorities @@ -98,7 +98,7 @@ class Events: def to_msg(self): ret = [] for event_name in self.events: - event = car.OnroadEvent.new_message() + event = log.OnroadEvent.new_message() event.name = event_name for event_type in EVENTS.get(event_name, {}): setattr(event, event_type, True) diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 160117faa8..8b7575d35d 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -35,7 +35,7 @@ State = log.SelfdriveState.OpenpilotState PandaType = log.PandaState.PandaType LaneChangeState = log.LaneChangeState LaneChangeDirection = log.LaneChangeDirection -EventName = car.OnroadEvent.EventName +EventName = log.OnroadEvent.EventName ButtonType = car.CarState.ButtonEvent.Type SafetyModel = car.CarParams.SafetyModel diff --git a/selfdrive/selfdrived/tests/test_alerts.py b/selfdrive/selfdrived/tests/test_alerts.py index a5249cc03f..b916741ad0 100644 --- a/selfdrive/selfdrived/tests/test_alerts.py +++ b/selfdrive/selfdrived/tests/test_alerts.py @@ -38,7 +38,7 @@ class TestAlerts: def test_events_defined(self): # Ensure all events in capnp schema are defined in events.py - events = car.OnroadEvent.EventName.schema.enumerants + events = log.OnroadEvent.EventName.schema.enumerants for name, e in events.items(): if not name.endswith("DEPRECATED"): diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index c4f1d19d9d..a90825cbd0 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -3,7 +3,7 @@ from collections.abc import Callable import functools import capnp -from cereal import messaging, car +from cereal import messaging, car, log from opendbc.car.fingerprints import MIGRATION from opendbc.car.toyota.values import EPS_SCALE from openpilot.selfdrive.modeld.constants import ModelConstants @@ -37,6 +37,8 @@ def migrate_all(lr: LogIterable, manager_states: bool = False, panda_states: boo migrate_liveTracks, migrate_driverAssistance, migrate_drivingModelData, + migrate_onroadEvents, + migrate_driverMonitoringState, ] if manager_states: migrations.append(migrate_managerState) @@ -393,3 +395,31 @@ def migrate_sensorEvents(msgs): add_ops.append(m.as_reader()) del_ops.append(index) return [], add_ops, del_ops + + +@migration(inputs=["onroadEventsDEPRECATED"], product="onroadEvents") +def migrate_onroadEvents(msgs): + ops = [] + for index, msg in msgs: + new_msg = messaging.new_message('onroadEvents', len(msg.onroadEventsDEPRECATED)) + new_msg.valid = msg.valid + new_msg.logMonoTime = msg.logMonoTime + + # dict converts name enum into string representation + new_msg.onroadEvents = [log.OnroadEvent(**event.to_dict()) for event in msg.onroadEventsDEPRECATED] + ops.append((index, new_msg.as_reader())) + + return ops, [], [] + + +@migration(inputs=["driverMonitoringState"]) +def migrate_driverMonitoringState(msgs): + ops = [] + for index, msg in msgs: + msg = msg.as_builder() + # dict converts name enum into string representation + msg.driverMonitoringState.events = [log.OnroadEvent(**event.to_dict()) for event in + msg.driverMonitoringState.eventsDEPRECATED] + ops.append((index, msg.as_reader())) + + return ops, [], [] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 9aa61ab9c4..eb67f60cc0 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -fbf16d1e9b056830a12fcf29a5137e1fc0b01354 \ No newline at end of file +05570b52a90fb8bf092f7a2563d6019577e1aa5d \ No newline at end of file diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index f2afad82ee..f27e444dbe 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -13,7 +13,7 @@ from collections import Counter, defaultdict from functools import cached_property from pathlib import Path -from cereal import car +from cereal import log import cereal.messaging as messaging from cereal.services import SERVICE_LIST from openpilot.common.basedir import BASEDIR @@ -422,7 +422,7 @@ class TestOnroad: if msg.which() == "selfdriveState": startup_alert = msg.selfdriveState.alertText1 break - expected = EVENTS[car.OnroadEvent.EventName.startup][ET.PERMANENT].alert_text_1 + expected = EVENTS[log.OnroadEvent.EventName.startup][ET.PERMANENT].alert_text_1 assert startup_alert == expected, "wrong startup alert" def test_engagable(self): diff --git a/selfdrive/test/test_time_to_onroad.py b/selfdrive/test/test_time_to_onroad.py index d3692eabe2..e68386bb58 100644 --- a/selfdrive/test/test_time_to_onroad.py +++ b/selfdrive/test/test_time_to_onroad.py @@ -3,13 +3,13 @@ import pytest import time import subprocess -from cereal import car +from cereal import log import cereal.messaging as messaging from openpilot.common.basedir import BASEDIR from openpilot.common.timeout import Timeout from openpilot.selfdrive.test.helpers import set_params_enabled -EventName = car.OnroadEvent.EventName +EventName = log.OnroadEvent.EventName @pytest.mark.tici From 8149f7cb119045028ba57f877e1d16d58c2ae712 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 3 Oct 2024 16:40:24 -0700 Subject: [PATCH 207/214] move car.capnp to opendbc (#33722) * move car.capnp to opendbc * bump * do card * fix some more tests * rm helpers * format fp * more * whoops * bump * bump to master --- cereal/car.capnp | 723 +----------------- opendbc_repo | 2 +- selfdrive/car/card.py | 24 +- selfdrive/car/helpers.py | 74 -- selfdrive/car/tests/test_car_interfaces.py | 15 +- selfdrive/car/tests/test_models.py | 17 +- .../controls/lib/tests/test_latcontrol.py | 2 - .../controls/lib/tests/test_vehicle_model.py | 3 +- selfdrive/debug/format_fingerprints.py | 11 +- selfdrive/modeld/modeld.py | 3 +- selfdrive/modeld/tests/test_modeld.py | 3 +- .../test/process_replay/process_replay.py | 4 +- selfdrive/test/process_replay/ref_commit | 2 +- system/hardware/tici/tests/test_power_draw.py | 3 +- 14 files changed, 41 insertions(+), 845 deletions(-) mode change 100644 => 120000 cereal/car.capnp delete mode 100644 selfdrive/car/helpers.py diff --git a/cereal/car.capnp b/cereal/car.capnp deleted file mode 100644 index c8474f431b..0000000000 --- a/cereal/car.capnp +++ /dev/null @@ -1,722 +0,0 @@ -using Cxx = import "./include/c++.capnp"; -$Cxx.namespace("cereal"); - -@0x8e2af1e708af8b8d; - -# ******* events causing controls state machine transition ******* - -# IMPORTANT: This struct is to not be modified so old logs can be parsed -struct OnroadEventDEPRECATED @0x9b1657f34caf3ad3 { - name @0 :EventName; - - # event types - enable @1 :Bool; - noEntry @2 :Bool; - warning @3 :Bool; # alerts presented only when enabled or soft disabling - userDisable @4 :Bool; - softDisable @5 :Bool; - immediateDisable @6 :Bool; - preEnable @7 :Bool; - permanent @8 :Bool; # alerts presented regardless of openpilot state - overrideLateral @10 :Bool; - overrideLongitudinal @9 :Bool; - - enum EventName @0xbaa8c5d505f727de { - canError @0; - steerUnavailable @1; - wrongGear @4; - doorOpen @5; - seatbeltNotLatched @6; - espDisabled @7; - wrongCarMode @8; - steerTempUnavailable @9; - reverseGear @10; - buttonCancel @11; - buttonEnable @12; - pedalPressed @13; # exits active state - preEnableStandstill @73; # added during pre-enable state with brake - gasPressedOverride @108; # added when user is pressing gas with no disengage on gas - steerOverride @114; - cruiseDisabled @14; - speedTooLow @17; - outOfSpace @18; - overheat @19; - calibrationIncomplete @20; - calibrationInvalid @21; - calibrationRecalibrating @117; - controlsMismatch @22; - pcmEnable @23; - pcmDisable @24; - radarFault @26; - brakeHold @28; - parkBrake @29; - manualRestart @30; - joystickDebug @34; - longitudinalManeuver @124; - steerTempUnavailableSilent @35; - resumeRequired @36; - preDriverDistracted @37; - promptDriverDistracted @38; - driverDistracted @39; - preDriverUnresponsive @43; - promptDriverUnresponsive @44; - driverUnresponsive @45; - belowSteerSpeed @46; - lowBattery @48; - accFaulted @51; - sensorDataInvalid @52; - commIssue @53; - commIssueAvgFreq @109; - tooDistracted @54; - posenetInvalid @55; - soundsUnavailable @56; - preLaneChangeLeft @57; - preLaneChangeRight @58; - laneChange @59; - lowMemory @63; - stockAeb @64; - ldw @65; - carUnrecognized @66; - invalidLkasSetting @69; - speedTooHigh @70; - laneChangeBlocked @71; - relayMalfunction @72; - stockFcw @74; - startup @75; - startupNoCar @76; - startupNoControl @77; - startupNoSecOcKey @125; - startupMaster @78; - fcw @79; - steerSaturated @80; - belowEngageSpeed @84; - noGps @85; - wrongCruiseMode @87; - modeldLagging @89; - deviceFalling @90; - fanMalfunction @91; - cameraMalfunction @92; - cameraFrameRate @110; - processNotRunning @95; - dashcamMode @96; - selfdriveInitializing @98; - usbError @99; - cruiseMismatch @106; - canBusMissing @111; - selfdrivedLagging @112; - resumeBlocked @113; - steerTimeLimit @115; - vehicleSensorsInvalid @116; - locationdTemporaryError @103; - locationdPermanentError @118; - paramsdTemporaryError @50; - paramsdPermanentError @119; - actuatorsApiUnavailable @120; - espActive @121; - personalityChanged @122; - aeb @123; - - radarCanErrorDEPRECATED @15; - communityFeatureDisallowedDEPRECATED @62; - radarCommIssueDEPRECATED @67; - driverMonitorLowAccDEPRECATED @68; - gasUnavailableDEPRECATED @3; - dataNeededDEPRECATED @16; - modelCommIssueDEPRECATED @27; - ipasOverrideDEPRECATED @33; - geofenceDEPRECATED @40; - driverMonitorOnDEPRECATED @41; - driverMonitorOffDEPRECATED @42; - calibrationProgressDEPRECATED @47; - invalidGiraffeHondaDEPRECATED @49; - invalidGiraffeToyotaDEPRECATED @60; - internetConnectivityNeededDEPRECATED @61; - whitePandaUnsupportedDEPRECATED @81; - commIssueWarningDEPRECATED @83; - focusRecoverActiveDEPRECATED @86; - neosUpdateRequiredDEPRECATED @88; - modelLagWarningDEPRECATED @93; - startupOneplusDEPRECATED @82; - startupFuzzyFingerprintDEPRECATED @97; - noTargetDEPRECATED @25; - brakeUnavailableDEPRECATED @2; - plannerErrorDEPRECATED @32; - gpsMalfunctionDEPRECATED @94; - roadCameraErrorDEPRECATED @100; - driverCameraErrorDEPRECATED @101; - wideRoadCameraErrorDEPRECATED @102; - highCpuUsageDEPRECATED @105; - startupNoFwDEPRECATED @104; - lowSpeedLockoutDEPRECATED @31; - lkasDisabledDEPRECATED @107; - } -} - -# ******* main car state @ 100hz ******* -# all speeds in m/s - -struct CarState { - # CAN health - canValid @26 :Bool; # invalid counter/checksums - canTimeout @40 :Bool; # CAN bus dropped out - canErrorCounter @48 :UInt32; - - # car speed - vEgo @1 :Float32; # best estimate of speed - aEgo @16 :Float32; # best estimate of aCAN cceleration - vEgoRaw @17 :Float32; # unfiltered speed from wheel speed sensors - vEgoCluster @44 :Float32; # best estimate of speed shown on car's instrument cluster, used for UI - - vCruise @53 :Float32; # actual set speed - vCruiseCluster @54 :Float32; # set speed to display in the UI - - yawRate @22 :Float32; # best estimate of yaw rate - standstill @18 :Bool; - wheelSpeeds @2 :WheelSpeeds; - - # gas pedal, 0.0-1.0 - gas @3 :Float32; # this is user pedal only - gasPressed @4 :Bool; # this is user pedal only - - engineRpm @46 :Float32; - - # brake pedal, 0.0-1.0 - brake @5 :Float32; # this is user pedal only - brakePressed @6 :Bool; # this is user pedal only - regenBraking @45 :Bool; # this is user pedal only - parkingBrake @39 :Bool; - brakeHoldActive @38 :Bool; - - # steering wheel - steeringAngleDeg @7 :Float32; - steeringAngleOffsetDeg @37 :Float32; # Offset betweens sensors in case there multiple - steeringRateDeg @15 :Float32; - steeringTorque @8 :Float32; # TODO: standardize units - steeringTorqueEps @27 :Float32; # TODO: standardize units - steeringPressed @9 :Bool; # if the user is using the steering wheel - steerFaultTemporary @35 :Bool; # temporary EPS fault - steerFaultPermanent @36 :Bool; # permanent EPS fault - invalidLkasSetting @55 :Bool; # stock LKAS is incorrectly configured (i.e. on or off) - stockAeb @30 :Bool; - stockFcw @31 :Bool; - espDisabled @32 :Bool; - accFaulted @42 :Bool; - carFaultedNonCritical @47 :Bool; # some ECU is faulted, but car remains controllable - espActive @51 :Bool; - vehicleSensorsInvalid @52 :Bool; # invalid steering angle readings, etc. - lowSpeedAlert @56 :Bool; # lost steering control due to a dynamic min steering speed - - # cruise state - cruiseState @10 :CruiseState; - - # gear - gearShifter @14 :GearShifter; - - # button presses - buttonEvents @11 :List(ButtonEvent); - leftBlinker @20 :Bool; - rightBlinker @21 :Bool; - genericToggle @23 :Bool; - - # lock info - doorOpen @24 :Bool; - seatbeltUnlatched @25 :Bool; - - # clutch (manual transmission only) - clutchPressed @28 :Bool; - - # blindspot sensors - leftBlindspot @33 :Bool; # Is there something blocking the left lane change - rightBlindspot @34 :Bool; # Is there something blocking the right lane change - - fuelGauge @41 :Float32; # battery or fuel tank level from 0.0 to 1.0 - charging @43 :Bool; - - # process meta - cumLagMs @50 :Float32; - - struct WheelSpeeds { - # optional wheel speeds - fl @0 :Float32; - fr @1 :Float32; - rl @2 :Float32; - rr @3 :Float32; - } - - struct CruiseState { - enabled @0 :Bool; - speed @1 :Float32; - speedCluster @6 :Float32; # Set speed as shown on instrument cluster - available @2 :Bool; - speedOffset @3 :Float32; - standstill @4 :Bool; - nonAdaptive @5 :Bool; - } - - enum GearShifter { - unknown @0; - park @1; - drive @2; - neutral @3; - reverse @4; - sport @5; - low @6; - brake @7; - eco @8; - manumatic @9; - } - - # send on change - struct ButtonEvent { - pressed @0 :Bool; - type @1 :Type; - - enum Type { - unknown @0; - leftBlinker @1; - rightBlinker @2; - accelCruise @3; - decelCruise @4; - cancel @5; - altButton1 @6; - altButton2 @7; - mainCruise @8; - setCruise @9; - resumeCruise @10; - gapAdjustCruise @11; - } - } - - # deprecated - errorsDEPRECATED @0 :List(OnroadEventDEPRECATED.EventName); - brakeLightsDEPRECATED @19 :Bool; - steeringRateLimitedDEPRECATED @29 :Bool; - canMonoTimesDEPRECATED @12: List(UInt64); - canRcvTimeoutDEPRECATED @49 :Bool; - eventsDEPRECATED @13 :List(OnroadEventDEPRECATED); -} - -# ******* radar state @ 20hz ******* - -struct RadarData @0x888ad6581cf0aacb { - errors @0 :List(Error); - points @1 :List(RadarPoint); - - enum Error { - canError @0; - fault @1; - wrongConfig @2; - } - - # similar to LiveTracks - # is one timestamp valid for all? I think so - struct RadarPoint { - trackId @0 :UInt64; # no trackId reuse - - # these 3 are the minimum required - dRel @1 :Float32; # m from the front bumper of the car - yRel @2 :Float32; # m - vRel @3 :Float32; # m/s - - # these are optional and valid if they are not NaN - aRel @4 :Float32; # m/s^2 - yvRel @5 :Float32; # m/s - - # some radars flag measurements VS estimates - measured @6 :Bool; - } - - # deprecated - canMonoTimesDEPRECATED @2 :List(UInt64); -} - -# ******* car controls @ 100hz ******* - -struct CarControl { - # must be true for any actuator commands to work - enabled @0 :Bool; - latActive @11: Bool; - longActive @12: Bool; - - # Final actuator commands - actuators @6 :Actuators; - - # Blinker controls - leftBlinker @15: Bool; - rightBlinker @16: Bool; - - orientationNED @13 :List(Float32); - angularVelocity @14 :List(Float32); - - cruiseControl @4 :CruiseControl; - hudControl @5 :HUDControl; - - struct Actuators { - # lateral commands, mutually exclusive - steer @2: Float32; # [0.0, 1.0] - steeringAngleDeg @3: Float32; - curvature @7: Float32; - - # longitudinal commands - accel @4: Float32; # m/s^2 - longControlState @5: LongControlState; - - # these are only for logging the actual values sent to the car over CAN - gas @0: Float32; # [0.0, 1.0] - brake @1: Float32; # [0.0, 1.0] - steerOutputCan @8: Float32; # value sent over can to the car - speed @6: Float32; # m/s - - enum LongControlState @0xe40f3a917d908282{ - off @0; - pid @1; - stopping @2; - starting @3; - } - } - - struct CruiseControl { - cancel @0: Bool; - resume @1: Bool; - override @4: Bool; - speedOverrideDEPRECATED @2: Float32; - accelOverrideDEPRECATED @3: Float32; - } - - struct HUDControl { - speedVisible @0: Bool; - setSpeed @1: Float32; - lanesVisible @2: Bool; - leadVisible @3: Bool; - visualAlert @4: VisualAlert; - audibleAlert @5: AudibleAlert; - rightLaneVisible @6: Bool; - leftLaneVisible @7: Bool; - rightLaneDepart @8: Bool; - leftLaneDepart @9: Bool; - leadDistanceBars @10: Int8; # 1-3: 1 is closest, 3 is farthest. some ports may utilize 2-4 bars instead - - enum VisualAlert { - # these are the choices from the Honda - # map as good as you can for your car - none @0; - fcw @1; - steerRequired @2; - brakePressed @3; - wrongGear @4; - seatbeltUnbuckled @5; - speedTooHigh @6; - ldw @7; - } - - enum AudibleAlert { - none @0; - - engage @1; - disengage @2; - refuse @3; - - warningSoft @4; - warningImmediate @5; - - prompt @6; - promptRepeat @7; - promptDistracted @8; - } - } - - gasDEPRECATED @1 :Float32; - brakeDEPRECATED @2 :Float32; - steeringTorqueDEPRECATED @3 :Float32; - activeDEPRECATED @7 :Bool; - rollDEPRECATED @8 :Float32; - pitchDEPRECATED @9 :Float32; - actuatorsOutputDEPRECATED @10 :Actuators; -} - -struct CarOutput { - # Any car specific rate limits or quirks applied by - # the CarController are reflected in actuatorsOutput - # and matches what is sent to the car - actuatorsOutput @0 :CarControl.Actuators; -} - -# ****** car param ****** - -struct CarParams { - carName @0 :Text; - carFingerprint @1 :Text; - fuzzyFingerprint @55 :Bool; - - notCar @66 :Bool; # flag for non-car robotics platforms - - pcmCruise @3 :Bool; # is openpilot's state tied to the PCM's cruise state? - enableDsu @5 :Bool; # driving support unit - enableBsm @56 :Bool; # blind spot monitoring - flags @64 :UInt32; # flags for car specific quirks - experimentalLongitudinalAvailable @71 :Bool; - - minEnableSpeed @7 :Float32; - minSteerSpeed @8 :Float32; - safetyConfigs @62 :List(SafetyConfig); - alternativeExperience @65 :Int16; # panda flag for features like no disengage on gas - - # Car docs fields - maxLateralAccel @68 :Float32; - autoResumeSng @69 :Bool; # describes whether car can resume from a stop automatically - - # things about the car in the manual - mass @17 :Float32; # [kg] curb weight: all fluids no cargo - wheelbase @18 :Float32; # [m] distance from rear axle to front axle - centerToFront @19 :Float32; # [m] distance from center of mass to front axle - steerRatio @20 :Float32; # [] ratio of steering wheel angle to front wheel angle - steerRatioRear @21 :Float32; # [] ratio of steering wheel angle to rear wheel angle (usually 0) - - # things we can derive - rotationalInertia @22 :Float32; # [kg*m2] body rotational inertia - tireStiffnessFactor @72 :Float32; # scaling factor used in calculating tireStiffness[Front,Rear] - tireStiffnessFront @23 :Float32; # [N/rad] front tire coeff of stiff - tireStiffnessRear @24 :Float32; # [N/rad] rear tire coeff of stiff - - longitudinalTuning @25 :LongitudinalPIDTuning; - lateralParams @48 :LateralParams; - lateralTuning :union { - pid @26 :LateralPIDTuning; - indiDEPRECATED @27 :LateralINDITuning; - lqrDEPRECATED @40 :LateralLQRTuning; - torque @67 :LateralTorqueTuning; - } - - steerLimitAlert @28 :Bool; - steerLimitTimer @47 :Float32; # time before steerLimitAlert is issued - - vEgoStopping @29 :Float32; # Speed at which the car goes into stopping state - vEgoStarting @59 :Float32; # Speed at which the car goes into starting state - stoppingControl @31 :Bool; # Does the car allow full control even at lows speeds when stopping - steerControlType @34 :SteerControlType; - radarUnavailable @35 :Bool; # True when radar objects aren't visible on CAN or aren't parsed out - stopAccel @60 :Float32; # Required acceleration to keep vehicle stationary - stoppingDecelRate @52 :Float32; # m/s^2/s while trying to stop - startAccel @32 :Float32; # Required acceleration to get car moving - startingState @70 :Bool; # Does this car make use of special starting state - - steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds - longitudinalActuatorDelay @58 :Float32; # Gas/Brake actuator delay in seconds - openpilotLongitudinalControl @37 :Bool; # is openpilot doing the longitudinal control? - carVin @38 :Text; # VIN number queried during fingerprinting - dashcamOnly @41: Bool; - passive @73: Bool; # is openpilot in control? - transmissionType @43 :TransmissionType; - carFw @44 :List(CarFw); - - radarTimeStep @45: Float32 = 0.05; # time delta between radar updates, 20Hz is very standard - radarDelay @74 :Float32; - fingerprintSource @49: FingerprintSource; - networkLocation @50 :NetworkLocation; # Where Panda/C2 is integrated into the car's CAN network - - wheelSpeedFactor @63 :Float32; # Multiplier on wheels speeds to computer actual speeds - - secOcRequired @75 :Bool; # Car requires SecOC message authentication to operate - secOcKeyAvailable @76 :Bool; # Stored SecOC key loaded from params - - struct SafetyConfig { - safetyModel @0 :SafetyModel; - safetyParam @3 :UInt16; - safetyParamDEPRECATED @1 :Int16; - safetyParam2DEPRECATED @2 :UInt32; - } - - struct LateralParams { - torqueBP @0 :List(Int32); - torqueV @1 :List(Int32); - } - - struct LateralPIDTuning { - kpBP @0 :List(Float32); - kpV @1 :List(Float32); - kiBP @2 :List(Float32); - kiV @3 :List(Float32); - kf @4 :Float32; - } - - struct LateralTorqueTuning { - useSteeringAngle @0 :Bool; - kp @1 :Float32; - ki @2 :Float32; - friction @3 :Float32; - kf @4 :Float32; - steeringAngleDeadzoneDeg @5 :Float32; - latAccelFactor @6 :Float32; - latAccelOffset @7 :Float32; - } - - struct LongitudinalPIDTuning { - kpBP @0 :List(Float32); - kpV @1 :List(Float32); - kiBP @2 :List(Float32); - kiV @3 :List(Float32); - kf @6 :Float32; - deadzoneBPDEPRECATED @4 :List(Float32); - deadzoneVDEPRECATED @5 :List(Float32); - } - - struct LateralINDITuning { - outerLoopGainBP @4 :List(Float32); - outerLoopGainV @5 :List(Float32); - innerLoopGainBP @6 :List(Float32); - innerLoopGainV @7 :List(Float32); - timeConstantBP @8 :List(Float32); - timeConstantV @9 :List(Float32); - actuatorEffectivenessBP @10 :List(Float32); - actuatorEffectivenessV @11 :List(Float32); - - outerLoopGainDEPRECATED @0 :Float32; - innerLoopGainDEPRECATED @1 :Float32; - timeConstantDEPRECATED @2 :Float32; - actuatorEffectivenessDEPRECATED @3 :Float32; - } - - struct LateralLQRTuning { - scale @0 :Float32; - ki @1 :Float32; - dcGain @2 :Float32; - - # State space system - a @3 :List(Float32); - b @4 :List(Float32); - c @5 :List(Float32); - - k @6 :List(Float32); # LQR gain - l @7 :List(Float32); # Kalman gain - } - - enum SafetyModel { - silent @0; - hondaNidec @1; - toyota @2; - elm327 @3; - gm @4; - hondaBoschGiraffe @5; - ford @6; - cadillac @7; - hyundai @8; - chrysler @9; - tesla @10; - subaru @11; - gmPassive @12; - mazda @13; - nissan @14; - volkswagen @15; - toyotaIpas @16; - allOutput @17; - gmAscm @18; - noOutput @19; # like silent but without silent CAN TXs - hondaBosch @20; - volkswagenPq @21; - subaruPreglobal @22; # pre-Global platform - hyundaiLegacy @23; - hyundaiCommunity @24; - volkswagenMlb @25; - hongqi @26; - body @27; - hyundaiCanfd @28; - volkswagenMqbEvo @29; - chryslerCusw @30; - psa @31; - fcaGiorgio @32; - } - - enum SteerControlType { - torque @0; - angle @1; - - curvatureDEPRECATED @2; - } - - enum TransmissionType { - unknown @0; - automatic @1; # Traditional auto, including DSG - manual @2; # True "stick shift" only - direct @3; # Electric vehicle or other direct drive - cvt @4; - } - - struct CarFw { - ecu @0 :Ecu; - fwVersion @1 :Data; - address @2 :UInt32; - subAddress @3 :UInt8; - responseAddress @4 :UInt32; - request @5 :List(Data); - brand @6 :Text; - bus @7 :UInt8; - logging @8 :Bool; - obdMultiplexing @9 :Bool; - } - - enum Ecu { - eps @0; - abs @1; - fwdRadar @2; - fwdCamera @3; - engine @4; - unknown @5; - transmission @8; # Transmission Control Module - hybrid @18; # hybrid control unit, e.g. Chrysler's HCP, Honda's IMA Control Unit, Toyota's hybrid control computer - srs @9; # airbag - gateway @10; # can gateway - hud @11; # heads up display - combinationMeter @12; # instrument cluster - electricBrakeBooster @15; - shiftByWire @16; - adas @19; - cornerRadar @21; - hvac @20; - parkingAdas @7; # parking assist system ECU, e.g. Toyota's IPAS, Hyundai's RSPA, etc. - epb @22; # electronic parking brake - telematics @23; - body @24; # body control module - - # Toyota only - dsu @6; - - # Honda only - vsa @13; # Vehicle Stability Assist - programmedFuelInjection @14; - - debug @17; - } - - enum FingerprintSource { - can @0; - fw @1; - fixed @2; - } - - enum NetworkLocation { - fwdCamera @0; # Standard/default integration at LKAS camera - gateway @1; # Integration at vehicle's CAN gateway - } - - enableGasInterceptorDEPRECATED @2 :Bool; - enableCameraDEPRECATED @4 :Bool; - enableApgsDEPRECATED @6 :Bool; - steerRateCostDEPRECATED @33 :Float32; - isPandaBlackDEPRECATED @39 :Bool; - hasStockCameraDEPRECATED @57 :Bool; - safetyParamDEPRECATED @10 :Int16; - safetyModelDEPRECATED @9 :SafetyModel; - safetyModelPassiveDEPRECATED @42 :SafetyModel = silent; - minSpeedCanDEPRECATED @51 :Float32; - communityFeatureDEPRECATED @46: Bool; - startingAccelRateDEPRECATED @53 :Float32; - steerMaxBPDEPRECATED @11 :List(Float32); - steerMaxVDEPRECATED @12 :List(Float32); - gasMaxBPDEPRECATED @13 :List(Float32); - gasMaxVDEPRECATED @14 :List(Float32); - brakeMaxBPDEPRECATED @15 :List(Float32); - brakeMaxVDEPRECATED @16 :List(Float32); - directAccelControlDEPRECATED @30 :Bool; - maxSteeringAngleDegDEPRECATED @54 :Float32; - longitudinalActuatorDelayLowerBoundDEPRECATED @61 :Float32; -} diff --git a/cereal/car.capnp b/cereal/car.capnp new file mode 120000 index 0000000000..4bc7f89b1f --- /dev/null +++ b/cereal/car.capnp @@ -0,0 +1 @@ +../opendbc_repo/opendbc/car/car.capnp \ No newline at end of file diff --git a/opendbc_repo b/opendbc_repo index a363ce1ff4..ff2ac79e07 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit a363ce1ff452e63f2e49938508d97aece4ba6a3e +Subproject commit ff2ac79e07c2d9021c2fd4fc886ca61c81cd2694 diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 0afd0e7323..9bd03bad80 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -21,7 +21,6 @@ from opendbc.car.interfaces import CarInterfaceBase, RadarInterfaceBase from openpilot.selfdrive.pandad import can_capnp_to_list, can_list_to_can_capnp from openpilot.selfdrive.car.cruise import VCruiseHelper from openpilot.selfdrive.car.car_specific import MockCarState -from openpilot.selfdrive.car.helpers import convert_carControl, convert_to_capnp REPLAY = "REPLAY" in os.environ @@ -63,8 +62,7 @@ def can_comm_callbacks(logcan: messaging.SubSocket, sendcan: messaging.PubSocket class Car: CI: CarInterfaceBase RI: RadarInterfaceBase - CP: structs.CarParams - CP_capnp: car.CarParams + CP: car.CarParams def __init__(self, CI=None, RI=None) -> None: self.can_sock = messaging.sub_sock('can', timeout=20) @@ -144,9 +142,7 @@ class Car: self.params.put("CarParamsPrevRoute", prev_cp) # Write CarParams for controls and radard - # convert to pycapnp representation for caching and logging - self.CP_capnp = convert_to_capnp(self.CP) - cp_bytes = self.CP_capnp.to_bytes() + cp_bytes = self.CP.to_bytes() self.params.put("CarParams", cp_bytes) self.params.put_nonblocking("CarParamsCache", cp_bytes) self.params.put_nonblocking("CarParamsPersistent", cp_bytes) @@ -160,19 +156,19 @@ class Car: # card is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) - def state_update(self) -> tuple[car.CarState, structs.RadarData | None]: + def state_update(self) -> tuple[car.CarState, structs.RadarDataT | None]: """carState update loop, driven by can""" can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) can_list = can_capnp_to_list(can_strs) # Update carState from CAN - CS = convert_to_capnp(self.CI.update(can_list)) + CS = self.CI.update(can_list) if self.CP.carName == 'mock': CS = self.mock_carstate.update(CS) # Update radar tracks from CAN - RD: structs.RadarData | None = self.RI.update(can_list) + RD: structs.RadarDataT | None = self.RI.update(can_list) self.sm.update(0) @@ -192,20 +188,20 @@ class Car: return CS, RD - def state_publish(self, CS: car.CarState, RD: structs.RadarData | None): + def state_publish(self, CS: car.CarState, RD: structs.RadarDataT | None): """carState and carParams publish loop""" # carParams - logged every 50 seconds (> 1 per segment) if self.sm.frame % int(50. / DT_CTRL) == 0: cp_send = messaging.new_message('carParams') cp_send.valid = True - cp_send.carParams = self.CP_capnp + cp_send.carParams = self.CP self.pm.send('carParams', cp_send) # publish new carOutput co_send = messaging.new_message('carOutput') co_send.valid = self.sm.all_checks(['carControl']) - co_send.carOutput.actuatorsOutput = convert_to_capnp(self.last_actuators_output) + co_send.carOutput.actuatorsOutput = self.last_actuators_output self.pm.send('carOutput', co_send) # kick off controlsd step while we actuate the latest carControl packet @@ -219,7 +215,7 @@ class Car: if RD is not None: tracks_msg = messaging.new_message('liveTracks') tracks_msg.valid = len(RD.errors) == 0 - tracks_msg.liveTracks = convert_to_capnp(RD) + tracks_msg.liveTracks = RD self.pm.send('liveTracks', tracks_msg) def controls_update(self, CS: car.CarState, CC: car.CarControl): @@ -235,7 +231,7 @@ class Car: if self.sm.all_alive(['carControl']): # send car controls over can now_nanos = self.can_log_mono_time if REPLAY else int(time.monotonic() * 1e9) - self.last_actuators_output, can_sends = self.CI.apply(convert_carControl(CC), now_nanos) + self.last_actuators_output, can_sends = self.CI.apply(CC, now_nanos) self.pm.send('sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid)) self.CC_prev = CC diff --git a/selfdrive/car/helpers.py b/selfdrive/car/helpers.py deleted file mode 100644 index 75e1c66d24..0000000000 --- a/selfdrive/car/helpers.py +++ /dev/null @@ -1,74 +0,0 @@ -import capnp -from typing import Any - -from cereal import car -from opendbc.car import structs - -_FIELDS = '__dataclass_fields__' # copy of dataclasses._FIELDS - - -def is_dataclass(obj): - """Similar to dataclasses.is_dataclass without instance type check checking""" - return hasattr(obj, _FIELDS) - - -def _asdictref_inner(obj) -> dict[str, Any] | Any: - if is_dataclass(obj): - ret = {} - for field in getattr(obj, _FIELDS): # similar to dataclasses.fields() - ret[field] = _asdictref_inner(getattr(obj, field)) - return ret - elif isinstance(obj, (tuple, list)): - return type(obj)(_asdictref_inner(v) for v in obj) - else: - return obj - - -def asdictref(obj) -> dict[str, Any]: - """ - Similar to dataclasses.asdict without recursive type checking and copy.deepcopy - Note that the resulting dict will contain references to the original struct as a result - """ - if not is_dataclass(obj): - raise TypeError("asdictref() should be called on dataclass instances") - - return _asdictref_inner(obj) - - -def convert_to_capnp(struct: structs.CarParams | structs.CarState | structs.CarControl.Actuators | structs.RadarData) -> capnp.lib.capnp._DynamicStructBuilder: - struct_dict = asdictref(struct) - - if isinstance(struct, structs.CarParams): - del struct_dict['lateralTuning'] - struct_capnp = car.CarParams.new_message(**struct_dict) - - # this is the only union, special handling - which = struct.lateralTuning.which() - struct_capnp.lateralTuning.init(which) - lateralTuning_dict = asdictref(getattr(struct.lateralTuning, which)) - setattr(struct_capnp.lateralTuning, which, lateralTuning_dict) - elif isinstance(struct, structs.CarState): - struct_capnp = car.CarState.new_message(**struct_dict) - elif isinstance(struct, structs.CarControl.Actuators): - struct_capnp = car.CarControl.Actuators.new_message(**struct_dict) - elif isinstance(struct, structs.RadarData): - struct_capnp = car.RadarData.new_message(**struct_dict) - else: - raise ValueError(f"Unsupported struct type: {type(struct)}") - - return struct_capnp - - -def convert_carControl(struct: capnp.lib.capnp._DynamicStructReader) -> structs.CarControl: - # TODO: recursively handle any car struct as needed - def remove_deprecated(s: dict) -> dict: - return {k: v for k, v in s.items() if not k.endswith('DEPRECATED')} - - struct_dict = struct.to_dict() - struct_dataclass = structs.CarControl(**remove_deprecated({k: v for k, v in struct_dict.items() if not isinstance(k, dict)})) - - struct_dataclass.actuators = structs.CarControl.Actuators(**remove_deprecated(struct_dict.get('actuators', {}))) - struct_dataclass.cruiseControl = structs.CarControl.CruiseControl(**remove_deprecated(struct_dict.get('cruiseControl', {}))) - struct_dataclass.hudControl = structs.CarControl.HUDControl(**remove_deprecated(struct_dict.get('hudControl', {}))) - - return struct_dataclass diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 66cf0dc696..4370ea141b 100644 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -12,7 +12,6 @@ from opendbc.car.tests.test_car_interfaces import get_fuzzy_car_interface_args from opendbc.car.fingerprints import all_known_cars from opendbc.car.fw_versions import FW_VERSIONS, FW_QUERY_CONFIGS from opendbc.car.mock.values import CAR as MOCK -from openpilot.selfdrive.car.card import convert_carControl, convert_to_capnp from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque @@ -41,6 +40,7 @@ class TestCarInterfaces: car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'], experimental_long=args['experimental_long'], docs=False) + car_params = car_params.as_reader() car_interface = CarInterface(car_params, CarController, CarState) assert car_params assert car_interface @@ -72,7 +72,7 @@ class TestCarInterfaces: # Run car interface now_nanos = 0 CC = car.CarControl.new_message(**cc_msg) - CC = convert_carControl(CC.as_reader()) + CC = CC.as_reader() for _ in range(10): car_interface.update([]) car_interface.apply(CC, now_nanos) @@ -80,7 +80,7 @@ class TestCarInterfaces: CC = car.CarControl.new_message(**cc_msg) CC.enabled = True - CC = convert_carControl(CC.as_reader()) + CC = CC.as_reader() for _ in range(10): car_interface.update([]) car_interface.apply(CC, now_nanos) @@ -89,11 +89,10 @@ class TestCarInterfaces: # Test controller initialization # TODO: wait until card refactor is merged to run controller a few times, # hypothesis also slows down significantly with just one more message draw - car_params_capnp = convert_to_capnp(car_params).as_reader() - LongControl(car_params_capnp) + LongControl(car_params) if car_params.steerControlType == CarParams.SteerControlType.angle: - LatControlAngle(car_params_capnp, car_interface) + LatControlAngle(car_params, car_interface) elif car_params.lateralTuning.which() == 'pid': - LatControlPID(car_params_capnp, car_interface) + LatControlPID(car_params, car_interface) elif car_params.lateralTuning.which() == 'torque': - LatControlTorque(car_params_capnp, car_interface) + LatControlTorque(car_params, car_interface) diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index ef54631e54..72f511b7ce 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -1,6 +1,4 @@ import capnp -import copy -import dataclasses import os import pytest import random @@ -20,7 +18,6 @@ from opendbc.car.car_helpers import FRAME_FINGERPRINT, interfaces from opendbc.car.honda.values import CAR as HONDA, HondaFlags from opendbc.car.values import Platform from opendbc.car.tests.routes import non_tested_cars, routes, CarTestRoute -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.selfdrived.events import ET from openpilot.selfdrive.selfdrived.selfdrived import SelfdriveD from openpilot.selfdrive.pandad import can_capnp_to_list @@ -187,7 +184,7 @@ class TestCarModelBase(unittest.TestCase): del cls.can_msgs def setUp(self): - self.CI = self.CarInterface(copy.deepcopy(self.CP), self.CarController, self.CarState) + self.CI = self.CarInterface(self.CP.copy(), self.CarController, self.CarState) assert self.CI Params().put_bool("OpenpilotEnabledToggle", self.openpilot_enabled) @@ -195,7 +192,7 @@ class TestCarModelBase(unittest.TestCase): # TODO: check safetyModel is in release panda build self.safety = libpanda_py.libpanda - cfg = car.CarParams.SafetyConfig(**dataclasses.asdict(self.CP.safetyConfigs[-1])) + cfg = self.CP.safetyConfigs[-1] set_status = self.safety.set_safety_hooks(cfg.safetyModel.raw, cfg.safetyParam) self.assertEqual(0, set_status, f"failed to set safetyModel {cfg}") self.safety.init_tests() @@ -220,7 +217,7 @@ class TestCarModelBase(unittest.TestCase): # TODO: also check for checksum violations from can parser can_invalid_cnt = 0 can_valid = False - CC = structs.CarControl() + CC = structs.CarControl().as_reader() for i, msg in enumerate(self.can_msgs): CS = self.CI.update(can_capnp_to_list((msg.as_builder().to_bytes(),))) @@ -312,17 +309,17 @@ class TestCarModelBase(unittest.TestCase): # Make sure we can send all messages while inactive CC = structs.CarControl() - test_car_controller(CC) + test_car_controller(CC.as_reader()) # Test cancel + general messages (controls_allowed=False & cruise_engaged=True) self.safety.set_cruise_engaged_prev(True) CC = structs.CarControl(cruiseControl=structs.CarControl.CruiseControl(cancel=True)) - test_car_controller(CC) + test_car_controller(CC.as_reader()) # Test resume + general messages (controls_allowed=True & cruise_engaged=True) self.safety.set_controls_allowed(True) CC = structs.CarControl(cruiseControl=structs.CarControl.CruiseControl(resume=True)) - test_car_controller(CC) + test_car_controller(CC.as_reader()) # Skip stdout/stderr capture with pytest, causes elevated memory usage @pytest.mark.nocapture @@ -409,7 +406,7 @@ class TestCarModelBase(unittest.TestCase): selfdrived = SelfdriveD(CP=self.CP) selfdrived.initialized = True for idx, can in enumerate(self.can_msgs): - CS = convert_to_capnp(self.CI.update(can_capnp_to_list((can.as_builder().to_bytes(), )))) + CS = self.CI.update(can_capnp_to_list((can.as_builder().to_bytes(), ))).as_reader() for msg in filter(lambda m: m.src in range(64), can.can): to_send = libpanda_py.make_CANPacket(msg.address, msg.src % 4, msg.dat) ret = self.safety.safety_rx_hook(to_send) diff --git a/selfdrive/controls/lib/tests/test_latcontrol.py b/selfdrive/controls/lib/tests/test_latcontrol.py index c8c8d02751..ba4bd0faec 100644 --- a/selfdrive/controls/lib/tests/test_latcontrol.py +++ b/selfdrive/controls/lib/tests/test_latcontrol.py @@ -5,7 +5,6 @@ from opendbc.car.car_helpers import interfaces from opendbc.car.honda.values import CAR as HONDA from opendbc.car.toyota.values import CAR as TOYOTA from opendbc.car.nissan.values import CAR as NISSAN -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle @@ -21,7 +20,6 @@ class TestLatControl: CarInterface, CarController, CarState, RadarInterface = interfaces[car_name] CP = CarInterface.get_non_essential_params(car_name) CI = CarInterface(CP, CarController, CarState) - CP = convert_to_capnp(CP) VM = VehicleModel(CP) controller = controller(CP.as_reader(), CI) diff --git a/selfdrive/controls/lib/tests/test_vehicle_model.py b/selfdrive/controls/lib/tests/test_vehicle_model.py index b58bdbe522..d15519a866 100644 --- a/selfdrive/controls/lib/tests/test_vehicle_model.py +++ b/selfdrive/controls/lib/tests/test_vehicle_model.py @@ -5,14 +5,13 @@ import numpy as np from opendbc.car.honda.interface import CarInterface from opendbc.car.honda.values import CAR -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel, dyn_ss_sol, create_dyn_state_matrices class TestVehicleModel: def setup_method(self): CP = CarInterface.get_non_essential_params(CAR.HONDA_CIVIC) - self.VM = VehicleModel(convert_to_capnp(CP)) + self.VM = VehicleModel(CP) def test_round_trip_yaw_rate(self): # TODO: fix VM to work at zero speed diff --git a/selfdrive/debug/format_fingerprints.py b/selfdrive/debug/format_fingerprints.py index ae1ed06b75..7207bd1ef1 100755 --- a/selfdrive/debug/format_fingerprints.py +++ b/selfdrive/debug/format_fingerprints.py @@ -2,12 +2,16 @@ import jinja2 import os +from cereal import car from openpilot.common.basedir import BASEDIR from opendbc.car.interfaces import get_interface_attr +Ecu = car.CarParams.Ecu + CARS = get_interface_attr('CAR') FW_VERSIONS = get_interface_attr('FW_VERSIONS') FINGERPRINTS = get_interface_attr('FINGERPRINTS') +ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} FINGERPRINTS_PY_TEMPLATE = jinja2.Template(""" {%- if FINGERPRINTS[brand] %} @@ -45,7 +49,7 @@ FW_VERSIONS{% if not FW_VERSIONS[brand] %}: dict[str, dict[tuple, list[bytes]]]{ {% for car, _ in FW_VERSIONS[brand].items() %} CAR.{{car.name}}: { {% for key, fw_versions in FW_VERSIONS[brand][car].items() %} - (Ecu.{{key[0]}}, 0x{{"%0x" | format(key[1] | int)}}, \ + (Ecu.{{ECU_NAME[key[0]]}}, 0x{{"%0x" | format(key[1] | int)}}, \ {% if key[2] %}0x{{"%0x" | format(key[2] | int)}}{% else %}{{key[2]}}{% endif %}): [ {% for fw_version in (fw_versions + extra_fw_versions.get(car, {}).get(key, [])) | unique | sort %} {{fw_version}}, @@ -67,8 +71,9 @@ def format_brand_fw_versions(brand, extra_fw_versions: None | dict[str, dict[tup comments = [line for line in f.readlines() if line.startswith("#") and "noqa" not in line] with open(fingerprints_file, "w") as f: - f.write(FINGERPRINTS_PY_TEMPLATE.render(brand=brand, comments=comments, FINGERPRINTS=FINGERPRINTS, - FW_VERSIONS=FW_VERSIONS, extra_fw_versions=extra_fw_versions)) + f.write(FINGERPRINTS_PY_TEMPLATE.render(brand=brand, comments=comments, ECU_NAME=ECU_NAME, + FINGERPRINTS=FINGERPRINTS, FW_VERSIONS=FW_VERSIONS, + extra_fw_versions=extra_fw_versions)) if __name__ == "__main__": diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index ec258f42f0..4e91d32400 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -17,7 +17,6 @@ from openpilot.common.realtime import config_realtime_process from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.transformations.model import get_warp_matrix from openpilot.system import sentry -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.desire_helper import DesireHelper from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime from openpilot.selfdrive.modeld.parse_model_outputs import Parser @@ -184,7 +183,7 @@ def main(demo=False): if demo: - CP = convert_to_capnp(get_demo_car_params()) + CP = get_demo_car_params() else: CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) cloudlog.info("modeld got CarParams: %s", CP.carName) diff --git a/selfdrive/modeld/tests/test_modeld.py b/selfdrive/modeld/tests/test_modeld.py index 1bf2977a91..145ba31ade 100644 --- a/selfdrive/modeld/tests/test_modeld.py +++ b/selfdrive/modeld/tests/test_modeld.py @@ -7,7 +7,6 @@ from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.params import Params from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.realtime import DT_MDL -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.system.manager.process_config import managed_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state @@ -24,7 +23,7 @@ class TestModeld: self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, False, CAM.width, CAM.height) self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, False, CAM.width, CAM.height) self.vipc_server.start_listener() - Params().put("CarParams", convert_to_capnp(get_demo_car_params()).to_bytes()) + Params().put("CarParams", get_demo_car_params().to_bytes()) self.sm = messaging.SubMaster(['modelV2', 'cameraOdometry']) self.pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState', 'liveCalibration']) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index b6d5ba6afd..9abdb6476a 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -24,7 +24,7 @@ from openpilot.common.prefix import OpenpilotPrefix from openpilot.common.timeout import Timeout from openpilot.common.realtime import DT_CTRL from panda.python import ALTERNATIVE_EXPERIENCE -from openpilot.selfdrive.car.card import can_comm_callbacks, convert_to_capnp +from openpilot.selfdrive.car.card import can_comm_callbacks from openpilot.system.manager.process_config import managed_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state, available_streams from openpilot.selfdrive.test.process_replay.migration import migrate_all @@ -370,7 +370,7 @@ def get_car_params_callback(rc, pm, msgs, fingerprint): if not params.get_bool("DisengageOnAccelerator"): CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS - params.put("CarParams", convert_to_capnp(CP).to_bytes()) + params.put("CarParams", CP.to_bytes()) def selfdrived_rcv_callback(msg, cfg, frame): diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index eb67f60cc0..67d865a654 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -05570b52a90fb8bf092f7a2563d6019577e1aa5d \ No newline at end of file +cbe81fea9b820b8dd38667866aac72a8a0dae966 \ No newline at end of file diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index 3b9d65b85a..c4ff080fa4 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -10,7 +10,6 @@ from cereal.services import SERVICE_LIST from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.mock import mock_messages from openpilot.common.params import Params -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.system.hardware.tici.power_monitor import get_power from openpilot.system.manager.process_config import managed_processes from openpilot.system.manager.manager import manager_cleanup @@ -43,7 +42,7 @@ PROCS = [ class TestPowerDraw: def setup_method(self): - Params().put("CarParams", convert_to_capnp(get_demo_car_params()).to_bytes()) + Params().put("CarParams", get_demo_car_params()).to_bytes() # wait a bit for power save to disable time.sleep(5) From 9d52a5b485fc45d3b05f2021bbf1bd1c4f15c83e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 3 Oct 2024 16:57:45 -0700 Subject: [PATCH 208/214] Revert "move car.capnp to opendbc" (#33725) Revert "move car.capnp to opendbc (#33722)" This reverts commit 8149f7cb119045028ba57f877e1d16d58c2ae712. --- cereal/car.capnp | 723 +++++++++++++++++- opendbc_repo | 2 +- selfdrive/car/card.py | 24 +- selfdrive/car/helpers.py | 74 ++ selfdrive/car/tests/test_car_interfaces.py | 15 +- selfdrive/car/tests/test_models.py | 17 +- .../controls/lib/tests/test_latcontrol.py | 2 + .../controls/lib/tests/test_vehicle_model.py | 3 +- selfdrive/debug/format_fingerprints.py | 11 +- selfdrive/modeld/modeld.py | 3 +- selfdrive/modeld/tests/test_modeld.py | 3 +- .../test/process_replay/process_replay.py | 4 +- selfdrive/test/process_replay/ref_commit | 2 +- system/hardware/tici/tests/test_power_draw.py | 3 +- 14 files changed, 845 insertions(+), 41 deletions(-) mode change 120000 => 100644 cereal/car.capnp create mode 100644 selfdrive/car/helpers.py diff --git a/cereal/car.capnp b/cereal/car.capnp deleted file mode 120000 index 4bc7f89b1f..0000000000 --- a/cereal/car.capnp +++ /dev/null @@ -1 +0,0 @@ -../opendbc_repo/opendbc/car/car.capnp \ No newline at end of file diff --git a/cereal/car.capnp b/cereal/car.capnp new file mode 100644 index 0000000000..c8474f431b --- /dev/null +++ b/cereal/car.capnp @@ -0,0 +1,722 @@ +using Cxx = import "./include/c++.capnp"; +$Cxx.namespace("cereal"); + +@0x8e2af1e708af8b8d; + +# ******* events causing controls state machine transition ******* + +# IMPORTANT: This struct is to not be modified so old logs can be parsed +struct OnroadEventDEPRECATED @0x9b1657f34caf3ad3 { + name @0 :EventName; + + # event types + enable @1 :Bool; + noEntry @2 :Bool; + warning @3 :Bool; # alerts presented only when enabled or soft disabling + userDisable @4 :Bool; + softDisable @5 :Bool; + immediateDisable @6 :Bool; + preEnable @7 :Bool; + permanent @8 :Bool; # alerts presented regardless of openpilot state + overrideLateral @10 :Bool; + overrideLongitudinal @9 :Bool; + + enum EventName @0xbaa8c5d505f727de { + canError @0; + steerUnavailable @1; + wrongGear @4; + doorOpen @5; + seatbeltNotLatched @6; + espDisabled @7; + wrongCarMode @8; + steerTempUnavailable @9; + reverseGear @10; + buttonCancel @11; + buttonEnable @12; + pedalPressed @13; # exits active state + preEnableStandstill @73; # added during pre-enable state with brake + gasPressedOverride @108; # added when user is pressing gas with no disengage on gas + steerOverride @114; + cruiseDisabled @14; + speedTooLow @17; + outOfSpace @18; + overheat @19; + calibrationIncomplete @20; + calibrationInvalid @21; + calibrationRecalibrating @117; + controlsMismatch @22; + pcmEnable @23; + pcmDisable @24; + radarFault @26; + brakeHold @28; + parkBrake @29; + manualRestart @30; + joystickDebug @34; + longitudinalManeuver @124; + steerTempUnavailableSilent @35; + resumeRequired @36; + preDriverDistracted @37; + promptDriverDistracted @38; + driverDistracted @39; + preDriverUnresponsive @43; + promptDriverUnresponsive @44; + driverUnresponsive @45; + belowSteerSpeed @46; + lowBattery @48; + accFaulted @51; + sensorDataInvalid @52; + commIssue @53; + commIssueAvgFreq @109; + tooDistracted @54; + posenetInvalid @55; + soundsUnavailable @56; + preLaneChangeLeft @57; + preLaneChangeRight @58; + laneChange @59; + lowMemory @63; + stockAeb @64; + ldw @65; + carUnrecognized @66; + invalidLkasSetting @69; + speedTooHigh @70; + laneChangeBlocked @71; + relayMalfunction @72; + stockFcw @74; + startup @75; + startupNoCar @76; + startupNoControl @77; + startupNoSecOcKey @125; + startupMaster @78; + fcw @79; + steerSaturated @80; + belowEngageSpeed @84; + noGps @85; + wrongCruiseMode @87; + modeldLagging @89; + deviceFalling @90; + fanMalfunction @91; + cameraMalfunction @92; + cameraFrameRate @110; + processNotRunning @95; + dashcamMode @96; + selfdriveInitializing @98; + usbError @99; + cruiseMismatch @106; + canBusMissing @111; + selfdrivedLagging @112; + resumeBlocked @113; + steerTimeLimit @115; + vehicleSensorsInvalid @116; + locationdTemporaryError @103; + locationdPermanentError @118; + paramsdTemporaryError @50; + paramsdPermanentError @119; + actuatorsApiUnavailable @120; + espActive @121; + personalityChanged @122; + aeb @123; + + radarCanErrorDEPRECATED @15; + communityFeatureDisallowedDEPRECATED @62; + radarCommIssueDEPRECATED @67; + driverMonitorLowAccDEPRECATED @68; + gasUnavailableDEPRECATED @3; + dataNeededDEPRECATED @16; + modelCommIssueDEPRECATED @27; + ipasOverrideDEPRECATED @33; + geofenceDEPRECATED @40; + driverMonitorOnDEPRECATED @41; + driverMonitorOffDEPRECATED @42; + calibrationProgressDEPRECATED @47; + invalidGiraffeHondaDEPRECATED @49; + invalidGiraffeToyotaDEPRECATED @60; + internetConnectivityNeededDEPRECATED @61; + whitePandaUnsupportedDEPRECATED @81; + commIssueWarningDEPRECATED @83; + focusRecoverActiveDEPRECATED @86; + neosUpdateRequiredDEPRECATED @88; + modelLagWarningDEPRECATED @93; + startupOneplusDEPRECATED @82; + startupFuzzyFingerprintDEPRECATED @97; + noTargetDEPRECATED @25; + brakeUnavailableDEPRECATED @2; + plannerErrorDEPRECATED @32; + gpsMalfunctionDEPRECATED @94; + roadCameraErrorDEPRECATED @100; + driverCameraErrorDEPRECATED @101; + wideRoadCameraErrorDEPRECATED @102; + highCpuUsageDEPRECATED @105; + startupNoFwDEPRECATED @104; + lowSpeedLockoutDEPRECATED @31; + lkasDisabledDEPRECATED @107; + } +} + +# ******* main car state @ 100hz ******* +# all speeds in m/s + +struct CarState { + # CAN health + canValid @26 :Bool; # invalid counter/checksums + canTimeout @40 :Bool; # CAN bus dropped out + canErrorCounter @48 :UInt32; + + # car speed + vEgo @1 :Float32; # best estimate of speed + aEgo @16 :Float32; # best estimate of aCAN cceleration + vEgoRaw @17 :Float32; # unfiltered speed from wheel speed sensors + vEgoCluster @44 :Float32; # best estimate of speed shown on car's instrument cluster, used for UI + + vCruise @53 :Float32; # actual set speed + vCruiseCluster @54 :Float32; # set speed to display in the UI + + yawRate @22 :Float32; # best estimate of yaw rate + standstill @18 :Bool; + wheelSpeeds @2 :WheelSpeeds; + + # gas pedal, 0.0-1.0 + gas @3 :Float32; # this is user pedal only + gasPressed @4 :Bool; # this is user pedal only + + engineRpm @46 :Float32; + + # brake pedal, 0.0-1.0 + brake @5 :Float32; # this is user pedal only + brakePressed @6 :Bool; # this is user pedal only + regenBraking @45 :Bool; # this is user pedal only + parkingBrake @39 :Bool; + brakeHoldActive @38 :Bool; + + # steering wheel + steeringAngleDeg @7 :Float32; + steeringAngleOffsetDeg @37 :Float32; # Offset betweens sensors in case there multiple + steeringRateDeg @15 :Float32; + steeringTorque @8 :Float32; # TODO: standardize units + steeringTorqueEps @27 :Float32; # TODO: standardize units + steeringPressed @9 :Bool; # if the user is using the steering wheel + steerFaultTemporary @35 :Bool; # temporary EPS fault + steerFaultPermanent @36 :Bool; # permanent EPS fault + invalidLkasSetting @55 :Bool; # stock LKAS is incorrectly configured (i.e. on or off) + stockAeb @30 :Bool; + stockFcw @31 :Bool; + espDisabled @32 :Bool; + accFaulted @42 :Bool; + carFaultedNonCritical @47 :Bool; # some ECU is faulted, but car remains controllable + espActive @51 :Bool; + vehicleSensorsInvalid @52 :Bool; # invalid steering angle readings, etc. + lowSpeedAlert @56 :Bool; # lost steering control due to a dynamic min steering speed + + # cruise state + cruiseState @10 :CruiseState; + + # gear + gearShifter @14 :GearShifter; + + # button presses + buttonEvents @11 :List(ButtonEvent); + leftBlinker @20 :Bool; + rightBlinker @21 :Bool; + genericToggle @23 :Bool; + + # lock info + doorOpen @24 :Bool; + seatbeltUnlatched @25 :Bool; + + # clutch (manual transmission only) + clutchPressed @28 :Bool; + + # blindspot sensors + leftBlindspot @33 :Bool; # Is there something blocking the left lane change + rightBlindspot @34 :Bool; # Is there something blocking the right lane change + + fuelGauge @41 :Float32; # battery or fuel tank level from 0.0 to 1.0 + charging @43 :Bool; + + # process meta + cumLagMs @50 :Float32; + + struct WheelSpeeds { + # optional wheel speeds + fl @0 :Float32; + fr @1 :Float32; + rl @2 :Float32; + rr @3 :Float32; + } + + struct CruiseState { + enabled @0 :Bool; + speed @1 :Float32; + speedCluster @6 :Float32; # Set speed as shown on instrument cluster + available @2 :Bool; + speedOffset @3 :Float32; + standstill @4 :Bool; + nonAdaptive @5 :Bool; + } + + enum GearShifter { + unknown @0; + park @1; + drive @2; + neutral @3; + reverse @4; + sport @5; + low @6; + brake @7; + eco @8; + manumatic @9; + } + + # send on change + struct ButtonEvent { + pressed @0 :Bool; + type @1 :Type; + + enum Type { + unknown @0; + leftBlinker @1; + rightBlinker @2; + accelCruise @3; + decelCruise @4; + cancel @5; + altButton1 @6; + altButton2 @7; + mainCruise @8; + setCruise @9; + resumeCruise @10; + gapAdjustCruise @11; + } + } + + # deprecated + errorsDEPRECATED @0 :List(OnroadEventDEPRECATED.EventName); + brakeLightsDEPRECATED @19 :Bool; + steeringRateLimitedDEPRECATED @29 :Bool; + canMonoTimesDEPRECATED @12: List(UInt64); + canRcvTimeoutDEPRECATED @49 :Bool; + eventsDEPRECATED @13 :List(OnroadEventDEPRECATED); +} + +# ******* radar state @ 20hz ******* + +struct RadarData @0x888ad6581cf0aacb { + errors @0 :List(Error); + points @1 :List(RadarPoint); + + enum Error { + canError @0; + fault @1; + wrongConfig @2; + } + + # similar to LiveTracks + # is one timestamp valid for all? I think so + struct RadarPoint { + trackId @0 :UInt64; # no trackId reuse + + # these 3 are the minimum required + dRel @1 :Float32; # m from the front bumper of the car + yRel @2 :Float32; # m + vRel @3 :Float32; # m/s + + # these are optional and valid if they are not NaN + aRel @4 :Float32; # m/s^2 + yvRel @5 :Float32; # m/s + + # some radars flag measurements VS estimates + measured @6 :Bool; + } + + # deprecated + canMonoTimesDEPRECATED @2 :List(UInt64); +} + +# ******* car controls @ 100hz ******* + +struct CarControl { + # must be true for any actuator commands to work + enabled @0 :Bool; + latActive @11: Bool; + longActive @12: Bool; + + # Final actuator commands + actuators @6 :Actuators; + + # Blinker controls + leftBlinker @15: Bool; + rightBlinker @16: Bool; + + orientationNED @13 :List(Float32); + angularVelocity @14 :List(Float32); + + cruiseControl @4 :CruiseControl; + hudControl @5 :HUDControl; + + struct Actuators { + # lateral commands, mutually exclusive + steer @2: Float32; # [0.0, 1.0] + steeringAngleDeg @3: Float32; + curvature @7: Float32; + + # longitudinal commands + accel @4: Float32; # m/s^2 + longControlState @5: LongControlState; + + # these are only for logging the actual values sent to the car over CAN + gas @0: Float32; # [0.0, 1.0] + brake @1: Float32; # [0.0, 1.0] + steerOutputCan @8: Float32; # value sent over can to the car + speed @6: Float32; # m/s + + enum LongControlState @0xe40f3a917d908282{ + off @0; + pid @1; + stopping @2; + starting @3; + } + } + + struct CruiseControl { + cancel @0: Bool; + resume @1: Bool; + override @4: Bool; + speedOverrideDEPRECATED @2: Float32; + accelOverrideDEPRECATED @3: Float32; + } + + struct HUDControl { + speedVisible @0: Bool; + setSpeed @1: Float32; + lanesVisible @2: Bool; + leadVisible @3: Bool; + visualAlert @4: VisualAlert; + audibleAlert @5: AudibleAlert; + rightLaneVisible @6: Bool; + leftLaneVisible @7: Bool; + rightLaneDepart @8: Bool; + leftLaneDepart @9: Bool; + leadDistanceBars @10: Int8; # 1-3: 1 is closest, 3 is farthest. some ports may utilize 2-4 bars instead + + enum VisualAlert { + # these are the choices from the Honda + # map as good as you can for your car + none @0; + fcw @1; + steerRequired @2; + brakePressed @3; + wrongGear @4; + seatbeltUnbuckled @5; + speedTooHigh @6; + ldw @7; + } + + enum AudibleAlert { + none @0; + + engage @1; + disengage @2; + refuse @3; + + warningSoft @4; + warningImmediate @5; + + prompt @6; + promptRepeat @7; + promptDistracted @8; + } + } + + gasDEPRECATED @1 :Float32; + brakeDEPRECATED @2 :Float32; + steeringTorqueDEPRECATED @3 :Float32; + activeDEPRECATED @7 :Bool; + rollDEPRECATED @8 :Float32; + pitchDEPRECATED @9 :Float32; + actuatorsOutputDEPRECATED @10 :Actuators; +} + +struct CarOutput { + # Any car specific rate limits or quirks applied by + # the CarController are reflected in actuatorsOutput + # and matches what is sent to the car + actuatorsOutput @0 :CarControl.Actuators; +} + +# ****** car param ****** + +struct CarParams { + carName @0 :Text; + carFingerprint @1 :Text; + fuzzyFingerprint @55 :Bool; + + notCar @66 :Bool; # flag for non-car robotics platforms + + pcmCruise @3 :Bool; # is openpilot's state tied to the PCM's cruise state? + enableDsu @5 :Bool; # driving support unit + enableBsm @56 :Bool; # blind spot monitoring + flags @64 :UInt32; # flags for car specific quirks + experimentalLongitudinalAvailable @71 :Bool; + + minEnableSpeed @7 :Float32; + minSteerSpeed @8 :Float32; + safetyConfigs @62 :List(SafetyConfig); + alternativeExperience @65 :Int16; # panda flag for features like no disengage on gas + + # Car docs fields + maxLateralAccel @68 :Float32; + autoResumeSng @69 :Bool; # describes whether car can resume from a stop automatically + + # things about the car in the manual + mass @17 :Float32; # [kg] curb weight: all fluids no cargo + wheelbase @18 :Float32; # [m] distance from rear axle to front axle + centerToFront @19 :Float32; # [m] distance from center of mass to front axle + steerRatio @20 :Float32; # [] ratio of steering wheel angle to front wheel angle + steerRatioRear @21 :Float32; # [] ratio of steering wheel angle to rear wheel angle (usually 0) + + # things we can derive + rotationalInertia @22 :Float32; # [kg*m2] body rotational inertia + tireStiffnessFactor @72 :Float32; # scaling factor used in calculating tireStiffness[Front,Rear] + tireStiffnessFront @23 :Float32; # [N/rad] front tire coeff of stiff + tireStiffnessRear @24 :Float32; # [N/rad] rear tire coeff of stiff + + longitudinalTuning @25 :LongitudinalPIDTuning; + lateralParams @48 :LateralParams; + lateralTuning :union { + pid @26 :LateralPIDTuning; + indiDEPRECATED @27 :LateralINDITuning; + lqrDEPRECATED @40 :LateralLQRTuning; + torque @67 :LateralTorqueTuning; + } + + steerLimitAlert @28 :Bool; + steerLimitTimer @47 :Float32; # time before steerLimitAlert is issued + + vEgoStopping @29 :Float32; # Speed at which the car goes into stopping state + vEgoStarting @59 :Float32; # Speed at which the car goes into starting state + stoppingControl @31 :Bool; # Does the car allow full control even at lows speeds when stopping + steerControlType @34 :SteerControlType; + radarUnavailable @35 :Bool; # True when radar objects aren't visible on CAN or aren't parsed out + stopAccel @60 :Float32; # Required acceleration to keep vehicle stationary + stoppingDecelRate @52 :Float32; # m/s^2/s while trying to stop + startAccel @32 :Float32; # Required acceleration to get car moving + startingState @70 :Bool; # Does this car make use of special starting state + + steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds + longitudinalActuatorDelay @58 :Float32; # Gas/Brake actuator delay in seconds + openpilotLongitudinalControl @37 :Bool; # is openpilot doing the longitudinal control? + carVin @38 :Text; # VIN number queried during fingerprinting + dashcamOnly @41: Bool; + passive @73: Bool; # is openpilot in control? + transmissionType @43 :TransmissionType; + carFw @44 :List(CarFw); + + radarTimeStep @45: Float32 = 0.05; # time delta between radar updates, 20Hz is very standard + radarDelay @74 :Float32; + fingerprintSource @49: FingerprintSource; + networkLocation @50 :NetworkLocation; # Where Panda/C2 is integrated into the car's CAN network + + wheelSpeedFactor @63 :Float32; # Multiplier on wheels speeds to computer actual speeds + + secOcRequired @75 :Bool; # Car requires SecOC message authentication to operate + secOcKeyAvailable @76 :Bool; # Stored SecOC key loaded from params + + struct SafetyConfig { + safetyModel @0 :SafetyModel; + safetyParam @3 :UInt16; + safetyParamDEPRECATED @1 :Int16; + safetyParam2DEPRECATED @2 :UInt32; + } + + struct LateralParams { + torqueBP @0 :List(Int32); + torqueV @1 :List(Int32); + } + + struct LateralPIDTuning { + kpBP @0 :List(Float32); + kpV @1 :List(Float32); + kiBP @2 :List(Float32); + kiV @3 :List(Float32); + kf @4 :Float32; + } + + struct LateralTorqueTuning { + useSteeringAngle @0 :Bool; + kp @1 :Float32; + ki @2 :Float32; + friction @3 :Float32; + kf @4 :Float32; + steeringAngleDeadzoneDeg @5 :Float32; + latAccelFactor @6 :Float32; + latAccelOffset @7 :Float32; + } + + struct LongitudinalPIDTuning { + kpBP @0 :List(Float32); + kpV @1 :List(Float32); + kiBP @2 :List(Float32); + kiV @3 :List(Float32); + kf @6 :Float32; + deadzoneBPDEPRECATED @4 :List(Float32); + deadzoneVDEPRECATED @5 :List(Float32); + } + + struct LateralINDITuning { + outerLoopGainBP @4 :List(Float32); + outerLoopGainV @5 :List(Float32); + innerLoopGainBP @6 :List(Float32); + innerLoopGainV @7 :List(Float32); + timeConstantBP @8 :List(Float32); + timeConstantV @9 :List(Float32); + actuatorEffectivenessBP @10 :List(Float32); + actuatorEffectivenessV @11 :List(Float32); + + outerLoopGainDEPRECATED @0 :Float32; + innerLoopGainDEPRECATED @1 :Float32; + timeConstantDEPRECATED @2 :Float32; + actuatorEffectivenessDEPRECATED @3 :Float32; + } + + struct LateralLQRTuning { + scale @0 :Float32; + ki @1 :Float32; + dcGain @2 :Float32; + + # State space system + a @3 :List(Float32); + b @4 :List(Float32); + c @5 :List(Float32); + + k @6 :List(Float32); # LQR gain + l @7 :List(Float32); # Kalman gain + } + + enum SafetyModel { + silent @0; + hondaNidec @1; + toyota @2; + elm327 @3; + gm @4; + hondaBoschGiraffe @5; + ford @6; + cadillac @7; + hyundai @8; + chrysler @9; + tesla @10; + subaru @11; + gmPassive @12; + mazda @13; + nissan @14; + volkswagen @15; + toyotaIpas @16; + allOutput @17; + gmAscm @18; + noOutput @19; # like silent but without silent CAN TXs + hondaBosch @20; + volkswagenPq @21; + subaruPreglobal @22; # pre-Global platform + hyundaiLegacy @23; + hyundaiCommunity @24; + volkswagenMlb @25; + hongqi @26; + body @27; + hyundaiCanfd @28; + volkswagenMqbEvo @29; + chryslerCusw @30; + psa @31; + fcaGiorgio @32; + } + + enum SteerControlType { + torque @0; + angle @1; + + curvatureDEPRECATED @2; + } + + enum TransmissionType { + unknown @0; + automatic @1; # Traditional auto, including DSG + manual @2; # True "stick shift" only + direct @3; # Electric vehicle or other direct drive + cvt @4; + } + + struct CarFw { + ecu @0 :Ecu; + fwVersion @1 :Data; + address @2 :UInt32; + subAddress @3 :UInt8; + responseAddress @4 :UInt32; + request @5 :List(Data); + brand @6 :Text; + bus @7 :UInt8; + logging @8 :Bool; + obdMultiplexing @9 :Bool; + } + + enum Ecu { + eps @0; + abs @1; + fwdRadar @2; + fwdCamera @3; + engine @4; + unknown @5; + transmission @8; # Transmission Control Module + hybrid @18; # hybrid control unit, e.g. Chrysler's HCP, Honda's IMA Control Unit, Toyota's hybrid control computer + srs @9; # airbag + gateway @10; # can gateway + hud @11; # heads up display + combinationMeter @12; # instrument cluster + electricBrakeBooster @15; + shiftByWire @16; + adas @19; + cornerRadar @21; + hvac @20; + parkingAdas @7; # parking assist system ECU, e.g. Toyota's IPAS, Hyundai's RSPA, etc. + epb @22; # electronic parking brake + telematics @23; + body @24; # body control module + + # Toyota only + dsu @6; + + # Honda only + vsa @13; # Vehicle Stability Assist + programmedFuelInjection @14; + + debug @17; + } + + enum FingerprintSource { + can @0; + fw @1; + fixed @2; + } + + enum NetworkLocation { + fwdCamera @0; # Standard/default integration at LKAS camera + gateway @1; # Integration at vehicle's CAN gateway + } + + enableGasInterceptorDEPRECATED @2 :Bool; + enableCameraDEPRECATED @4 :Bool; + enableApgsDEPRECATED @6 :Bool; + steerRateCostDEPRECATED @33 :Float32; + isPandaBlackDEPRECATED @39 :Bool; + hasStockCameraDEPRECATED @57 :Bool; + safetyParamDEPRECATED @10 :Int16; + safetyModelDEPRECATED @9 :SafetyModel; + safetyModelPassiveDEPRECATED @42 :SafetyModel = silent; + minSpeedCanDEPRECATED @51 :Float32; + communityFeatureDEPRECATED @46: Bool; + startingAccelRateDEPRECATED @53 :Float32; + steerMaxBPDEPRECATED @11 :List(Float32); + steerMaxVDEPRECATED @12 :List(Float32); + gasMaxBPDEPRECATED @13 :List(Float32); + gasMaxVDEPRECATED @14 :List(Float32); + brakeMaxBPDEPRECATED @15 :List(Float32); + brakeMaxVDEPRECATED @16 :List(Float32); + directAccelControlDEPRECATED @30 :Bool; + maxSteeringAngleDegDEPRECATED @54 :Float32; + longitudinalActuatorDelayLowerBoundDEPRECATED @61 :Float32; +} diff --git a/opendbc_repo b/opendbc_repo index ff2ac79e07..a363ce1ff4 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit ff2ac79e07c2d9021c2fd4fc886ca61c81cd2694 +Subproject commit a363ce1ff452e63f2e49938508d97aece4ba6a3e diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 9bd03bad80..0afd0e7323 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -21,6 +21,7 @@ from opendbc.car.interfaces import CarInterfaceBase, RadarInterfaceBase from openpilot.selfdrive.pandad import can_capnp_to_list, can_list_to_can_capnp from openpilot.selfdrive.car.cruise import VCruiseHelper from openpilot.selfdrive.car.car_specific import MockCarState +from openpilot.selfdrive.car.helpers import convert_carControl, convert_to_capnp REPLAY = "REPLAY" in os.environ @@ -62,7 +63,8 @@ def can_comm_callbacks(logcan: messaging.SubSocket, sendcan: messaging.PubSocket class Car: CI: CarInterfaceBase RI: RadarInterfaceBase - CP: car.CarParams + CP: structs.CarParams + CP_capnp: car.CarParams def __init__(self, CI=None, RI=None) -> None: self.can_sock = messaging.sub_sock('can', timeout=20) @@ -142,7 +144,9 @@ class Car: self.params.put("CarParamsPrevRoute", prev_cp) # Write CarParams for controls and radard - cp_bytes = self.CP.to_bytes() + # convert to pycapnp representation for caching and logging + self.CP_capnp = convert_to_capnp(self.CP) + cp_bytes = self.CP_capnp.to_bytes() self.params.put("CarParams", cp_bytes) self.params.put_nonblocking("CarParamsCache", cp_bytes) self.params.put_nonblocking("CarParamsPersistent", cp_bytes) @@ -156,19 +160,19 @@ class Car: # card is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) - def state_update(self) -> tuple[car.CarState, structs.RadarDataT | None]: + def state_update(self) -> tuple[car.CarState, structs.RadarData | None]: """carState update loop, driven by can""" can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) can_list = can_capnp_to_list(can_strs) # Update carState from CAN - CS = self.CI.update(can_list) + CS = convert_to_capnp(self.CI.update(can_list)) if self.CP.carName == 'mock': CS = self.mock_carstate.update(CS) # Update radar tracks from CAN - RD: structs.RadarDataT | None = self.RI.update(can_list) + RD: structs.RadarData | None = self.RI.update(can_list) self.sm.update(0) @@ -188,20 +192,20 @@ class Car: return CS, RD - def state_publish(self, CS: car.CarState, RD: structs.RadarDataT | None): + def state_publish(self, CS: car.CarState, RD: structs.RadarData | None): """carState and carParams publish loop""" # carParams - logged every 50 seconds (> 1 per segment) if self.sm.frame % int(50. / DT_CTRL) == 0: cp_send = messaging.new_message('carParams') cp_send.valid = True - cp_send.carParams = self.CP + cp_send.carParams = self.CP_capnp self.pm.send('carParams', cp_send) # publish new carOutput co_send = messaging.new_message('carOutput') co_send.valid = self.sm.all_checks(['carControl']) - co_send.carOutput.actuatorsOutput = self.last_actuators_output + co_send.carOutput.actuatorsOutput = convert_to_capnp(self.last_actuators_output) self.pm.send('carOutput', co_send) # kick off controlsd step while we actuate the latest carControl packet @@ -215,7 +219,7 @@ class Car: if RD is not None: tracks_msg = messaging.new_message('liveTracks') tracks_msg.valid = len(RD.errors) == 0 - tracks_msg.liveTracks = RD + tracks_msg.liveTracks = convert_to_capnp(RD) self.pm.send('liveTracks', tracks_msg) def controls_update(self, CS: car.CarState, CC: car.CarControl): @@ -231,7 +235,7 @@ class Car: if self.sm.all_alive(['carControl']): # send car controls over can now_nanos = self.can_log_mono_time if REPLAY else int(time.monotonic() * 1e9) - self.last_actuators_output, can_sends = self.CI.apply(CC, now_nanos) + self.last_actuators_output, can_sends = self.CI.apply(convert_carControl(CC), now_nanos) self.pm.send('sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid)) self.CC_prev = CC diff --git a/selfdrive/car/helpers.py b/selfdrive/car/helpers.py new file mode 100644 index 0000000000..75e1c66d24 --- /dev/null +++ b/selfdrive/car/helpers.py @@ -0,0 +1,74 @@ +import capnp +from typing import Any + +from cereal import car +from opendbc.car import structs + +_FIELDS = '__dataclass_fields__' # copy of dataclasses._FIELDS + + +def is_dataclass(obj): + """Similar to dataclasses.is_dataclass without instance type check checking""" + return hasattr(obj, _FIELDS) + + +def _asdictref_inner(obj) -> dict[str, Any] | Any: + if is_dataclass(obj): + ret = {} + for field in getattr(obj, _FIELDS): # similar to dataclasses.fields() + ret[field] = _asdictref_inner(getattr(obj, field)) + return ret + elif isinstance(obj, (tuple, list)): + return type(obj)(_asdictref_inner(v) for v in obj) + else: + return obj + + +def asdictref(obj) -> dict[str, Any]: + """ + Similar to dataclasses.asdict without recursive type checking and copy.deepcopy + Note that the resulting dict will contain references to the original struct as a result + """ + if not is_dataclass(obj): + raise TypeError("asdictref() should be called on dataclass instances") + + return _asdictref_inner(obj) + + +def convert_to_capnp(struct: structs.CarParams | structs.CarState | structs.CarControl.Actuators | structs.RadarData) -> capnp.lib.capnp._DynamicStructBuilder: + struct_dict = asdictref(struct) + + if isinstance(struct, structs.CarParams): + del struct_dict['lateralTuning'] + struct_capnp = car.CarParams.new_message(**struct_dict) + + # this is the only union, special handling + which = struct.lateralTuning.which() + struct_capnp.lateralTuning.init(which) + lateralTuning_dict = asdictref(getattr(struct.lateralTuning, which)) + setattr(struct_capnp.lateralTuning, which, lateralTuning_dict) + elif isinstance(struct, structs.CarState): + struct_capnp = car.CarState.new_message(**struct_dict) + elif isinstance(struct, structs.CarControl.Actuators): + struct_capnp = car.CarControl.Actuators.new_message(**struct_dict) + elif isinstance(struct, structs.RadarData): + struct_capnp = car.RadarData.new_message(**struct_dict) + else: + raise ValueError(f"Unsupported struct type: {type(struct)}") + + return struct_capnp + + +def convert_carControl(struct: capnp.lib.capnp._DynamicStructReader) -> structs.CarControl: + # TODO: recursively handle any car struct as needed + def remove_deprecated(s: dict) -> dict: + return {k: v for k, v in s.items() if not k.endswith('DEPRECATED')} + + struct_dict = struct.to_dict() + struct_dataclass = structs.CarControl(**remove_deprecated({k: v for k, v in struct_dict.items() if not isinstance(k, dict)})) + + struct_dataclass.actuators = structs.CarControl.Actuators(**remove_deprecated(struct_dict.get('actuators', {}))) + struct_dataclass.cruiseControl = structs.CarControl.CruiseControl(**remove_deprecated(struct_dict.get('cruiseControl', {}))) + struct_dataclass.hudControl = structs.CarControl.HUDControl(**remove_deprecated(struct_dict.get('hudControl', {}))) + + return struct_dataclass diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 4370ea141b..66cf0dc696 100644 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -12,6 +12,7 @@ from opendbc.car.tests.test_car_interfaces import get_fuzzy_car_interface_args from opendbc.car.fingerprints import all_known_cars from opendbc.car.fw_versions import FW_VERSIONS, FW_QUERY_CONFIGS from opendbc.car.mock.values import CAR as MOCK +from openpilot.selfdrive.car.card import convert_carControl, convert_to_capnp from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque @@ -40,7 +41,6 @@ class TestCarInterfaces: car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'], experimental_long=args['experimental_long'], docs=False) - car_params = car_params.as_reader() car_interface = CarInterface(car_params, CarController, CarState) assert car_params assert car_interface @@ -72,7 +72,7 @@ class TestCarInterfaces: # Run car interface now_nanos = 0 CC = car.CarControl.new_message(**cc_msg) - CC = CC.as_reader() + CC = convert_carControl(CC.as_reader()) for _ in range(10): car_interface.update([]) car_interface.apply(CC, now_nanos) @@ -80,7 +80,7 @@ class TestCarInterfaces: CC = car.CarControl.new_message(**cc_msg) CC.enabled = True - CC = CC.as_reader() + CC = convert_carControl(CC.as_reader()) for _ in range(10): car_interface.update([]) car_interface.apply(CC, now_nanos) @@ -89,10 +89,11 @@ class TestCarInterfaces: # Test controller initialization # TODO: wait until card refactor is merged to run controller a few times, # hypothesis also slows down significantly with just one more message draw - LongControl(car_params) + car_params_capnp = convert_to_capnp(car_params).as_reader() + LongControl(car_params_capnp) if car_params.steerControlType == CarParams.SteerControlType.angle: - LatControlAngle(car_params, car_interface) + LatControlAngle(car_params_capnp, car_interface) elif car_params.lateralTuning.which() == 'pid': - LatControlPID(car_params, car_interface) + LatControlPID(car_params_capnp, car_interface) elif car_params.lateralTuning.which() == 'torque': - LatControlTorque(car_params, car_interface) + LatControlTorque(car_params_capnp, car_interface) diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 72f511b7ce..ef54631e54 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -1,4 +1,6 @@ import capnp +import copy +import dataclasses import os import pytest import random @@ -18,6 +20,7 @@ from opendbc.car.car_helpers import FRAME_FINGERPRINT, interfaces from opendbc.car.honda.values import CAR as HONDA, HondaFlags from opendbc.car.values import Platform from opendbc.car.tests.routes import non_tested_cars, routes, CarTestRoute +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.selfdrived.events import ET from openpilot.selfdrive.selfdrived.selfdrived import SelfdriveD from openpilot.selfdrive.pandad import can_capnp_to_list @@ -184,7 +187,7 @@ class TestCarModelBase(unittest.TestCase): del cls.can_msgs def setUp(self): - self.CI = self.CarInterface(self.CP.copy(), self.CarController, self.CarState) + self.CI = self.CarInterface(copy.deepcopy(self.CP), self.CarController, self.CarState) assert self.CI Params().put_bool("OpenpilotEnabledToggle", self.openpilot_enabled) @@ -192,7 +195,7 @@ class TestCarModelBase(unittest.TestCase): # TODO: check safetyModel is in release panda build self.safety = libpanda_py.libpanda - cfg = self.CP.safetyConfigs[-1] + cfg = car.CarParams.SafetyConfig(**dataclasses.asdict(self.CP.safetyConfigs[-1])) set_status = self.safety.set_safety_hooks(cfg.safetyModel.raw, cfg.safetyParam) self.assertEqual(0, set_status, f"failed to set safetyModel {cfg}") self.safety.init_tests() @@ -217,7 +220,7 @@ class TestCarModelBase(unittest.TestCase): # TODO: also check for checksum violations from can parser can_invalid_cnt = 0 can_valid = False - CC = structs.CarControl().as_reader() + CC = structs.CarControl() for i, msg in enumerate(self.can_msgs): CS = self.CI.update(can_capnp_to_list((msg.as_builder().to_bytes(),))) @@ -309,17 +312,17 @@ class TestCarModelBase(unittest.TestCase): # Make sure we can send all messages while inactive CC = structs.CarControl() - test_car_controller(CC.as_reader()) + test_car_controller(CC) # Test cancel + general messages (controls_allowed=False & cruise_engaged=True) self.safety.set_cruise_engaged_prev(True) CC = structs.CarControl(cruiseControl=structs.CarControl.CruiseControl(cancel=True)) - test_car_controller(CC.as_reader()) + test_car_controller(CC) # Test resume + general messages (controls_allowed=True & cruise_engaged=True) self.safety.set_controls_allowed(True) CC = structs.CarControl(cruiseControl=structs.CarControl.CruiseControl(resume=True)) - test_car_controller(CC.as_reader()) + test_car_controller(CC) # Skip stdout/stderr capture with pytest, causes elevated memory usage @pytest.mark.nocapture @@ -406,7 +409,7 @@ class TestCarModelBase(unittest.TestCase): selfdrived = SelfdriveD(CP=self.CP) selfdrived.initialized = True for idx, can in enumerate(self.can_msgs): - CS = self.CI.update(can_capnp_to_list((can.as_builder().to_bytes(), ))).as_reader() + CS = convert_to_capnp(self.CI.update(can_capnp_to_list((can.as_builder().to_bytes(), )))) for msg in filter(lambda m: m.src in range(64), can.can): to_send = libpanda_py.make_CANPacket(msg.address, msg.src % 4, msg.dat) ret = self.safety.safety_rx_hook(to_send) diff --git a/selfdrive/controls/lib/tests/test_latcontrol.py b/selfdrive/controls/lib/tests/test_latcontrol.py index ba4bd0faec..c8c8d02751 100644 --- a/selfdrive/controls/lib/tests/test_latcontrol.py +++ b/selfdrive/controls/lib/tests/test_latcontrol.py @@ -5,6 +5,7 @@ from opendbc.car.car_helpers import interfaces from opendbc.car.honda.values import CAR as HONDA from opendbc.car.toyota.values import CAR as TOYOTA from opendbc.car.nissan.values import CAR as NISSAN +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle @@ -20,6 +21,7 @@ class TestLatControl: CarInterface, CarController, CarState, RadarInterface = interfaces[car_name] CP = CarInterface.get_non_essential_params(car_name) CI = CarInterface(CP, CarController, CarState) + CP = convert_to_capnp(CP) VM = VehicleModel(CP) controller = controller(CP.as_reader(), CI) diff --git a/selfdrive/controls/lib/tests/test_vehicle_model.py b/selfdrive/controls/lib/tests/test_vehicle_model.py index d15519a866..b58bdbe522 100644 --- a/selfdrive/controls/lib/tests/test_vehicle_model.py +++ b/selfdrive/controls/lib/tests/test_vehicle_model.py @@ -5,13 +5,14 @@ import numpy as np from opendbc.car.honda.interface import CarInterface from opendbc.car.honda.values import CAR +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel, dyn_ss_sol, create_dyn_state_matrices class TestVehicleModel: def setup_method(self): CP = CarInterface.get_non_essential_params(CAR.HONDA_CIVIC) - self.VM = VehicleModel(CP) + self.VM = VehicleModel(convert_to_capnp(CP)) def test_round_trip_yaw_rate(self): # TODO: fix VM to work at zero speed diff --git a/selfdrive/debug/format_fingerprints.py b/selfdrive/debug/format_fingerprints.py index 7207bd1ef1..ae1ed06b75 100755 --- a/selfdrive/debug/format_fingerprints.py +++ b/selfdrive/debug/format_fingerprints.py @@ -2,16 +2,12 @@ import jinja2 import os -from cereal import car from openpilot.common.basedir import BASEDIR from opendbc.car.interfaces import get_interface_attr -Ecu = car.CarParams.Ecu - CARS = get_interface_attr('CAR') FW_VERSIONS = get_interface_attr('FW_VERSIONS') FINGERPRINTS = get_interface_attr('FINGERPRINTS') -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} FINGERPRINTS_PY_TEMPLATE = jinja2.Template(""" {%- if FINGERPRINTS[brand] %} @@ -49,7 +45,7 @@ FW_VERSIONS{% if not FW_VERSIONS[brand] %}: dict[str, dict[tuple, list[bytes]]]{ {% for car, _ in FW_VERSIONS[brand].items() %} CAR.{{car.name}}: { {% for key, fw_versions in FW_VERSIONS[brand][car].items() %} - (Ecu.{{ECU_NAME[key[0]]}}, 0x{{"%0x" | format(key[1] | int)}}, \ + (Ecu.{{key[0]}}, 0x{{"%0x" | format(key[1] | int)}}, \ {% if key[2] %}0x{{"%0x" | format(key[2] | int)}}{% else %}{{key[2]}}{% endif %}): [ {% for fw_version in (fw_versions + extra_fw_versions.get(car, {}).get(key, [])) | unique | sort %} {{fw_version}}, @@ -71,9 +67,8 @@ def format_brand_fw_versions(brand, extra_fw_versions: None | dict[str, dict[tup comments = [line for line in f.readlines() if line.startswith("#") and "noqa" not in line] with open(fingerprints_file, "w") as f: - f.write(FINGERPRINTS_PY_TEMPLATE.render(brand=brand, comments=comments, ECU_NAME=ECU_NAME, - FINGERPRINTS=FINGERPRINTS, FW_VERSIONS=FW_VERSIONS, - extra_fw_versions=extra_fw_versions)) + f.write(FINGERPRINTS_PY_TEMPLATE.render(brand=brand, comments=comments, FINGERPRINTS=FINGERPRINTS, + FW_VERSIONS=FW_VERSIONS, extra_fw_versions=extra_fw_versions)) if __name__ == "__main__": diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index 4e91d32400..ec258f42f0 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -17,6 +17,7 @@ from openpilot.common.realtime import config_realtime_process from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.transformations.model import get_warp_matrix from openpilot.system import sentry +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.desire_helper import DesireHelper from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime from openpilot.selfdrive.modeld.parse_model_outputs import Parser @@ -183,7 +184,7 @@ def main(demo=False): if demo: - CP = get_demo_car_params() + CP = convert_to_capnp(get_demo_car_params()) else: CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) cloudlog.info("modeld got CarParams: %s", CP.carName) diff --git a/selfdrive/modeld/tests/test_modeld.py b/selfdrive/modeld/tests/test_modeld.py index 145ba31ade..1bf2977a91 100644 --- a/selfdrive/modeld/tests/test_modeld.py +++ b/selfdrive/modeld/tests/test_modeld.py @@ -7,6 +7,7 @@ from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.params import Params from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.realtime import DT_MDL +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.system.manager.process_config import managed_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state @@ -23,7 +24,7 @@ class TestModeld: self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, False, CAM.width, CAM.height) self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, False, CAM.width, CAM.height) self.vipc_server.start_listener() - Params().put("CarParams", get_demo_car_params().to_bytes()) + Params().put("CarParams", convert_to_capnp(get_demo_car_params()).to_bytes()) self.sm = messaging.SubMaster(['modelV2', 'cameraOdometry']) self.pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState', 'liveCalibration']) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 9abdb6476a..b6d5ba6afd 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -24,7 +24,7 @@ from openpilot.common.prefix import OpenpilotPrefix from openpilot.common.timeout import Timeout from openpilot.common.realtime import DT_CTRL from panda.python import ALTERNATIVE_EXPERIENCE -from openpilot.selfdrive.car.card import can_comm_callbacks +from openpilot.selfdrive.car.card import can_comm_callbacks, convert_to_capnp from openpilot.system.manager.process_config import managed_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state, available_streams from openpilot.selfdrive.test.process_replay.migration import migrate_all @@ -370,7 +370,7 @@ def get_car_params_callback(rc, pm, msgs, fingerprint): if not params.get_bool("DisengageOnAccelerator"): CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS - params.put("CarParams", CP.to_bytes()) + params.put("CarParams", convert_to_capnp(CP).to_bytes()) def selfdrived_rcv_callback(msg, cfg, frame): diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 67d865a654..eb67f60cc0 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -cbe81fea9b820b8dd38667866aac72a8a0dae966 \ No newline at end of file +05570b52a90fb8bf092f7a2563d6019577e1aa5d \ No newline at end of file diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index c4ff080fa4..3b9d65b85a 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -10,6 +10,7 @@ from cereal.services import SERVICE_LIST from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.mock import mock_messages from openpilot.common.params import Params +from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.system.hardware.tici.power_monitor import get_power from openpilot.system.manager.process_config import managed_processes from openpilot.system.manager.manager import manager_cleanup @@ -42,7 +43,7 @@ PROCS = [ class TestPowerDraw: def setup_method(self): - Params().put("CarParams", get_demo_car_params()).to_bytes() + Params().put("CarParams", convert_to_capnp(get_demo_car_params()).to_bytes()) # wait a bit for power save to disable time.sleep(5) From 68f4c8a9868d7fdb9b46e2d96f1d345e62a4a443 Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Fri, 4 Oct 2024 09:19:06 +0900 Subject: [PATCH 209/214] ui: remove space (#33724) --- selfdrive/ui/ui.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index a9206b59bb..b11330a046 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -70,7 +70,7 @@ void ui_update_params(UIState *s) { void UIState::updateStatus() { if (scene.started && sm->updated("selfdriveState")) { auto ss = (*sm)["selfdriveState"].getSelfdriveState(); - auto state = ss .getState(); + auto state = ss.getState(); if (state == cereal::SelfdriveState::OpenpilotState::PRE_ENABLED || state == cereal::SelfdriveState::OpenpilotState::OVERRIDING) { status = STATUS_OVERRIDE; } else { From 4a5052606463ccac2a740b3b8c20fdfd422ef237 Mon Sep 17 00:00:00 2001 From: Alexandre Nobuharu Sato <66435071+AlexandreSato@users.noreply.github.com> Date: Thu, 3 Oct 2024 21:20:01 -0300 Subject: [PATCH 210/214] Typo on README.md of replay instructions (#33726) --- tools/replay/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/replay/README.md b/tools/replay/README.md index 65a1e7a0b3..5e91aae943 100644 --- a/tools/replay/README.md +++ b/tools/replay/README.md @@ -37,7 +37,7 @@ tools/replay/replay --data_dir="/path_to/route" # a2a0ccea32023010|2023-07-27--13-01-19--0 # a2a0ccea32023010|2023-07-27--13-01-19--1 # You can replay it like this: -tools/replay/replay "a2a0ccea32023010|2023-07-27--13-01-19" --data-dir="/path_to_routes" +tools/replay/replay "a2a0ccea32023010|2023-07-27--13-01-19" --data_dir="/path_to_routes" ``` ## Send Messages via ZMQ From 7556233cca6acc8484020e2ae667df95c25631fe Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 3 Oct 2024 22:47:03 -0700 Subject: [PATCH 211/214] Reapply "move car.capnp to opendbc (#33722)" (#33728) * Reapply "move car.capnp to opendbc" (#33725) This reverts commit 9d52a5b485fc45d3b05f2021bbf1bd1c4f15c83e. * why can't i repro?! * Revert "why can't i repro?!" This reverts commit 0435d218f790faf7b7aaed27d05ab9ee67b087e6. * does this cause card to try and read it? * better place * wtf * Reapply "why can't i repro?!" This reverts commit d24fd5a0abf454f47d5591e3b39039fdc4d0251c. * also here --- cereal/car.capnp | 723 +----------------- opendbc_repo | 2 +- selfdrive/car/card.py | 26 +- selfdrive/car/helpers.py | 74 -- selfdrive/car/tests/test_car_interfaces.py | 15 +- selfdrive/car/tests/test_models.py | 17 +- .../controls/lib/tests/test_latcontrol.py | 2 - .../controls/lib/tests/test_vehicle_model.py | 3 +- selfdrive/debug/format_fingerprints.py | 11 +- selfdrive/modeld/modeld.py | 3 +- selfdrive/modeld/tests/test_modeld.py | 3 +- .../test/process_replay/process_replay.py | 6 +- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/test_onroad.py | 5 +- system/hardware/tici/tests/test_power_draw.py | 3 +- 15 files changed, 47 insertions(+), 848 deletions(-) mode change 100644 => 120000 cereal/car.capnp delete mode 100644 selfdrive/car/helpers.py diff --git a/cereal/car.capnp b/cereal/car.capnp deleted file mode 100644 index c8474f431b..0000000000 --- a/cereal/car.capnp +++ /dev/null @@ -1,722 +0,0 @@ -using Cxx = import "./include/c++.capnp"; -$Cxx.namespace("cereal"); - -@0x8e2af1e708af8b8d; - -# ******* events causing controls state machine transition ******* - -# IMPORTANT: This struct is to not be modified so old logs can be parsed -struct OnroadEventDEPRECATED @0x9b1657f34caf3ad3 { - name @0 :EventName; - - # event types - enable @1 :Bool; - noEntry @2 :Bool; - warning @3 :Bool; # alerts presented only when enabled or soft disabling - userDisable @4 :Bool; - softDisable @5 :Bool; - immediateDisable @6 :Bool; - preEnable @7 :Bool; - permanent @8 :Bool; # alerts presented regardless of openpilot state - overrideLateral @10 :Bool; - overrideLongitudinal @9 :Bool; - - enum EventName @0xbaa8c5d505f727de { - canError @0; - steerUnavailable @1; - wrongGear @4; - doorOpen @5; - seatbeltNotLatched @6; - espDisabled @7; - wrongCarMode @8; - steerTempUnavailable @9; - reverseGear @10; - buttonCancel @11; - buttonEnable @12; - pedalPressed @13; # exits active state - preEnableStandstill @73; # added during pre-enable state with brake - gasPressedOverride @108; # added when user is pressing gas with no disengage on gas - steerOverride @114; - cruiseDisabled @14; - speedTooLow @17; - outOfSpace @18; - overheat @19; - calibrationIncomplete @20; - calibrationInvalid @21; - calibrationRecalibrating @117; - controlsMismatch @22; - pcmEnable @23; - pcmDisable @24; - radarFault @26; - brakeHold @28; - parkBrake @29; - manualRestart @30; - joystickDebug @34; - longitudinalManeuver @124; - steerTempUnavailableSilent @35; - resumeRequired @36; - preDriverDistracted @37; - promptDriverDistracted @38; - driverDistracted @39; - preDriverUnresponsive @43; - promptDriverUnresponsive @44; - driverUnresponsive @45; - belowSteerSpeed @46; - lowBattery @48; - accFaulted @51; - sensorDataInvalid @52; - commIssue @53; - commIssueAvgFreq @109; - tooDistracted @54; - posenetInvalid @55; - soundsUnavailable @56; - preLaneChangeLeft @57; - preLaneChangeRight @58; - laneChange @59; - lowMemory @63; - stockAeb @64; - ldw @65; - carUnrecognized @66; - invalidLkasSetting @69; - speedTooHigh @70; - laneChangeBlocked @71; - relayMalfunction @72; - stockFcw @74; - startup @75; - startupNoCar @76; - startupNoControl @77; - startupNoSecOcKey @125; - startupMaster @78; - fcw @79; - steerSaturated @80; - belowEngageSpeed @84; - noGps @85; - wrongCruiseMode @87; - modeldLagging @89; - deviceFalling @90; - fanMalfunction @91; - cameraMalfunction @92; - cameraFrameRate @110; - processNotRunning @95; - dashcamMode @96; - selfdriveInitializing @98; - usbError @99; - cruiseMismatch @106; - canBusMissing @111; - selfdrivedLagging @112; - resumeBlocked @113; - steerTimeLimit @115; - vehicleSensorsInvalid @116; - locationdTemporaryError @103; - locationdPermanentError @118; - paramsdTemporaryError @50; - paramsdPermanentError @119; - actuatorsApiUnavailable @120; - espActive @121; - personalityChanged @122; - aeb @123; - - radarCanErrorDEPRECATED @15; - communityFeatureDisallowedDEPRECATED @62; - radarCommIssueDEPRECATED @67; - driverMonitorLowAccDEPRECATED @68; - gasUnavailableDEPRECATED @3; - dataNeededDEPRECATED @16; - modelCommIssueDEPRECATED @27; - ipasOverrideDEPRECATED @33; - geofenceDEPRECATED @40; - driverMonitorOnDEPRECATED @41; - driverMonitorOffDEPRECATED @42; - calibrationProgressDEPRECATED @47; - invalidGiraffeHondaDEPRECATED @49; - invalidGiraffeToyotaDEPRECATED @60; - internetConnectivityNeededDEPRECATED @61; - whitePandaUnsupportedDEPRECATED @81; - commIssueWarningDEPRECATED @83; - focusRecoverActiveDEPRECATED @86; - neosUpdateRequiredDEPRECATED @88; - modelLagWarningDEPRECATED @93; - startupOneplusDEPRECATED @82; - startupFuzzyFingerprintDEPRECATED @97; - noTargetDEPRECATED @25; - brakeUnavailableDEPRECATED @2; - plannerErrorDEPRECATED @32; - gpsMalfunctionDEPRECATED @94; - roadCameraErrorDEPRECATED @100; - driverCameraErrorDEPRECATED @101; - wideRoadCameraErrorDEPRECATED @102; - highCpuUsageDEPRECATED @105; - startupNoFwDEPRECATED @104; - lowSpeedLockoutDEPRECATED @31; - lkasDisabledDEPRECATED @107; - } -} - -# ******* main car state @ 100hz ******* -# all speeds in m/s - -struct CarState { - # CAN health - canValid @26 :Bool; # invalid counter/checksums - canTimeout @40 :Bool; # CAN bus dropped out - canErrorCounter @48 :UInt32; - - # car speed - vEgo @1 :Float32; # best estimate of speed - aEgo @16 :Float32; # best estimate of aCAN cceleration - vEgoRaw @17 :Float32; # unfiltered speed from wheel speed sensors - vEgoCluster @44 :Float32; # best estimate of speed shown on car's instrument cluster, used for UI - - vCruise @53 :Float32; # actual set speed - vCruiseCluster @54 :Float32; # set speed to display in the UI - - yawRate @22 :Float32; # best estimate of yaw rate - standstill @18 :Bool; - wheelSpeeds @2 :WheelSpeeds; - - # gas pedal, 0.0-1.0 - gas @3 :Float32; # this is user pedal only - gasPressed @4 :Bool; # this is user pedal only - - engineRpm @46 :Float32; - - # brake pedal, 0.0-1.0 - brake @5 :Float32; # this is user pedal only - brakePressed @6 :Bool; # this is user pedal only - regenBraking @45 :Bool; # this is user pedal only - parkingBrake @39 :Bool; - brakeHoldActive @38 :Bool; - - # steering wheel - steeringAngleDeg @7 :Float32; - steeringAngleOffsetDeg @37 :Float32; # Offset betweens sensors in case there multiple - steeringRateDeg @15 :Float32; - steeringTorque @8 :Float32; # TODO: standardize units - steeringTorqueEps @27 :Float32; # TODO: standardize units - steeringPressed @9 :Bool; # if the user is using the steering wheel - steerFaultTemporary @35 :Bool; # temporary EPS fault - steerFaultPermanent @36 :Bool; # permanent EPS fault - invalidLkasSetting @55 :Bool; # stock LKAS is incorrectly configured (i.e. on or off) - stockAeb @30 :Bool; - stockFcw @31 :Bool; - espDisabled @32 :Bool; - accFaulted @42 :Bool; - carFaultedNonCritical @47 :Bool; # some ECU is faulted, but car remains controllable - espActive @51 :Bool; - vehicleSensorsInvalid @52 :Bool; # invalid steering angle readings, etc. - lowSpeedAlert @56 :Bool; # lost steering control due to a dynamic min steering speed - - # cruise state - cruiseState @10 :CruiseState; - - # gear - gearShifter @14 :GearShifter; - - # button presses - buttonEvents @11 :List(ButtonEvent); - leftBlinker @20 :Bool; - rightBlinker @21 :Bool; - genericToggle @23 :Bool; - - # lock info - doorOpen @24 :Bool; - seatbeltUnlatched @25 :Bool; - - # clutch (manual transmission only) - clutchPressed @28 :Bool; - - # blindspot sensors - leftBlindspot @33 :Bool; # Is there something blocking the left lane change - rightBlindspot @34 :Bool; # Is there something blocking the right lane change - - fuelGauge @41 :Float32; # battery or fuel tank level from 0.0 to 1.0 - charging @43 :Bool; - - # process meta - cumLagMs @50 :Float32; - - struct WheelSpeeds { - # optional wheel speeds - fl @0 :Float32; - fr @1 :Float32; - rl @2 :Float32; - rr @3 :Float32; - } - - struct CruiseState { - enabled @0 :Bool; - speed @1 :Float32; - speedCluster @6 :Float32; # Set speed as shown on instrument cluster - available @2 :Bool; - speedOffset @3 :Float32; - standstill @4 :Bool; - nonAdaptive @5 :Bool; - } - - enum GearShifter { - unknown @0; - park @1; - drive @2; - neutral @3; - reverse @4; - sport @5; - low @6; - brake @7; - eco @8; - manumatic @9; - } - - # send on change - struct ButtonEvent { - pressed @0 :Bool; - type @1 :Type; - - enum Type { - unknown @0; - leftBlinker @1; - rightBlinker @2; - accelCruise @3; - decelCruise @4; - cancel @5; - altButton1 @6; - altButton2 @7; - mainCruise @8; - setCruise @9; - resumeCruise @10; - gapAdjustCruise @11; - } - } - - # deprecated - errorsDEPRECATED @0 :List(OnroadEventDEPRECATED.EventName); - brakeLightsDEPRECATED @19 :Bool; - steeringRateLimitedDEPRECATED @29 :Bool; - canMonoTimesDEPRECATED @12: List(UInt64); - canRcvTimeoutDEPRECATED @49 :Bool; - eventsDEPRECATED @13 :List(OnroadEventDEPRECATED); -} - -# ******* radar state @ 20hz ******* - -struct RadarData @0x888ad6581cf0aacb { - errors @0 :List(Error); - points @1 :List(RadarPoint); - - enum Error { - canError @0; - fault @1; - wrongConfig @2; - } - - # similar to LiveTracks - # is one timestamp valid for all? I think so - struct RadarPoint { - trackId @0 :UInt64; # no trackId reuse - - # these 3 are the minimum required - dRel @1 :Float32; # m from the front bumper of the car - yRel @2 :Float32; # m - vRel @3 :Float32; # m/s - - # these are optional and valid if they are not NaN - aRel @4 :Float32; # m/s^2 - yvRel @5 :Float32; # m/s - - # some radars flag measurements VS estimates - measured @6 :Bool; - } - - # deprecated - canMonoTimesDEPRECATED @2 :List(UInt64); -} - -# ******* car controls @ 100hz ******* - -struct CarControl { - # must be true for any actuator commands to work - enabled @0 :Bool; - latActive @11: Bool; - longActive @12: Bool; - - # Final actuator commands - actuators @6 :Actuators; - - # Blinker controls - leftBlinker @15: Bool; - rightBlinker @16: Bool; - - orientationNED @13 :List(Float32); - angularVelocity @14 :List(Float32); - - cruiseControl @4 :CruiseControl; - hudControl @5 :HUDControl; - - struct Actuators { - # lateral commands, mutually exclusive - steer @2: Float32; # [0.0, 1.0] - steeringAngleDeg @3: Float32; - curvature @7: Float32; - - # longitudinal commands - accel @4: Float32; # m/s^2 - longControlState @5: LongControlState; - - # these are only for logging the actual values sent to the car over CAN - gas @0: Float32; # [0.0, 1.0] - brake @1: Float32; # [0.0, 1.0] - steerOutputCan @8: Float32; # value sent over can to the car - speed @6: Float32; # m/s - - enum LongControlState @0xe40f3a917d908282{ - off @0; - pid @1; - stopping @2; - starting @3; - } - } - - struct CruiseControl { - cancel @0: Bool; - resume @1: Bool; - override @4: Bool; - speedOverrideDEPRECATED @2: Float32; - accelOverrideDEPRECATED @3: Float32; - } - - struct HUDControl { - speedVisible @0: Bool; - setSpeed @1: Float32; - lanesVisible @2: Bool; - leadVisible @3: Bool; - visualAlert @4: VisualAlert; - audibleAlert @5: AudibleAlert; - rightLaneVisible @6: Bool; - leftLaneVisible @7: Bool; - rightLaneDepart @8: Bool; - leftLaneDepart @9: Bool; - leadDistanceBars @10: Int8; # 1-3: 1 is closest, 3 is farthest. some ports may utilize 2-4 bars instead - - enum VisualAlert { - # these are the choices from the Honda - # map as good as you can for your car - none @0; - fcw @1; - steerRequired @2; - brakePressed @3; - wrongGear @4; - seatbeltUnbuckled @5; - speedTooHigh @6; - ldw @7; - } - - enum AudibleAlert { - none @0; - - engage @1; - disengage @2; - refuse @3; - - warningSoft @4; - warningImmediate @5; - - prompt @6; - promptRepeat @7; - promptDistracted @8; - } - } - - gasDEPRECATED @1 :Float32; - brakeDEPRECATED @2 :Float32; - steeringTorqueDEPRECATED @3 :Float32; - activeDEPRECATED @7 :Bool; - rollDEPRECATED @8 :Float32; - pitchDEPRECATED @9 :Float32; - actuatorsOutputDEPRECATED @10 :Actuators; -} - -struct CarOutput { - # Any car specific rate limits or quirks applied by - # the CarController are reflected in actuatorsOutput - # and matches what is sent to the car - actuatorsOutput @0 :CarControl.Actuators; -} - -# ****** car param ****** - -struct CarParams { - carName @0 :Text; - carFingerprint @1 :Text; - fuzzyFingerprint @55 :Bool; - - notCar @66 :Bool; # flag for non-car robotics platforms - - pcmCruise @3 :Bool; # is openpilot's state tied to the PCM's cruise state? - enableDsu @5 :Bool; # driving support unit - enableBsm @56 :Bool; # blind spot monitoring - flags @64 :UInt32; # flags for car specific quirks - experimentalLongitudinalAvailable @71 :Bool; - - minEnableSpeed @7 :Float32; - minSteerSpeed @8 :Float32; - safetyConfigs @62 :List(SafetyConfig); - alternativeExperience @65 :Int16; # panda flag for features like no disengage on gas - - # Car docs fields - maxLateralAccel @68 :Float32; - autoResumeSng @69 :Bool; # describes whether car can resume from a stop automatically - - # things about the car in the manual - mass @17 :Float32; # [kg] curb weight: all fluids no cargo - wheelbase @18 :Float32; # [m] distance from rear axle to front axle - centerToFront @19 :Float32; # [m] distance from center of mass to front axle - steerRatio @20 :Float32; # [] ratio of steering wheel angle to front wheel angle - steerRatioRear @21 :Float32; # [] ratio of steering wheel angle to rear wheel angle (usually 0) - - # things we can derive - rotationalInertia @22 :Float32; # [kg*m2] body rotational inertia - tireStiffnessFactor @72 :Float32; # scaling factor used in calculating tireStiffness[Front,Rear] - tireStiffnessFront @23 :Float32; # [N/rad] front tire coeff of stiff - tireStiffnessRear @24 :Float32; # [N/rad] rear tire coeff of stiff - - longitudinalTuning @25 :LongitudinalPIDTuning; - lateralParams @48 :LateralParams; - lateralTuning :union { - pid @26 :LateralPIDTuning; - indiDEPRECATED @27 :LateralINDITuning; - lqrDEPRECATED @40 :LateralLQRTuning; - torque @67 :LateralTorqueTuning; - } - - steerLimitAlert @28 :Bool; - steerLimitTimer @47 :Float32; # time before steerLimitAlert is issued - - vEgoStopping @29 :Float32; # Speed at which the car goes into stopping state - vEgoStarting @59 :Float32; # Speed at which the car goes into starting state - stoppingControl @31 :Bool; # Does the car allow full control even at lows speeds when stopping - steerControlType @34 :SteerControlType; - radarUnavailable @35 :Bool; # True when radar objects aren't visible on CAN or aren't parsed out - stopAccel @60 :Float32; # Required acceleration to keep vehicle stationary - stoppingDecelRate @52 :Float32; # m/s^2/s while trying to stop - startAccel @32 :Float32; # Required acceleration to get car moving - startingState @70 :Bool; # Does this car make use of special starting state - - steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds - longitudinalActuatorDelay @58 :Float32; # Gas/Brake actuator delay in seconds - openpilotLongitudinalControl @37 :Bool; # is openpilot doing the longitudinal control? - carVin @38 :Text; # VIN number queried during fingerprinting - dashcamOnly @41: Bool; - passive @73: Bool; # is openpilot in control? - transmissionType @43 :TransmissionType; - carFw @44 :List(CarFw); - - radarTimeStep @45: Float32 = 0.05; # time delta between radar updates, 20Hz is very standard - radarDelay @74 :Float32; - fingerprintSource @49: FingerprintSource; - networkLocation @50 :NetworkLocation; # Where Panda/C2 is integrated into the car's CAN network - - wheelSpeedFactor @63 :Float32; # Multiplier on wheels speeds to computer actual speeds - - secOcRequired @75 :Bool; # Car requires SecOC message authentication to operate - secOcKeyAvailable @76 :Bool; # Stored SecOC key loaded from params - - struct SafetyConfig { - safetyModel @0 :SafetyModel; - safetyParam @3 :UInt16; - safetyParamDEPRECATED @1 :Int16; - safetyParam2DEPRECATED @2 :UInt32; - } - - struct LateralParams { - torqueBP @0 :List(Int32); - torqueV @1 :List(Int32); - } - - struct LateralPIDTuning { - kpBP @0 :List(Float32); - kpV @1 :List(Float32); - kiBP @2 :List(Float32); - kiV @3 :List(Float32); - kf @4 :Float32; - } - - struct LateralTorqueTuning { - useSteeringAngle @0 :Bool; - kp @1 :Float32; - ki @2 :Float32; - friction @3 :Float32; - kf @4 :Float32; - steeringAngleDeadzoneDeg @5 :Float32; - latAccelFactor @6 :Float32; - latAccelOffset @7 :Float32; - } - - struct LongitudinalPIDTuning { - kpBP @0 :List(Float32); - kpV @1 :List(Float32); - kiBP @2 :List(Float32); - kiV @3 :List(Float32); - kf @6 :Float32; - deadzoneBPDEPRECATED @4 :List(Float32); - deadzoneVDEPRECATED @5 :List(Float32); - } - - struct LateralINDITuning { - outerLoopGainBP @4 :List(Float32); - outerLoopGainV @5 :List(Float32); - innerLoopGainBP @6 :List(Float32); - innerLoopGainV @7 :List(Float32); - timeConstantBP @8 :List(Float32); - timeConstantV @9 :List(Float32); - actuatorEffectivenessBP @10 :List(Float32); - actuatorEffectivenessV @11 :List(Float32); - - outerLoopGainDEPRECATED @0 :Float32; - innerLoopGainDEPRECATED @1 :Float32; - timeConstantDEPRECATED @2 :Float32; - actuatorEffectivenessDEPRECATED @3 :Float32; - } - - struct LateralLQRTuning { - scale @0 :Float32; - ki @1 :Float32; - dcGain @2 :Float32; - - # State space system - a @3 :List(Float32); - b @4 :List(Float32); - c @5 :List(Float32); - - k @6 :List(Float32); # LQR gain - l @7 :List(Float32); # Kalman gain - } - - enum SafetyModel { - silent @0; - hondaNidec @1; - toyota @2; - elm327 @3; - gm @4; - hondaBoschGiraffe @5; - ford @6; - cadillac @7; - hyundai @8; - chrysler @9; - tesla @10; - subaru @11; - gmPassive @12; - mazda @13; - nissan @14; - volkswagen @15; - toyotaIpas @16; - allOutput @17; - gmAscm @18; - noOutput @19; # like silent but without silent CAN TXs - hondaBosch @20; - volkswagenPq @21; - subaruPreglobal @22; # pre-Global platform - hyundaiLegacy @23; - hyundaiCommunity @24; - volkswagenMlb @25; - hongqi @26; - body @27; - hyundaiCanfd @28; - volkswagenMqbEvo @29; - chryslerCusw @30; - psa @31; - fcaGiorgio @32; - } - - enum SteerControlType { - torque @0; - angle @1; - - curvatureDEPRECATED @2; - } - - enum TransmissionType { - unknown @0; - automatic @1; # Traditional auto, including DSG - manual @2; # True "stick shift" only - direct @3; # Electric vehicle or other direct drive - cvt @4; - } - - struct CarFw { - ecu @0 :Ecu; - fwVersion @1 :Data; - address @2 :UInt32; - subAddress @3 :UInt8; - responseAddress @4 :UInt32; - request @5 :List(Data); - brand @6 :Text; - bus @7 :UInt8; - logging @8 :Bool; - obdMultiplexing @9 :Bool; - } - - enum Ecu { - eps @0; - abs @1; - fwdRadar @2; - fwdCamera @3; - engine @4; - unknown @5; - transmission @8; # Transmission Control Module - hybrid @18; # hybrid control unit, e.g. Chrysler's HCP, Honda's IMA Control Unit, Toyota's hybrid control computer - srs @9; # airbag - gateway @10; # can gateway - hud @11; # heads up display - combinationMeter @12; # instrument cluster - electricBrakeBooster @15; - shiftByWire @16; - adas @19; - cornerRadar @21; - hvac @20; - parkingAdas @7; # parking assist system ECU, e.g. Toyota's IPAS, Hyundai's RSPA, etc. - epb @22; # electronic parking brake - telematics @23; - body @24; # body control module - - # Toyota only - dsu @6; - - # Honda only - vsa @13; # Vehicle Stability Assist - programmedFuelInjection @14; - - debug @17; - } - - enum FingerprintSource { - can @0; - fw @1; - fixed @2; - } - - enum NetworkLocation { - fwdCamera @0; # Standard/default integration at LKAS camera - gateway @1; # Integration at vehicle's CAN gateway - } - - enableGasInterceptorDEPRECATED @2 :Bool; - enableCameraDEPRECATED @4 :Bool; - enableApgsDEPRECATED @6 :Bool; - steerRateCostDEPRECATED @33 :Float32; - isPandaBlackDEPRECATED @39 :Bool; - hasStockCameraDEPRECATED @57 :Bool; - safetyParamDEPRECATED @10 :Int16; - safetyModelDEPRECATED @9 :SafetyModel; - safetyModelPassiveDEPRECATED @42 :SafetyModel = silent; - minSpeedCanDEPRECATED @51 :Float32; - communityFeatureDEPRECATED @46: Bool; - startingAccelRateDEPRECATED @53 :Float32; - steerMaxBPDEPRECATED @11 :List(Float32); - steerMaxVDEPRECATED @12 :List(Float32); - gasMaxBPDEPRECATED @13 :List(Float32); - gasMaxVDEPRECATED @14 :List(Float32); - brakeMaxBPDEPRECATED @15 :List(Float32); - brakeMaxVDEPRECATED @16 :List(Float32); - directAccelControlDEPRECATED @30 :Bool; - maxSteeringAngleDegDEPRECATED @54 :Float32; - longitudinalActuatorDelayLowerBoundDEPRECATED @61 :Float32; -} diff --git a/cereal/car.capnp b/cereal/car.capnp new file mode 120000 index 0000000000..4bc7f89b1f --- /dev/null +++ b/cereal/car.capnp @@ -0,0 +1 @@ +../opendbc_repo/opendbc/car/car.capnp \ No newline at end of file diff --git a/opendbc_repo b/opendbc_repo index a363ce1ff4..ff2ac79e07 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit a363ce1ff452e63f2e49938508d97aece4ba6a3e +Subproject commit ff2ac79e07c2d9021c2fd4fc886ca61c81cd2694 diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index 0afd0e7323..a83d5bb989 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -21,7 +21,6 @@ from opendbc.car.interfaces import CarInterfaceBase, RadarInterfaceBase from openpilot.selfdrive.pandad import can_capnp_to_list, can_list_to_can_capnp from openpilot.selfdrive.car.cruise import VCruiseHelper from openpilot.selfdrive.car.car_specific import MockCarState -from openpilot.selfdrive.car.helpers import convert_carControl, convert_to_capnp REPLAY = "REPLAY" in os.environ @@ -63,8 +62,7 @@ def can_comm_callbacks(logcan: messaging.SubSocket, sendcan: messaging.PubSocket class Car: CI: CarInterfaceBase RI: RadarInterfaceBase - CP: structs.CarParams - CP_capnp: car.CarParams + CP: car.CarParams def __init__(self, CI=None, RI=None) -> None: self.can_sock = messaging.sub_sock('can', timeout=20) @@ -98,7 +96,7 @@ class Car: cached_params_raw = self.params.get("CarParamsCache") if cached_params_raw is not None: with car.CarParams.from_bytes(cached_params_raw) as _cached_params: - cached_params = structs.CarParams(carName=_cached_params.carName, carFw=_cached_params.carFw, carVin=_cached_params.carVin) + cached_params = _cached_params self.CI = get_car(*self.can_callbacks, obd_callback(self.params), experimental_long_allowed, num_pandas, cached_params) self.RI = get_radar_interface(self.CI.CP) @@ -144,9 +142,7 @@ class Car: self.params.put("CarParamsPrevRoute", prev_cp) # Write CarParams for controls and radard - # convert to pycapnp representation for caching and logging - self.CP_capnp = convert_to_capnp(self.CP) - cp_bytes = self.CP_capnp.to_bytes() + cp_bytes = self.CP.to_bytes() self.params.put("CarParams", cp_bytes) self.params.put_nonblocking("CarParamsCache", cp_bytes) self.params.put_nonblocking("CarParamsPersistent", cp_bytes) @@ -160,19 +156,19 @@ class Car: # card is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) - def state_update(self) -> tuple[car.CarState, structs.RadarData | None]: + def state_update(self) -> tuple[car.CarState, structs.RadarDataT | None]: """carState update loop, driven by can""" can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) can_list = can_capnp_to_list(can_strs) # Update carState from CAN - CS = convert_to_capnp(self.CI.update(can_list)) + CS = self.CI.update(can_list) if self.CP.carName == 'mock': CS = self.mock_carstate.update(CS) # Update radar tracks from CAN - RD: structs.RadarData | None = self.RI.update(can_list) + RD: structs.RadarDataT | None = self.RI.update(can_list) self.sm.update(0) @@ -192,20 +188,20 @@ class Car: return CS, RD - def state_publish(self, CS: car.CarState, RD: structs.RadarData | None): + def state_publish(self, CS: car.CarState, RD: structs.RadarDataT | None): """carState and carParams publish loop""" # carParams - logged every 50 seconds (> 1 per segment) if self.sm.frame % int(50. / DT_CTRL) == 0: cp_send = messaging.new_message('carParams') cp_send.valid = True - cp_send.carParams = self.CP_capnp + cp_send.carParams = self.CP self.pm.send('carParams', cp_send) # publish new carOutput co_send = messaging.new_message('carOutput') co_send.valid = self.sm.all_checks(['carControl']) - co_send.carOutput.actuatorsOutput = convert_to_capnp(self.last_actuators_output) + co_send.carOutput.actuatorsOutput = self.last_actuators_output self.pm.send('carOutput', co_send) # kick off controlsd step while we actuate the latest carControl packet @@ -219,7 +215,7 @@ class Car: if RD is not None: tracks_msg = messaging.new_message('liveTracks') tracks_msg.valid = len(RD.errors) == 0 - tracks_msg.liveTracks = convert_to_capnp(RD) + tracks_msg.liveTracks = RD self.pm.send('liveTracks', tracks_msg) def controls_update(self, CS: car.CarState, CC: car.CarControl): @@ -235,7 +231,7 @@ class Car: if self.sm.all_alive(['carControl']): # send car controls over can now_nanos = self.can_log_mono_time if REPLAY else int(time.monotonic() * 1e9) - self.last_actuators_output, can_sends = self.CI.apply(convert_carControl(CC), now_nanos) + self.last_actuators_output, can_sends = self.CI.apply(CC, now_nanos) self.pm.send('sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid)) self.CC_prev = CC diff --git a/selfdrive/car/helpers.py b/selfdrive/car/helpers.py deleted file mode 100644 index 75e1c66d24..0000000000 --- a/selfdrive/car/helpers.py +++ /dev/null @@ -1,74 +0,0 @@ -import capnp -from typing import Any - -from cereal import car -from opendbc.car import structs - -_FIELDS = '__dataclass_fields__' # copy of dataclasses._FIELDS - - -def is_dataclass(obj): - """Similar to dataclasses.is_dataclass without instance type check checking""" - return hasattr(obj, _FIELDS) - - -def _asdictref_inner(obj) -> dict[str, Any] | Any: - if is_dataclass(obj): - ret = {} - for field in getattr(obj, _FIELDS): # similar to dataclasses.fields() - ret[field] = _asdictref_inner(getattr(obj, field)) - return ret - elif isinstance(obj, (tuple, list)): - return type(obj)(_asdictref_inner(v) for v in obj) - else: - return obj - - -def asdictref(obj) -> dict[str, Any]: - """ - Similar to dataclasses.asdict without recursive type checking and copy.deepcopy - Note that the resulting dict will contain references to the original struct as a result - """ - if not is_dataclass(obj): - raise TypeError("asdictref() should be called on dataclass instances") - - return _asdictref_inner(obj) - - -def convert_to_capnp(struct: structs.CarParams | structs.CarState | structs.CarControl.Actuators | structs.RadarData) -> capnp.lib.capnp._DynamicStructBuilder: - struct_dict = asdictref(struct) - - if isinstance(struct, structs.CarParams): - del struct_dict['lateralTuning'] - struct_capnp = car.CarParams.new_message(**struct_dict) - - # this is the only union, special handling - which = struct.lateralTuning.which() - struct_capnp.lateralTuning.init(which) - lateralTuning_dict = asdictref(getattr(struct.lateralTuning, which)) - setattr(struct_capnp.lateralTuning, which, lateralTuning_dict) - elif isinstance(struct, structs.CarState): - struct_capnp = car.CarState.new_message(**struct_dict) - elif isinstance(struct, structs.CarControl.Actuators): - struct_capnp = car.CarControl.Actuators.new_message(**struct_dict) - elif isinstance(struct, structs.RadarData): - struct_capnp = car.RadarData.new_message(**struct_dict) - else: - raise ValueError(f"Unsupported struct type: {type(struct)}") - - return struct_capnp - - -def convert_carControl(struct: capnp.lib.capnp._DynamicStructReader) -> structs.CarControl: - # TODO: recursively handle any car struct as needed - def remove_deprecated(s: dict) -> dict: - return {k: v for k, v in s.items() if not k.endswith('DEPRECATED')} - - struct_dict = struct.to_dict() - struct_dataclass = structs.CarControl(**remove_deprecated({k: v for k, v in struct_dict.items() if not isinstance(k, dict)})) - - struct_dataclass.actuators = structs.CarControl.Actuators(**remove_deprecated(struct_dict.get('actuators', {}))) - struct_dataclass.cruiseControl = structs.CarControl.CruiseControl(**remove_deprecated(struct_dict.get('cruiseControl', {}))) - struct_dataclass.hudControl = structs.CarControl.HUDControl(**remove_deprecated(struct_dict.get('hudControl', {}))) - - return struct_dataclass diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 66cf0dc696..4370ea141b 100644 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -12,7 +12,6 @@ from opendbc.car.tests.test_car_interfaces import get_fuzzy_car_interface_args from opendbc.car.fingerprints import all_known_cars from opendbc.car.fw_versions import FW_VERSIONS, FW_QUERY_CONFIGS from opendbc.car.mock.values import CAR as MOCK -from openpilot.selfdrive.car.card import convert_carControl, convert_to_capnp from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque @@ -41,6 +40,7 @@ class TestCarInterfaces: car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'], experimental_long=args['experimental_long'], docs=False) + car_params = car_params.as_reader() car_interface = CarInterface(car_params, CarController, CarState) assert car_params assert car_interface @@ -72,7 +72,7 @@ class TestCarInterfaces: # Run car interface now_nanos = 0 CC = car.CarControl.new_message(**cc_msg) - CC = convert_carControl(CC.as_reader()) + CC = CC.as_reader() for _ in range(10): car_interface.update([]) car_interface.apply(CC, now_nanos) @@ -80,7 +80,7 @@ class TestCarInterfaces: CC = car.CarControl.new_message(**cc_msg) CC.enabled = True - CC = convert_carControl(CC.as_reader()) + CC = CC.as_reader() for _ in range(10): car_interface.update([]) car_interface.apply(CC, now_nanos) @@ -89,11 +89,10 @@ class TestCarInterfaces: # Test controller initialization # TODO: wait until card refactor is merged to run controller a few times, # hypothesis also slows down significantly with just one more message draw - car_params_capnp = convert_to_capnp(car_params).as_reader() - LongControl(car_params_capnp) + LongControl(car_params) if car_params.steerControlType == CarParams.SteerControlType.angle: - LatControlAngle(car_params_capnp, car_interface) + LatControlAngle(car_params, car_interface) elif car_params.lateralTuning.which() == 'pid': - LatControlPID(car_params_capnp, car_interface) + LatControlPID(car_params, car_interface) elif car_params.lateralTuning.which() == 'torque': - LatControlTorque(car_params_capnp, car_interface) + LatControlTorque(car_params, car_interface) diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index ef54631e54..72f511b7ce 100644 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -1,6 +1,4 @@ import capnp -import copy -import dataclasses import os import pytest import random @@ -20,7 +18,6 @@ from opendbc.car.car_helpers import FRAME_FINGERPRINT, interfaces from opendbc.car.honda.values import CAR as HONDA, HondaFlags from opendbc.car.values import Platform from opendbc.car.tests.routes import non_tested_cars, routes, CarTestRoute -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.selfdrived.events import ET from openpilot.selfdrive.selfdrived.selfdrived import SelfdriveD from openpilot.selfdrive.pandad import can_capnp_to_list @@ -187,7 +184,7 @@ class TestCarModelBase(unittest.TestCase): del cls.can_msgs def setUp(self): - self.CI = self.CarInterface(copy.deepcopy(self.CP), self.CarController, self.CarState) + self.CI = self.CarInterface(self.CP.copy(), self.CarController, self.CarState) assert self.CI Params().put_bool("OpenpilotEnabledToggle", self.openpilot_enabled) @@ -195,7 +192,7 @@ class TestCarModelBase(unittest.TestCase): # TODO: check safetyModel is in release panda build self.safety = libpanda_py.libpanda - cfg = car.CarParams.SafetyConfig(**dataclasses.asdict(self.CP.safetyConfigs[-1])) + cfg = self.CP.safetyConfigs[-1] set_status = self.safety.set_safety_hooks(cfg.safetyModel.raw, cfg.safetyParam) self.assertEqual(0, set_status, f"failed to set safetyModel {cfg}") self.safety.init_tests() @@ -220,7 +217,7 @@ class TestCarModelBase(unittest.TestCase): # TODO: also check for checksum violations from can parser can_invalid_cnt = 0 can_valid = False - CC = structs.CarControl() + CC = structs.CarControl().as_reader() for i, msg in enumerate(self.can_msgs): CS = self.CI.update(can_capnp_to_list((msg.as_builder().to_bytes(),))) @@ -312,17 +309,17 @@ class TestCarModelBase(unittest.TestCase): # Make sure we can send all messages while inactive CC = structs.CarControl() - test_car_controller(CC) + test_car_controller(CC.as_reader()) # Test cancel + general messages (controls_allowed=False & cruise_engaged=True) self.safety.set_cruise_engaged_prev(True) CC = structs.CarControl(cruiseControl=structs.CarControl.CruiseControl(cancel=True)) - test_car_controller(CC) + test_car_controller(CC.as_reader()) # Test resume + general messages (controls_allowed=True & cruise_engaged=True) self.safety.set_controls_allowed(True) CC = structs.CarControl(cruiseControl=structs.CarControl.CruiseControl(resume=True)) - test_car_controller(CC) + test_car_controller(CC.as_reader()) # Skip stdout/stderr capture with pytest, causes elevated memory usage @pytest.mark.nocapture @@ -409,7 +406,7 @@ class TestCarModelBase(unittest.TestCase): selfdrived = SelfdriveD(CP=self.CP) selfdrived.initialized = True for idx, can in enumerate(self.can_msgs): - CS = convert_to_capnp(self.CI.update(can_capnp_to_list((can.as_builder().to_bytes(), )))) + CS = self.CI.update(can_capnp_to_list((can.as_builder().to_bytes(), ))).as_reader() for msg in filter(lambda m: m.src in range(64), can.can): to_send = libpanda_py.make_CANPacket(msg.address, msg.src % 4, msg.dat) ret = self.safety.safety_rx_hook(to_send) diff --git a/selfdrive/controls/lib/tests/test_latcontrol.py b/selfdrive/controls/lib/tests/test_latcontrol.py index c8c8d02751..ba4bd0faec 100644 --- a/selfdrive/controls/lib/tests/test_latcontrol.py +++ b/selfdrive/controls/lib/tests/test_latcontrol.py @@ -5,7 +5,6 @@ from opendbc.car.car_helpers import interfaces from opendbc.car.honda.values import CAR as HONDA from opendbc.car.toyota.values import CAR as TOYOTA from opendbc.car.nissan.values import CAR as NISSAN -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle @@ -21,7 +20,6 @@ class TestLatControl: CarInterface, CarController, CarState, RadarInterface = interfaces[car_name] CP = CarInterface.get_non_essential_params(car_name) CI = CarInterface(CP, CarController, CarState) - CP = convert_to_capnp(CP) VM = VehicleModel(CP) controller = controller(CP.as_reader(), CI) diff --git a/selfdrive/controls/lib/tests/test_vehicle_model.py b/selfdrive/controls/lib/tests/test_vehicle_model.py index b58bdbe522..d15519a866 100644 --- a/selfdrive/controls/lib/tests/test_vehicle_model.py +++ b/selfdrive/controls/lib/tests/test_vehicle_model.py @@ -5,14 +5,13 @@ import numpy as np from opendbc.car.honda.interface import CarInterface from opendbc.car.honda.values import CAR -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel, dyn_ss_sol, create_dyn_state_matrices class TestVehicleModel: def setup_method(self): CP = CarInterface.get_non_essential_params(CAR.HONDA_CIVIC) - self.VM = VehicleModel(convert_to_capnp(CP)) + self.VM = VehicleModel(CP) def test_round_trip_yaw_rate(self): # TODO: fix VM to work at zero speed diff --git a/selfdrive/debug/format_fingerprints.py b/selfdrive/debug/format_fingerprints.py index ae1ed06b75..7207bd1ef1 100755 --- a/selfdrive/debug/format_fingerprints.py +++ b/selfdrive/debug/format_fingerprints.py @@ -2,12 +2,16 @@ import jinja2 import os +from cereal import car from openpilot.common.basedir import BASEDIR from opendbc.car.interfaces import get_interface_attr +Ecu = car.CarParams.Ecu + CARS = get_interface_attr('CAR') FW_VERSIONS = get_interface_attr('FW_VERSIONS') FINGERPRINTS = get_interface_attr('FINGERPRINTS') +ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} FINGERPRINTS_PY_TEMPLATE = jinja2.Template(""" {%- if FINGERPRINTS[brand] %} @@ -45,7 +49,7 @@ FW_VERSIONS{% if not FW_VERSIONS[brand] %}: dict[str, dict[tuple, list[bytes]]]{ {% for car, _ in FW_VERSIONS[brand].items() %} CAR.{{car.name}}: { {% for key, fw_versions in FW_VERSIONS[brand][car].items() %} - (Ecu.{{key[0]}}, 0x{{"%0x" | format(key[1] | int)}}, \ + (Ecu.{{ECU_NAME[key[0]]}}, 0x{{"%0x" | format(key[1] | int)}}, \ {% if key[2] %}0x{{"%0x" | format(key[2] | int)}}{% else %}{{key[2]}}{% endif %}): [ {% for fw_version in (fw_versions + extra_fw_versions.get(car, {}).get(key, [])) | unique | sort %} {{fw_version}}, @@ -67,8 +71,9 @@ def format_brand_fw_versions(brand, extra_fw_versions: None | dict[str, dict[tup comments = [line for line in f.readlines() if line.startswith("#") and "noqa" not in line] with open(fingerprints_file, "w") as f: - f.write(FINGERPRINTS_PY_TEMPLATE.render(brand=brand, comments=comments, FINGERPRINTS=FINGERPRINTS, - FW_VERSIONS=FW_VERSIONS, extra_fw_versions=extra_fw_versions)) + f.write(FINGERPRINTS_PY_TEMPLATE.render(brand=brand, comments=comments, ECU_NAME=ECU_NAME, + FINGERPRINTS=FINGERPRINTS, FW_VERSIONS=FW_VERSIONS, + extra_fw_versions=extra_fw_versions)) if __name__ == "__main__": diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index ec258f42f0..4e91d32400 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -17,7 +17,6 @@ from openpilot.common.realtime import config_realtime_process from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.transformations.model import get_warp_matrix from openpilot.system import sentry -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.selfdrive.controls.lib.desire_helper import DesireHelper from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime from openpilot.selfdrive.modeld.parse_model_outputs import Parser @@ -184,7 +183,7 @@ def main(demo=False): if demo: - CP = convert_to_capnp(get_demo_car_params()) + CP = get_demo_car_params() else: CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) cloudlog.info("modeld got CarParams: %s", CP.carName) diff --git a/selfdrive/modeld/tests/test_modeld.py b/selfdrive/modeld/tests/test_modeld.py index 1bf2977a91..145ba31ade 100644 --- a/selfdrive/modeld/tests/test_modeld.py +++ b/selfdrive/modeld/tests/test_modeld.py @@ -7,7 +7,6 @@ from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.params import Params from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.realtime import DT_MDL -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.system.manager.process_config import managed_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state @@ -24,7 +23,7 @@ class TestModeld: self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, False, CAM.width, CAM.height) self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, False, CAM.width, CAM.height) self.vipc_server.start_listener() - Params().put("CarParams", convert_to_capnp(get_demo_car_params()).to_bytes()) + Params().put("CarParams", get_demo_car_params().to_bytes()) self.sm = messaging.SubMaster(['modelV2', 'cameraOdometry']) self.pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState', 'liveCalibration']) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index b6d5ba6afd..a4392f908d 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -24,7 +24,7 @@ from openpilot.common.prefix import OpenpilotPrefix from openpilot.common.timeout import Timeout from openpilot.common.realtime import DT_CTRL from panda.python import ALTERNATIVE_EXPERIENCE -from openpilot.selfdrive.car.card import can_comm_callbacks, convert_to_capnp +from openpilot.selfdrive.car.card import can_comm_callbacks from openpilot.system.manager.process_config import managed_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state, available_streams from openpilot.selfdrive.test.process_replay.migration import migrate_all @@ -363,14 +363,14 @@ def get_car_params_callback(rc, pm, msgs, fingerprint): cached_params = None if has_cached_cp: with car.CarParams.from_bytes(cached_params_raw) as _cached_params: - cached_params = structs.CarParams(carName=_cached_params.carName, carFw=_cached_params.carFw, carVin=_cached_params.carVin) + cached_params = _cached_params CP = get_car(*can_callbacks, lambda obd: None, Params().get_bool("ExperimentalLongitudinalEnabled"), cached_params=cached_params).CP if not params.get_bool("DisengageOnAccelerator"): CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS - params.put("CarParams", convert_to_capnp(CP).to_bytes()) + params.put("CarParams", CP.to_bytes()) def selfdrived_rcv_callback(msg, cfg, frame): diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index eb67f60cc0..67d865a654 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -05570b52a90fb8bf092f7a2563d6019577e1aa5d \ No newline at end of file +cbe81fea9b820b8dd38667866aac72a8a0dae966 \ No newline at end of file diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index f27e444dbe..8a5f770636 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -13,7 +13,7 @@ from collections import Counter, defaultdict from functools import cached_property from pathlib import Path -from cereal import log +from cereal import car, log import cereal.messaging as messaging from cereal.services import SERVICE_LIST from openpilot.common.basedir import BASEDIR @@ -143,6 +143,9 @@ class TestOnroad: route = params.get("CurrentRoute", encoding="utf-8") time.sleep(0.1) + # test car params caching + params.put("CarParamsCache", car.CarParams().to_bytes()) + while len(cls.segments) < 3: segs = set() if Path(Paths.log_root()).exists(): diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index 3b9d65b85a..0ef34549b5 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -10,7 +10,6 @@ from cereal.services import SERVICE_LIST from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.mock import mock_messages from openpilot.common.params import Params -from openpilot.selfdrive.car.card import convert_to_capnp from openpilot.system.hardware.tici.power_monitor import get_power from openpilot.system.manager.process_config import managed_processes from openpilot.system.manager.manager import manager_cleanup @@ -43,7 +42,7 @@ PROCS = [ class TestPowerDraw: def setup_method(self): - Params().put("CarParams", convert_to_capnp(get_demo_car_params()).to_bytes()) + Params().put("CarParams", get_demo_car_params().to_bytes()) # wait a bit for power save to disable time.sleep(5) From 81ed1decc99ced8ffad1000568baa0dedba0ca89 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 3 Oct 2024 22:50:09 -0700 Subject: [PATCH 212/214] unused import --- selfdrive/test/process_replay/process_replay.py | 1 - 1 file changed, 1 deletion(-) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index a4392f908d..0b71a2a1b9 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -17,7 +17,6 @@ import cereal.messaging as messaging from cereal import car from cereal.services import SERVICE_LIST from msgq.visionipc import VisionIpcServer, get_endpoint_name as vipc_get_endpoint_name -from opendbc.car import structs from opendbc.car.car_helpers import get_car, interfaces from openpilot.common.params import Params from openpilot.common.prefix import OpenpilotPrefix From 66ec7880053b01b81aec13c1a91bae60c3b5529e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 3 Oct 2024 23:39:13 -0700 Subject: [PATCH 213/214] Test all of selfdrive/ (#33575) * test selfdrived! * exit() is for interactive sessions * fix * comments * more * test all of selfdrive/ * ignore what we used to * fix test_alerts * fix test_alertmanager.py --- conftest.py | 13 +++++++++++++ pyproject.toml | 9 +-------- selfdrive/selfdrived/tests/test_alertmanager.py | 4 ++-- selfdrive/selfdrived/tests/test_alerts.py | 2 +- selfdrive/test/cpp_harness.py | 3 +-- selfdrive/test/process_replay/process_replay.py | 2 +- selfdrive/ui/tests/test_runner.cc | 1 + 7 files changed, 20 insertions(+), 14 deletions(-) diff --git a/conftest.py b/conftest.py index fc4931fb54..7ee0c78943 100644 --- a/conftest.py +++ b/conftest.py @@ -8,6 +8,19 @@ from openpilot.common.prefix import OpenpilotPrefix from openpilot.system.manager import manager from openpilot.system.hardware import TICI, HARDWARE +# TODO: pytest-cpp doesn't support FAIL, and we need to create test translations in sessionstart +# pending https://github.com/pytest-dev/pytest-cpp/pull/147 +collect_ignore = [ + "selfdrive/ui/tests/test_translations", + "selfdrive/test/process_replay/test_processes.py", + "selfdrive/test/process_replay/test_regen.py", + "selfdrive/test/test_time_to_onroad.py", +] +collect_ignore_glob = [ + "selfdrive/debug/*.py", + "selfdrive/modeld/*.py", +] + def pytest_sessionstart(session): # TODO: fix tests and enable test order randomization diff --git a/pyproject.toml b/pyproject.toml index 8ed4ff855b..00b9ecf3e5 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -148,14 +148,7 @@ markers = [ ] testpaths = [ "common", - "selfdrive/pandad", - "selfdrive/car", - "selfdrive/opcar", - "selfdrive/controls", - "selfdrive/locationd", - "selfdrive/monitoring", - "selfdrive/test/longitudinal_maneuvers", - "selfdrive/test/process_replay/test_fuzzy.py", + "selfdrive", "system/updated", "system/athena", "system/camerad", diff --git a/selfdrive/selfdrived/tests/test_alertmanager.py b/selfdrive/selfdrived/tests/test_alertmanager.py index 20bf4e8903..b75a4d1cbe 100644 --- a/selfdrive/selfdrived/tests/test_alertmanager.py +++ b/selfdrive/selfdrived/tests/test_alertmanager.py @@ -1,6 +1,6 @@ import random -from openpilot.selfdrive.selfdrived.events import Alert, EVENTS +from openpilot.selfdrive.selfdrived.events import Alert, EmptyAlert, EVENTS from openpilot.selfdrive.selfdrived.alertmanager import AlertManager @@ -34,6 +34,6 @@ class TestAlertManager: AM.add_many(frame, [alert, ]) AM.process_alerts(frame, {}) - shown = AM.current_alert is not None + shown = AM.current_alert != EmptyAlert should_show = frame <= show_duration assert shown == should_show, f"{frame=} {add_duration=} {duration=}" diff --git a/selfdrive/selfdrived/tests/test_alerts.py b/selfdrive/selfdrived/tests/test_alerts.py index b916741ad0..f6a0e365fc 100644 --- a/selfdrive/selfdrived/tests/test_alerts.py +++ b/selfdrive/selfdrived/tests/test_alerts.py @@ -33,7 +33,7 @@ class TestAlerts: # Create fake objects for callback cls.CS = car.CarState.new_message() cls.CP = car.CarParams.new_message() - cfg = [c for c in CONFIGS if c.proc_name == 'controlsd'][0] + cfg = [c for c in CONFIGS if c.proc_name == 'selfdrived'][0] cls.sm = SubMaster(cfg.pubs) def test_events_defined(self): diff --git a/selfdrive/test/cpp_harness.py b/selfdrive/test/cpp_harness.py index f9d3e681a5..f9f425102b 100755 --- a/selfdrive/test/cpp_harness.py +++ b/selfdrive/test/cpp_harness.py @@ -4,8 +4,7 @@ import sys from openpilot.common.prefix import OpenpilotPrefix - with OpenpilotPrefix(): ret = subprocess.call(sys.argv[1:]) -exit(ret) +sys.exit(ret) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 0b71a2a1b9..a5008931c8 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -466,7 +466,7 @@ CONFIGS = [ "longitudinalPlan", "livePose", "liveParameters", "radarState", "modelV2", "driverCameraState", "roadCameraState", "wideRoadCameraState", "managerState", "liveTorqueParameters", "accelerometer", "gyroscope", "carOutput", - "gpsLocationExternal", "gpsLocation", "controlsState", "carControl", "driverAssistance", + "gpsLocationExternal", "gpsLocation", "controlsState", "carControl", "driverAssistance", "alertDebug", ], subs=["selfdriveState", "onroadEvents"], ignore=["logMonoTime"], diff --git a/selfdrive/ui/tests/test_runner.cc b/selfdrive/ui/tests/test_runner.cc index ac63139d17..c8cc0d3e05 100644 --- a/selfdrive/ui/tests/test_runner.cc +++ b/selfdrive/ui/tests/test_runner.cc @@ -11,6 +11,7 @@ int main(int argc, char **argv) { QApplication app(argc, argv); QString language_file = "main_test_en"; + // FIXME: pytest-cpp considers this print as a test case qDebug() << "Loading language:" << language_file; QTranslator translator; From 77f8275b19d52b325a2564d7560a537c29885f8d Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 3 Oct 2024 23:44:04 -0700 Subject: [PATCH 214/214] bump opendbc update refs --- opendbc_repo | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index ff2ac79e07..739117d561 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit ff2ac79e07c2d9021c2fd4fc886ca61c81cd2694 +Subproject commit 739117d561b265de5caf843c3f117490a9de57e6 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 67d865a654..0ec17758ac 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -cbe81fea9b820b8dd38667866aac72a8a0dae966 \ No newline at end of file +bfbdd4706abcf5757790526d99d0000644017b1e \ No newline at end of file