diff --git a/Jenkinsfile b/Jenkinsfile index f0c0cf1370..f3a63d3dec 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -208,30 +208,22 @@ node { ]) }, 'HW + Unit Tests': { - deviceStage("tici-hardware", "tici-common", ["UNSAFE=1"], [ + deviceStage("tizi-hardware", "tizi-common", ["UNSAFE=1"], [ step("build", "cd system/manager && ./build.py"), step("test pandad", "pytest selfdrive/pandad/tests/test_pandad.py", [diffPaths: ["panda", "selfdrive/pandad/"]]), step("test power draw", "pytest -s system/hardware/tici/tests/test_power_draw.py"), step("test encoder", "LD_LIBRARY_PATH=/usr/local/lib pytest system/loggerd/tests/test_encoder.py", [diffPaths: ["system/loggerd/"]]), - step("test pigeond", "pytest system/ubloxd/tests/test_pigeond.py", [diffPaths: ["system/ubloxd/"]]), step("test manager", "pytest system/manager/test/test_manager.py"), ]) }, 'loopback': { - deviceStage("loopback", "tici-loopback", ["UNSAFE=1"], [ + deviceStage("loopback", "tizi-loopback", ["UNSAFE=1"], [ step("build openpilot", "cd system/manager && ./build.py"), step("test pandad loopback", "pytest selfdrive/pandad/tests/test_pandad_loopback.py"), ]) }, - 'camerad AR0231': { - deviceStage("AR0231", "tici-ar0231", ["UNSAFE=1"], [ - step("build", "cd system/manager && ./build.py"), - step("test camerad", "pytest system/camerad/test/test_camerad.py", [timeout: 60]), - step("test exposure", "pytest system/camerad/test/test_exposure.py"), - ]) - }, 'camerad OX03C10': { - deviceStage("OX03C10", "tici-ox03c10", ["UNSAFE=1"], [ + deviceStage("OX03C10", "tizi-ox03c10", ["UNSAFE=1"], [ step("build", "cd system/manager && ./build.py"), step("test camerad", "pytest system/camerad/test/test_camerad.py", [timeout: 60]), step("test exposure", "pytest system/camerad/test/test_exposure.py"), @@ -245,17 +237,13 @@ node { ]) }, 'sensord': { - deviceStage("LSM + MMC", "tici-lsmc", ["UNSAFE=1"], [ - step("build", "cd system/manager && ./build.py"), - step("test sensord", "pytest system/sensord/tests/test_sensord.py"), - ]) - deviceStage("BMX + LSM", "tici-bmx-lsm", ["UNSAFE=1"], [ + deviceStage("LSM + MMC", "tizi-lsmc", ["UNSAFE=1"], [ step("build", "cd system/manager && ./build.py"), step("test sensord", "pytest system/sensord/tests/test_sensord.py"), ]) }, 'replay': { - deviceStage("model-replay", "tici-replay", ["UNSAFE=1"], [ + deviceStage("model-replay", "tizi-replay", ["UNSAFE=1"], [ step("build", "cd system/manager && ./build.py", [diffPaths: ["selfdrive/modeld/", "tinygrad_repo", "selfdrive/test/process_replay/model_replay.py"]]), step("model replay", "selfdrive/test/process_replay/model_replay.py", [diffPaths: ["selfdrive/modeld/", "tinygrad_repo", "selfdrive/test/process_replay/model_replay.py"]]), ]) @@ -265,7 +253,6 @@ node { step("build openpilot", "cd system/manager && ./build.py"), step("test pandad loopback", "SINGLE_PANDA=1 pytest selfdrive/pandad/tests/test_pandad_loopback.py"), step("test pandad spi", "pytest selfdrive/pandad/tests/test_pandad_spi.py"), - step("test pandad", "pytest selfdrive/pandad/tests/test_pandad.py", [diffPaths: ["panda", "selfdrive/pandad/"]]), step("test amp", "pytest system/hardware/tici/tests/test_amplifier.py"), // TODO: enable once new AGNOS is available // step("test esim", "pytest system/hardware/tici/tests/test_esim.py"), diff --git a/README.md b/README.md index f3af58f85b..9f1819afbf 100644 --- a/README.md +++ b/README.md @@ -42,10 +42,10 @@ Using openpilot in a car ------ To use openpilot in a car, you need four things: -1. **Supported Device:** a comma 3/3X, available at [comma.ai/shop](https://comma.ai/shop/comma-3x). -2. **Software:** The setup procedure for the comma 3/3X allows users to enter a URL for custom software. Use the URL `openpilot.comma.ai` to install the release version. +1. **Supported Device:** a comma 3X, available at [comma.ai/shop](https://comma.ai/shop/comma-3x). +2. **Software:** The setup procedure for the comma 3X allows users to enter a URL for custom software. Use the URL `openpilot.comma.ai` to install the release version. 3. **Supported Car:** Ensure that you have one of [the 275+ supported cars](docs/CARS.md). -4. **Car Harness:** You will also need a [car harness](https://comma.ai/shop/car-harness) to connect your comma 3/3X to your car. +4. **Car Harness:** You will also need a [car harness](https://comma.ai/shop/car-harness) to connect your comma 3X to your car. We have detailed instructions for [how to install the harness and device in a car](https://comma.ai/setup). Note that it's possible to run openpilot on [other hardware](https://blog.comma.ai/self-driving-car-for-free/), although it's not plug-and-play. diff --git a/RELEASES.md b/RELEASES.md index dacf0eaa17..d89ee24628 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,5 +1,9 @@ Version 0.10.1 (2025-09-08) ======================== +* New driving model + * World Model: removed global localization inputs + * World Model: 2x the number of parameters + * World Model: trained on 4x the number of segments * Record driving feedback using LKAS button * Honda City 2023 support thanks to drFritz! diff --git a/cereal/log.capnp b/cereal/log.capnp index e756843562..b98c1f5242 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -585,7 +585,6 @@ struct PandaState @0xa7649e2575e4591e { heartbeatLost @22 :Bool; interruptLoad @25 :Float32; fanPower @28 :UInt8; - fanStallCount @34 :UInt8; spiErrorCount @33 :UInt16; @@ -714,6 +713,7 @@ struct PandaState @0xa7649e2575e4591e { usbPowerModeDEPRECATED @12 :PeripheralState.UsbPowerModeDEPRECATED; safetyParamDEPRECATED @20 :Int16; safetyParam2DEPRECATED @26 :UInt32; + fanStallCountDEPRECATED @34 :UInt8; } struct PeripheralState { diff --git a/common/params_keys.h b/common/params_keys.h index c54600462c..211b4d550b 100644 --- a/common/params_keys.h +++ b/common/params_keys.h @@ -94,7 +94,6 @@ inline static std::unordered_map keys = { {"Offroad_NeosUpdate", {CLEAR_ON_MANAGER_START, JSON}}, {"Offroad_NoFirmware", {CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION, JSON}}, {"Offroad_Recalibration", {CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION, JSON}}, - {"Offroad_StorageMissing", {CLEAR_ON_MANAGER_START, JSON}}, {"Offroad_TemperatureTooHigh", {CLEAR_ON_MANAGER_START, JSON}}, {"Offroad_UnregisteredHardware", {CLEAR_ON_MANAGER_START, JSON}}, {"Offroad_UpdateFailed", {CLEAR_ON_MANAGER_START, JSON}}, diff --git a/docs/CONTRIBUTING.md b/docs/CONTRIBUTING.md index 154734b7fc..7583095eaf 100644 --- a/docs/CONTRIBUTING.md +++ b/docs/CONTRIBUTING.md @@ -39,7 +39,7 @@ All of these are examples of good PRs: ### First contribution [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. +There's lot of bounties that don't require a comma 3X or a car. ## Pull Requests diff --git a/docs/SAFETY.md b/docs/SAFETY.md index 18a450a395..25815e3372 100644 --- a/docs/SAFETY.md +++ b/docs/SAFETY.md @@ -16,7 +16,7 @@ industry standards of safety for Level 2 Driver Assistance Systems. In particula ISO26262 guidelines, including those from [pertinent documents](https://www.nhtsa.gov/sites/nhtsa.dot.gov/files/documents/13498a_812_573_alcsystemreport.pdf) released by NHTSA. In addition, we impose strict coding guidelines (like [MISRA C : 2012](https://www.misra.org.uk/what-is-misra/)) on parts of openpilot that are safety relevant. We also perform software-in-the-loop, -hardware-in-the-loop and in-vehicle tests before each software release. +hardware-in-the-loop, and in-vehicle tests before each software release. Following Hazard and Risk Analysis and FMEA, at a very high level, we have designed openpilot ensuring two main safety requirements. @@ -29,8 +29,18 @@ ensuring two main safety requirements. For additional safety implementation details, refer to [panda safety model](https://github.com/commaai/panda#safety-model). For vehicle specific implementation of the safety concept, refer to [opendbc/safety/safety](https://github.com/commaai/opendbc/tree/master/opendbc/safety/safety). -**Extra note**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or - not fully meeting the above requirements. +[^1]: For these actuator limits we observe ISO11270 and ISO15622. Lateral limits described there translate to 0.9 seconds of maximum actuation to achieve a 1m lateral deviation. -[^1]: For these actuator limits we observe ISO11270 and ISO15622. Lateral limits described there translate to 0.9 seconds of maximum actuation to achieve a 1m lateral deviation. +--- +### Forks of openpilot + +* Do not disable or nerf [driver monitoring](https://github.com/commaai/openpilot/tree/master/selfdrive/monitoring) +* Do not disable or nerf [excessive actuation checks](https://github.com/commaai/openpilot/tree/master/selfdrive/selfdrived/helpers.py) +* If your fork modifies any of the code in `opendbc/safety/`: + * your fork cannot use the openpilot trademark + * your fork must preserve the full [safety test suite](https://github.com/commaai/opendbc/tree/master/opendbc/safety/tests) and all tests must pass, including any new coverage required by the fork's changes + +Failure to comply with these standards will get you and your users banned from comma.ai servers. + +**comma.ai strongly discourages the use of openpilot forks with safety code either missing or not fully meeting the above requirements.** diff --git a/docs/how-to/connect-to-comma.md b/docs/how-to/connect-to-comma.md index cbaccaae6a..5f02e11599 100644 --- a/docs/how-to/connect-to-comma.md +++ b/docs/how-to/connect-to-comma.md @@ -1,11 +1,11 @@ -# connect to a comma 3/3X +# connect to a comma 3X -A comma 3/3X is a normal [Linux](https://github.com/commaai/agnos-builder) computer that exposes [SSH](https://wiki.archlinux.org/title/Secure_Shell) and a [serial console](https://wiki.archlinux.org/title/Working_with_the_serial_console). +A comma 3X is a normal [Linux](https://github.com/commaai/agnos-builder) computer that exposes [SSH](https://wiki.archlinux.org/title/Secure_Shell) and a [serial console](https://wiki.archlinux.org/title/Working_with_the_serial_console). ## Serial Console On both the comma three and 3X, the serial console is accessible from the main OBD-C port. -Connect the comma 3/3X to your computer with a normal USB C cable, or use a [comma serial](https://comma.ai/shop/comma-serial) for steady 12V power. +Connect the comma 3X to your computer with a normal USB C cable, or use a [comma serial](https://comma.ai/shop/comma-serial) for steady 12V power. On the comma three, the serial console is exposed through a UART-to-USB chip, and `tools/scripts/serial.sh` can be used to connect. @@ -45,7 +45,7 @@ In order to use ADB on your device, you'll need to perform the following steps u * Here's an example command for connecting to your device using its tethered connection: `adb connect 192.168.43.1:5555` > [!NOTE] -> The default port for ADB is 5555 on the comma 3/3X. +> The default port for ADB is 5555 on the comma 3X. For more info on ADB, see the [Android Debug Bridge (ADB) documentation](https://developer.android.com/tools/adb). diff --git a/docs/how-to/replay-a-drive.md b/docs/how-to/replay-a-drive.md index 084b6bf825..b0db36a46f 100644 --- a/docs/how-to/replay-a-drive.md +++ b/docs/how-to/replay-a-drive.md @@ -8,7 +8,7 @@ Replaying is a critical tool for openpilot development and debugging. Just run `tools/replay/replay --demo`. ## Replaying CAN data -*Hardware required: jungle and comma 3/3X* +*Hardware required: jungle and comma 3X* 1. Connect your PC to a jungle. 2. diff --git a/docs/how-to/turn-the-speed-blue.md b/docs/how-to/turn-the-speed-blue.md index 13b3b03e80..eb6e75afa2 100644 --- a/docs/how-to/turn-the-speed-blue.md +++ b/docs/how-to/turn-the-speed-blue.md @@ -3,7 +3,7 @@ In 30 minutes, we'll get an openpilot development environment set up on your computer and make some changes to openpilot's UI. -And if you have a comma 3/3X, we'll deploy the change to your device for testing. +And if you have a comma 3X, we'll deploy the change to your device for testing. ## 1. Set up your development environment diff --git a/mkdocs.yml b/mkdocs.yml index a66d1c76d4..550f807aca 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -21,7 +21,7 @@ nav: - What is openpilot?: getting-started/what-is-openpilot.md - How-to: - Turn the speed blue: how-to/turn-the-speed-blue.md - - Connect to a comma 3/3X: how-to/connect-to-comma.md + - Connect to a comma 3X: how-to/connect-to-comma.md # - Make your first pull request: how-to/make-first-pr.md #- Replay a drive: how-to/replay-a-drive.md - Concepts: diff --git a/opendbc_repo b/opendbc_repo index 0fe56bc289..7afc25d8d4 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 0fe56bc289d72d2f278e9c085f2ada6ecb13e688 +Subproject commit 7afc25d8d4096bb31e25c0b7ae0b961ea05f5394 diff --git a/panda b/panda index 3dc2138623..819fa5854e 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 3dc21386239e3073a623156b75901aa302340d6c +Subproject commit 819fa5854e2e75da7f982f7d06be69c61793d6e1 diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 5c4729ee9a..c40443d7e7 100644 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -1,15 +1,12 @@ import os -import math import hypothesis.strategies as st from hypothesis import Phase, given, settings from parameterized import parameterized from cereal import car from opendbc.car import DT_CTRL -from opendbc.car.car_helpers import interfaces from opendbc.car.structs import CarParams -from opendbc.car.tests.test_car_interfaces import get_fuzzy_car_interface_args -from opendbc.car.fw_versions import FW_VERSIONS, FW_QUERY_CONFIGS +from opendbc.car.tests.test_car_interfaces import get_fuzzy_car_interface from opendbc.car.mock.values import CAR as MOCK from opendbc.car.values import PLATFORMS from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle @@ -18,11 +15,6 @@ from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.longcontrol import LongControl from openpilot.selfdrive.test.fuzzy_generation import FuzzyGenerator -ALL_ECUS = {ecu for ecus in FW_VERSIONS.values() for ecu in ecus.keys()} -ALL_ECUS |= {ecu for config in FW_QUERY_CONFIGS.values() for ecu in config.extra_ecus} - -ALL_REQUESTS = {tuple(r.request) for config in FW_QUERY_CONFIGS.values() for r in config.requests} - MAX_EXAMPLES = int(os.environ.get('MAX_EXAMPLES', '60')) @@ -34,39 +26,8 @@ class TestCarInterfaces: phases=(Phase.reuse, Phase.generate, Phase.shrink)) @given(data=st.data()) def test_car_interfaces(self, car_name, data): - CarInterface = interfaces[car_name] - - args = get_fuzzy_car_interface_args(data.draw) - - car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'], - alpha_long=args['alpha_long'], is_release=False, docs=False) - car_params = car_params.as_reader() - car_interface = CarInterface(car_params) - assert car_params - assert car_interface - - assert car_params.mass > 1 - assert car_params.wheelbase > 0 - # centerToFront is center of gravity to front wheels, assert a reasonable range - assert car_params.wheelbase * 0.3 < car_params.centerToFront < car_params.wheelbase * 0.7 - assert car_params.maxLateralAccel > 0 - - # Longitudinal sanity checks - assert len(car_params.longitudinalTuning.kpV) == len(car_params.longitudinalTuning.kpBP) - assert len(car_params.longitudinalTuning.kiV) == len(car_params.longitudinalTuning.kiBP) - - # Lateral sanity checks - if car_params.steerControlType != CarParams.SteerControlType.angle: - tune = car_params.lateralTuning - if tune.which() == 'pid': - if car_name != MOCK.MOCK: - assert not math.isnan(tune.pid.kf) and tune.pid.kf > 0 - assert len(tune.pid.kpV) > 0 and len(tune.pid.kpV) == len(tune.pid.kpBP) - assert len(tune.pid.kiV) > 0 and len(tune.pid.kiV) == len(tune.pid.kiBP) - - elif tune.which() == 'torque': - assert not math.isnan(tune.torque.kf) and tune.torque.kf > 0 - assert not math.isnan(tune.torque.friction) and tune.torque.friction > 0 + car_interface = get_fuzzy_car_interface(car_name, data.draw) + car_params = car_interface.CP.as_reader() cc_msg = FuzzyGenerator.get_random_msg(data.draw, car.CarControl, real_floats=True) # Run car interface diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index dffe85c473..5a2814e089 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -52,10 +52,8 @@ class LatControlTorque(LatControl): actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) roll_compensation = params.roll * ACCELERATION_DUE_TO_GRAVITY curvature_deadzone = abs(VM.calc_curvature(math.radians(self.steering_angle_deadzone_deg), CS.vEgo, 0.0)) - desired_lateral_accel = desired_curvature * CS.vEgo ** 2 - # desired rate is the desired rate of change in the setpoint, not the absolute desired curvature - # desired_lateral_jerk = desired_curvature_rate * CS.vEgo ** 2 + desired_lateral_accel = desired_curvature * CS.vEgo ** 2 actual_lateral_accel = actual_curvature * CS.vEgo ** 2 lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 @@ -67,6 +65,8 @@ class LatControlTorque(LatControl): # do error correction in lateral acceleration space, convert at end to handle non-linear torque responses correctly pid_log.error = float(setpoint - measurement) ff = gravity_adjusted_lateral_accel + # latAccelOffset corrects roll compensation bias from device roll misalignment relative to car roll + ff -= self.torque_params.latAccelOffset ff += get_friction(desired_lateral_accel - actual_lateral_accel, lateral_accel_deadzone, FRICTION_THRESHOLD, self.torque_params) freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5 diff --git a/selfdrive/controls/tests/test_torqued_lat_accel_offset.py b/selfdrive/controls/tests/test_torqued_lat_accel_offset.py new file mode 100644 index 0000000000..84389856b6 --- /dev/null +++ b/selfdrive/controls/tests/test_torqued_lat_accel_offset.py @@ -0,0 +1,70 @@ +import numpy as np +from cereal import car, messaging +from opendbc.car import ACCELERATION_DUE_TO_GRAVITY +from opendbc.car import structs +from opendbc.car.lateral import get_friction, FRICTION_THRESHOLD +from openpilot.common.realtime import DT_MDL +from openpilot.selfdrive.locationd.torqued import TorqueEstimator, MIN_BUCKET_POINTS, POINTS_PER_BUCKET, STEER_BUCKET_BOUNDS + +np.random.seed(0) + +LA_ERR_STD = 1.0 +INPUT_NOISE_STD = 0.08 +V_EGO = 30.0 + +WARMUP_BUCKET_POINTS = (1.5*MIN_BUCKET_POINTS).astype(int) +STRAIGHT_ROAD_LA_BOUNDS = (0.02, 0.03) + +ROLL_BIAS_DEG = 2.0 +ROLL_COMPENSATION_BIAS = ACCELERATION_DUE_TO_GRAVITY*float(np.sin(np.deg2rad(ROLL_BIAS_DEG))) +TORQUE_TUNE = structs.CarParams.LateralTorqueTuning(latAccelFactor=2.0, latAccelOffset=0.0, friction=0.2) +TORQUE_TUNE_BIASED = structs.CarParams.LateralTorqueTuning(latAccelFactor=2.0, latAccelOffset=-ROLL_COMPENSATION_BIAS, friction=0.2) + +def generate_inputs(torque_tune, la_err_std, input_noise_std=None): + rng = np.random.default_rng(0) + steer_torques = np.concat([rng.uniform(bnd[0], bnd[1], pts) for bnd, pts in zip(STEER_BUCKET_BOUNDS, WARMUP_BUCKET_POINTS, strict=True)]) + la_errs = rng.normal(scale=la_err_std, size=steer_torques.size) + frictions = np.array([get_friction(la_err, 0.0, FRICTION_THRESHOLD, torque_tune) for la_err in la_errs]) + lat_accels = torque_tune.latAccelFactor*steer_torques + torque_tune.latAccelOffset + frictions + if input_noise_std is not None: + steer_torques += rng.normal(scale=input_noise_std, size=steer_torques.size) + lat_accels += rng.normal(scale=input_noise_std, size=steer_torques.size) + return steer_torques, lat_accels + +def get_warmed_up_estimator(steer_torques, lat_accels): + est = TorqueEstimator(car.CarParams()) + for steer_torque, lat_accel in zip(steer_torques, lat_accels, strict=True): + est.filtered_points.add_point(steer_torque, lat_accel) + return est + +def simulate_straight_road_msgs(est): + carControl = messaging.new_message('carControl').carControl + carOutput = messaging.new_message('carOutput').carOutput + carState = messaging.new_message('carState').carState + livePose = messaging.new_message('livePose').livePose + carControl.latActive = True + carState.vEgo = V_EGO + carState.steeringPressed = False + ts = DT_MDL*np.arange(2*POINTS_PER_BUCKET) + steer_torques = np.concat((np.linspace(-0.03, -0.02, POINTS_PER_BUCKET), np.linspace(0.02, 0.03, POINTS_PER_BUCKET))) + lat_accels = TORQUE_TUNE.latAccelFactor * steer_torques + for t, steer_torque, lat_accel in zip(ts, steer_torques, lat_accels, strict=True): + carOutput.actuatorsOutput.torque = float(-steer_torque) + livePose.orientationNED.x = float(np.deg2rad(ROLL_BIAS_DEG)) + livePose.angularVelocityDevice.z = float(lat_accel / V_EGO) + for which, msg in (('carControl', carControl), ('carOutput', carOutput), ('carState', carState), ('livePose', livePose)): + est.handle_log(t, which, msg) + +def test_estimated_offset(): + steer_torques, lat_accels = generate_inputs(TORQUE_TUNE_BIASED, la_err_std=LA_ERR_STD, input_noise_std=INPUT_NOISE_STD) + est = get_warmed_up_estimator(steer_torques, lat_accels) + msg = est.get_msg() + # TODO add lataccelfactor and friction check when we have more accurate estimates + assert abs(msg.liveTorqueParameters.latAccelOffsetRaw - TORQUE_TUNE_BIASED.latAccelOffset) < 0.1 + +def test_straight_road_roll_bias(): + steer_torques, lat_accels = generate_inputs(TORQUE_TUNE, la_err_std=LA_ERR_STD, input_noise_std=INPUT_NOISE_STD) + est = get_warmed_up_estimator(steer_torques, lat_accels) + simulate_straight_road_msgs(est) + msg = est.get_msg() + assert (msg.liveTorqueParameters.latAccelOffsetRaw < -0.05) and np.isfinite(msg.liveTorqueParameters.latAccelOffsetRaw) diff --git a/selfdrive/modeld/constants.py b/selfdrive/modeld/constants.py index 5ca0a86bc8..ff7e1d8600 100644 --- a/selfdrive/modeld/constants.py +++ b/selfdrive/modeld/constants.py @@ -13,12 +13,9 @@ class ModelConstants: META_T_IDXS = [2., 4., 6., 8., 10.] # model inputs constants - MODEL_FREQ = 20 - HISTORY_FREQ = 5 - HISTORY_LEN_SECONDS = 5 - TEMPORAL_SKIP = MODEL_FREQ // HISTORY_FREQ - FULL_HISTORY_BUFFER_LEN = MODEL_FREQ * HISTORY_LEN_SECONDS - INPUT_HISTORY_BUFFER_LEN = HISTORY_FREQ * HISTORY_LEN_SECONDS + N_FRAMES = 2 + MODEL_RUN_FREQ = 20 + MODEL_CONTEXT_FREQ = 5 # "model_trained_fps" FEATURE_LEN = 512 diff --git a/selfdrive/modeld/fill_model_msg.py b/selfdrive/modeld/fill_model_msg.py index a2b54b420e..82c4c92b1d 100644 --- a/selfdrive/modeld/fill_model_msg.py +++ b/selfdrive/modeld/fill_model_msg.py @@ -149,7 +149,7 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D meta.hardBrakePredicted = hard_brake_predicted.item() # confidence - if vipc_frame_id % (2*ModelConstants.MODEL_FREQ) == 0: + if vipc_frame_id % (2*ModelConstants.MODEL_RUN_FREQ) == 0: # any disengage prob brake_disengage_probs = net_output_data['meta'][0,Meta.BRAKE_DISENGAGE] gas_disengage_probs = net_output_data['meta'][0,Meta.GAS_DISENGAGE] diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index 8bc8bf01ab..e08fc30c2e 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -77,6 +77,64 @@ class FrameMeta: if vipc is not None: self.frame_id, self.timestamp_sof, self.timestamp_eof = vipc.frame_id, vipc.timestamp_sof, vipc.timestamp_eof +class InputQueues: + def __init__ (self, model_fps, env_fps, n_frames_input): + assert env_fps % model_fps == 0 + assert env_fps >= model_fps + self.model_fps = model_fps + self.env_fps = env_fps + self.n_frames_input = n_frames_input + + self.dtypes = {} + self.shapes = {} + self.q = {} + + def update_dtypes_and_shapes(self, input_dtypes, input_shapes) -> None: + self.dtypes.update(input_dtypes) + if self.env_fps == self.model_fps: + self.shapes.update(input_shapes) + else: + for k in input_shapes: + shape = list(input_shapes[k]) + if 'img' in k: + n_channels = shape[1] // self.n_frames_input + shape[1] = (self.env_fps // self.model_fps + (self.n_frames_input - 1)) * n_channels + else: + shape[1] = (self.env_fps // self.model_fps) * shape[1] + self.shapes[k] = tuple(shape) + + def reset(self) -> None: + self.q = {k: np.zeros(self.shapes[k], dtype=self.dtypes[k]) for k in self.dtypes.keys()} + + def enqueue(self, inputs:dict[str, np.ndarray]) -> None: + for k in inputs.keys(): + if inputs[k].dtype != self.dtypes[k]: + raise ValueError(f'supplied input <{k}({inputs[k].dtype})> has wrong dtype, expected {self.dtypes[k]}') + input_shape = list(self.shapes[k]) + input_shape[1] = -1 + single_input = inputs[k].reshape(tuple(input_shape)) + sz = single_input.shape[1] + self.q[k][:,:-sz] = self.q[k][:,sz:] + self.q[k][:,-sz:] = single_input + + def get(self, *names) -> dict[str, np.ndarray]: + if self.env_fps == self.model_fps: + return {k: self.q[k] for k in names} + else: + out = {} + for k in names: + shape = self.shapes[k] + if 'img' in k: + n_channels = shape[1] // (self.env_fps // self.model_fps + (self.n_frames_input - 1)) + out[k] = np.concatenate([self.q[k][:, s:s+n_channels] for s in np.linspace(0, shape[1] - n_channels, self.n_frames_input, dtype=int)], axis=1) + elif 'pulse' in k: + # any pulse within interval counts + out[k] = self.q[k].reshape((shape[0], shape[1] * self.model_fps // self.env_fps, self.env_fps // self.model_fps, -1)).max(axis=2) + else: + idxs = np.arange(-1, -shape[1], -self.env_fps // self.model_fps)[::-1] + out[k] = self.q[k][:, idxs] + return out + class ModelState: frames: dict[str, DrivingModelFrame] inputs: dict[str, np.ndarray] @@ -97,19 +155,15 @@ class ModelState: self.policy_output_slices = policy_metadata['output_slices'] policy_output_size = policy_metadata['output_shapes']['outputs'][1] - self.frames = {name: DrivingModelFrame(context, ModelConstants.TEMPORAL_SKIP) for name in self.vision_input_names} + self.frames = {name: DrivingModelFrame(context, ModelConstants.MODEL_RUN_FREQ//ModelConstants.MODEL_CONTEXT_FREQ) for name in self.vision_input_names} self.prev_desire = np.zeros(ModelConstants.DESIRE_LEN, dtype=np.float32) - self.full_features_buffer = np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32) - self.full_desire = np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.DESIRE_LEN), dtype=np.float32) - self.temporal_idxs = slice(-1-(ModelConstants.TEMPORAL_SKIP*(ModelConstants.INPUT_HISTORY_BUFFER_LEN-1)), None, ModelConstants.TEMPORAL_SKIP) - # policy inputs - self.numpy_inputs = { - 'desire': np.zeros((1, ModelConstants.INPUT_HISTORY_BUFFER_LEN, ModelConstants.DESIRE_LEN), dtype=np.float32), - 'traffic_convention': np.zeros((1, ModelConstants.TRAFFIC_CONVENTION_LEN), dtype=np.float32), - 'features_buffer': np.zeros((1, ModelConstants.INPUT_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32), - } + self.numpy_inputs = {k: np.zeros(self.policy_input_shapes[k], dtype=np.float32) for k in self.policy_input_shapes} + self.full_input_queues = InputQueues(ModelConstants.MODEL_CONTEXT_FREQ, ModelConstants.MODEL_RUN_FREQ, ModelConstants.N_FRAMES) + for k in ['desire_pulse', 'features_buffer']: + self.full_input_queues.update_dtypes_and_shapes({k: self.numpy_inputs[k].dtype}, {k: self.numpy_inputs[k].shape}) + self.full_input_queues.reset() # img buffers are managed in openCL transform code self.vision_inputs: dict[str, Tensor] = {} @@ -131,15 +185,10 @@ class ModelState: def run(self, bufs: dict[str, VisionBuf], transforms: dict[str, np.ndarray], 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 - new_desire = np.where(inputs['desire'] - self.prev_desire > .99, inputs['desire'], 0) - self.prev_desire[:] = inputs['desire'] - - self.full_desire[0,:-1] = self.full_desire[0,1:] - self.full_desire[0,-1] = new_desire - self.numpy_inputs['desire'][:] = self.full_desire.reshape((1,ModelConstants.INPUT_HISTORY_BUFFER_LEN,ModelConstants.TEMPORAL_SKIP,-1)).max(axis=2) + inputs['desire_pulse'][0] = 0 + new_desire = np.where(inputs['desire_pulse'] - self.prev_desire > .99, inputs['desire_pulse'], 0) + self.prev_desire[:] = inputs['desire_pulse'] - self.numpy_inputs['traffic_convention'][:] = inputs['traffic_convention'] imgs_cl = {name: self.frames[name].prepare(bufs[name], transforms[name].flatten()) for name in self.vision_input_names} if TICI and not USBGPU: @@ -158,9 +207,10 @@ class ModelState: self.vision_output = self.vision_run(**self.vision_inputs).contiguous().realize().uop.base.buffer.numpy() vision_outputs_dict = self.parser.parse_vision_outputs(self.slice_outputs(self.vision_output, self.vision_output_slices)) - self.full_features_buffer[0,:-1] = self.full_features_buffer[0,1:] - self.full_features_buffer[0,-1] = vision_outputs_dict['hidden_state'][0, :] - self.numpy_inputs['features_buffer'][:] = self.full_features_buffer[0, self.temporal_idxs] + self.full_input_queues.enqueue({'features_buffer': vision_outputs_dict['hidden_state'], 'desire_pulse': new_desire}) + for k in ['desire_pulse', 'features_buffer']: + self.numpy_inputs[k][:] = self.full_input_queues.get(k)[k] + self.numpy_inputs['traffic_convention'][:] = inputs['traffic_convention'] self.policy_output = self.policy_run(**self.policy_inputs).contiguous().realize().uop.base.buffer.numpy() policy_outputs_dict = self.parser.parse_policy_outputs(self.slice_outputs(self.policy_output, self.policy_output_slices)) @@ -218,7 +268,7 @@ def main(demo=False): params = Params() # setup filter to track dropped frames - frame_dropped_filter = FirstOrderFilter(0., 10., 1. / ModelConstants.MODEL_FREQ) + frame_dropped_filter = FirstOrderFilter(0., 10., 1. / ModelConstants.MODEL_RUN_FREQ) frame_id = 0 last_vipc_frame_id = 0 run_count = 0 @@ -313,7 +363,7 @@ def main(demo=False): bufs = {name: buf_extra if 'big' in name else buf_main for name in model.vision_input_names} transforms = {name: model_transform_extra if 'big' in name else model_transform_main for name in model.vision_input_names} inputs:dict[str, np.ndarray] = { - 'desire': vec_desire, + 'desire_pulse': vec_desire, 'traffic_convention': traffic_convention, } diff --git a/selfdrive/modeld/models/driving_policy.onnx b/selfdrive/modeld/models/driving_policy.onnx index 867a0d3b9b..7b87846748 100644 --- a/selfdrive/modeld/models/driving_policy.onnx +++ b/selfdrive/modeld/models/driving_policy.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:04b763fb71efe57a8a4c4168a8043ecd58939015026ded0dc755ded6905ac251 -size 12343523 +oid sha256:ebb38a934d6472c061cc6010f46d9720ca132d631a47e585a893bdd41ade2419 +size 12343535 diff --git a/selfdrive/modeld/models/driving_vision.onnx b/selfdrive/modeld/models/driving_vision.onnx index ce0dc927e7..4b4fa05df8 100644 --- a/selfdrive/modeld/models/driving_vision.onnx +++ b/selfdrive/modeld/models/driving_vision.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:e66bb8d53eced3786ed71a59b55ffc6810944cb217f0518621cc76303260a1ef +oid sha256:befac016a247b7ad5dc5b55d339d127774ed7bd2b848f1583f72aa4caee37781 size 46271991 diff --git a/selfdrive/pandad/pandad.cc b/selfdrive/pandad/pandad.cc index faaeb15319..8289df5491 100644 --- a/selfdrive/pandad/pandad.cc +++ b/selfdrive/pandad/pandad.cc @@ -152,7 +152,6 @@ void fill_panda_state(cereal::PandaState::Builder &ps, cereal::PandaState::Panda ps.setHarnessStatus(cereal::PandaState::HarnessStatus(health.car_harness_status_pkt)); ps.setInterruptLoad(health.interrupt_load_pkt); ps.setFanPower(health.fan_power); - ps.setFanStallCount(health.fan_stall_count); ps.setSafetyRxChecksInvalid((bool)(health.safety_rx_checks_invalid_pkt)); ps.setSpiErrorCount(health.spi_error_count_pkt); ps.setSbu1Voltage(health.sbu1_voltage_mV / 1000.0f); diff --git a/selfdrive/pandad/pandad.py b/selfdrive/pandad/pandad.py index 4e49813f5d..d75af283f2 100755 --- a/selfdrive/pandad/pandad.py +++ b/selfdrive/pandad/pandad.py @@ -85,11 +85,6 @@ def main() -> None: cloudlog.event("pandad.flash_and_connect", count=count) params.remove("PandaSignatures") - # TODO: remove this in the next AGNOS - # wait until USB is up before counting - if time.monotonic() < 60.: - no_internal_panda_count = 0 - # Handle missing internal panda if no_internal_panda_count > 0: if no_internal_panda_count == 3: diff --git a/selfdrive/pandad/tests/bootstub.panda.bin b/selfdrive/pandad/tests/bootstub.panda.bin deleted file mode 100755 index 43db537061..0000000000 Binary files a/selfdrive/pandad/tests/bootstub.panda.bin and /dev/null differ diff --git a/selfdrive/pandad/tests/test_pandad.py b/selfdrive/pandad/tests/test_pandad.py index 87f30e4793..6a7359fd85 100644 --- a/selfdrive/pandad/tests/test_pandad.py +++ b/selfdrive/pandad/tests/test_pandad.py @@ -22,8 +22,6 @@ class TestPandad: if len(Panda.list()) == 0: self._run_test(60) - self.spi = HARDWARE.get_device_type() != 'tici' - def teardown_method(self): managed_processes['pandad'].stop() @@ -106,11 +104,9 @@ class TestPandad: # - 0.2s pandad -> pandad # - plus some buffer print("startup times", ts, sum(ts) / len(ts)) - assert 0.1 < (sum(ts)/len(ts)) < (0.7 if self.spi else 5.0) + assert 0.1 < (sum(ts)/len(ts)) < 0.7 def test_protocol_version_check(self): - if not self.spi: - pytest.skip("SPI test") # flash old fw fn = os.path.join(HERE, "bootstub.panda_h7_spiv0.bin") self._flash_bootstub_and_test(fn, expect_mismatch=True) diff --git a/selfdrive/pandad/tests/test_pandad_spi.py b/selfdrive/pandad/tests/test_pandad_spi.py index 9f7cc3b029..da4b181993 100644 --- a/selfdrive/pandad/tests/test_pandad_spi.py +++ b/selfdrive/pandad/tests/test_pandad_spi.py @@ -6,7 +6,6 @@ import random import cereal.messaging as messaging from cereal.services import SERVICE_LIST -from openpilot.system.hardware import HARDWARE from openpilot.selfdrive.test.helpers import with_processes from openpilot.selfdrive.pandad.tests.test_pandad_loopback import setup_pandad, send_random_can_messages @@ -16,8 +15,6 @@ JUNGLE_SPAM = "JUNGLE_SPAM" in os.environ class TestBoarddSpi: @classmethod def setup_class(cls): - if HARDWARE.get_device_type() == 'tici': - pytest.skip("only for spi pandas") os.environ['STARTED'] = '1' os.environ['SPI_ERR_PROB'] = '0.001' if not JUNGLE_SPAM: diff --git a/selfdrive/selfdrived/alerts_offroad.json b/selfdrive/selfdrived/alerts_offroad.json index 42aca22008..3d97135f60 100644 --- a/selfdrive/selfdrived/alerts_offroad.json +++ b/selfdrive/selfdrived/alerts_offroad.json @@ -29,10 +29,6 @@ "text": "Device failed to register with the comma.ai backend. It will not connect or upload to comma.ai servers, and receives no support from comma.ai. If this is a device purchased at comma.ai/shop, open a ticket at https://comma.ai/support.", "severity": 1 }, - "Offroad_StorageMissing": { - "text": "NVMe drive not mounted.", - "severity": 1 - }, "Offroad_CarUnrecognized": { "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 diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index cf22040e84..e9c62fe327 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -21,7 +21,6 @@ from openpilot.selfdrive.selfdrived.helpers import ExcessiveActuationCheck 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 @@ -122,13 +121,6 @@ class SelfdriveD: self.state_machine = StateMachine() self.rk = Ratekeeper(100, print_delay_threshold=None) - # some comma three with NVMe experience NVMe dropouts mid-drive that - # cause loggerd to crash on write, so ignore it only on that platform - self.ignored_processes = set() - nvme_expected = os.path.exists('/dev/nvme0n1') or (not os.path.isfile("/persist/comma/living-in-the-moment")) - if HARDWARE.get_device_type() == 'tici' and nvme_expected: - self.ignored_processes = {'loggerd', } - # 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: @@ -299,7 +291,7 @@ class SelfdriveD: if not_running != self.not_running_prev: cloudlog.event("process_not_running", not_running=not_running, error=True) self.not_running_prev = not_running - if self.sm.recv_frame['managerState'] and (not_running - self.ignored_processes): + if self.sm.recv_frame['managerState'] and not_running: self.events.add(EventName.processNotRunning) else: if not SIMULATION and not self.rk.lagging: diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 56a0fdb61a..1144b7955e 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -591,7 +591,7 @@ def get_custom_params_from_lr(lr: LogIterable, initial_state: str = "first") -> if len(live_calibration) > 0: custom_params["CalibrationParams"] = live_calibration[msg_index].as_builder().to_bytes() if len(live_parameters) > 0: - custom_params["LiveParameters"] = live_parameters[msg_index].as_builder().to_bytes() + custom_params["LiveParametersV2"] = live_parameters[msg_index].as_builder().to_bytes() if len(live_torque_parameters) > 0: custom_params["LiveTorqueParameters"] = live_torque_parameters[msg_index].as_builder().to_bytes() diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 8e4ff1e2a8..a833fadb94 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -209b47bea61e145cf2d27eb3ab650c97bcd1d33f \ No newline at end of file +afcab1abb62b9d5678342956cced4712f44e909e \ 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 422183c5d5..32aead0b4f 100755 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -29,7 +29,7 @@ UI_DELAY = 0.1 # may be slower on CI? TEST_ROUTE = "a2a0ccea32023010|2023-07-27--13-01-19" STREAMS: list[tuple[VisionStreamType, CameraConfig, bytes]] = [] -OFFROAD_ALERTS = ['Offroad_StorageMissing', 'Offroad_IsTakingSnapshot'] +OFFROAD_ALERTS = ['Offroad_IsTakingSnapshot', ] DATA: dict[str, capnp.lib.capnp._DynamicStructBuilder] = dict.fromkeys( ["carParams", "deviceState", "pandaStates", "controlsState", "selfdriveState", "liveCalibration", "modelV2", "radarState", "driverMonitoringState", "carState", diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 4f8bd7ddfc..9ec61b9b81 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -54,8 +54,7 @@ static void update_state(UIState *s) { } if (sm.updated("wideRoadCameraState")) { auto cam_state = sm["wideRoadCameraState"].getWideRoadCameraState(); - float scale = (cam_state.getSensor() == cereal::FrameData::ImageSensor::AR0231) ? 6.0f : 1.0f; - scene.light_sensor = std::max(100.0f - scale * cam_state.getExposureValPercent(), 0.0f); + scene.light_sensor = std::max(100.0f - cam_state.getExposureValPercent(), 0.0f); } else if (!sm.allAliveAndValid({"wideRoadCameraState"})) { scene.light_sensor = -1; } diff --git a/selfdrive/ui/ui_state.py b/selfdrive/ui/ui_state.py index c2bb5f77a4..c4a2c0ca11 100644 --- a/selfdrive/ui/ui_state.py +++ b/selfdrive/ui/ui_state.py @@ -105,10 +105,7 @@ class UIState: # Handle wide road camera state updates if self.sm.updated["wideRoadCameraState"]: cam_state = self.sm["wideRoadCameraState"] - - # Scale factor based on sensor type - scale = 6.0 if cam_state.sensor == 'ar0231' else 1.0 - self.light_sensor = max(100.0 - scale * cam_state.exposureValPercent, 0.0) + self.light_sensor = max(100.0 - cam_state.exposureValPercent, 0.0) elif not self.sm.alive["wideRoadCameraState"] or not self.sm.valid["wideRoadCameraState"]: self.light_sensor = -1 diff --git a/system/camerad/SConscript b/system/camerad/SConscript index fe5cf87b78..734f748a2a 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -4,7 +4,7 @@ libs = [common, 'OpenCL', messaging, visionipc, gpucommon] if arch != "Darwin": camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/spectra.cc', - 'cameras/cdm.cc', 'sensors/ar0231.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc']) + 'cameras/cdm.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/hw.h b/system/camerad/cameras/hw.h index d299627ce9..f20a1b3ade 100644 --- a/system/camerad/cameras/hw.h +++ b/system/camerad/cameras/hw.h @@ -13,7 +13,7 @@ typedef enum { ISP_BPS_PROCESSED, // fully processed image through the BPS } SpectraOutputType; -// For the comma 3/3X three camera platform +// For the comma 3X three camera platform struct CameraConfig { int camera_num; diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc index 47ae9061f4..caf7871573 100644 --- a/system/camerad/cameras/spectra.cc +++ b/system/camerad/cameras/spectra.cc @@ -1004,8 +1004,7 @@ bool SpectraCamera::openSensor() { }; // Figure out which sensor we have - if (!init_sensor_lambda(new AR0231) && - !init_sensor_lambda(new OX03C10) && + if (!init_sensor_lambda(new OX03C10) && !init_sensor_lambda(new OS04C10)) { LOGE("** sensor %d FAILED bringup, disabling", cc.camera_num); enabled = false; diff --git a/system/camerad/sensors/ar0231.cc b/system/camerad/sensors/ar0231.cc deleted file mode 100644 index e4ae29f079..0000000000 --- a/system/camerad/sensors/ar0231.cc +++ /dev/null @@ -1,136 +0,0 @@ -#include -#include - -#include "system/camerad/sensors/sensor.h" - -namespace { - -const size_t AR0231_REGISTERS_HEIGHT = 2; -// TODO: this extra height is universal and doesn't apply per camera -const size_t AR0231_STATS_HEIGHT = 2 + 8; - -const float sensor_analog_gains_AR0231[] = { - 1.0 / 8.0, 2.0 / 8.0, 2.0 / 7.0, 3.0 / 7.0, // 0, 1, 2, 3 - 3.0 / 6.0, 4.0 / 6.0, 4.0 / 5.0, 5.0 / 5.0, // 4, 5, 6, 7 - 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 - -} // namespace - -AR0231::AR0231() { - image_sensor = cereal::FrameData::ImageSensor::AR0231; - bayer_pattern = CAM_ISP_PATTERN_BAYER_GRGRGR; - pixel_size_mm = 0.003; - data_word = true; - frame_width = 1928; - frame_height = 1208; - frame_stride = (frame_width * 12 / 8) + 4; - extra_height = AR0231_REGISTERS_HEIGHT + AR0231_STATS_HEIGHT; - - registers_offset = 0; - frame_offset = AR0231_REGISTERS_HEIGHT; - stats_offset = AR0231_REGISTERS_HEIGHT + frame_height; - - start_reg_array.assign(std::begin(start_reg_array_ar0231), std::end(start_reg_array_ar0231)); - init_reg_array.assign(std::begin(init_array_ar0231), std::end(init_array_ar0231)); - probe_reg_addr = 0x3000; - probe_expected_data = 0x354; - bits_per_pixel = 12; - mipi_format = CAM_FORMAT_MIPI_RAW_12; - frame_data_type = 0x12; // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead - mclk_frequency = 19200000; //Hz - - readout_time_ns = 22850000; - - dc_gain_factor = 2.5; - dc_gain_min_weight = 0; - dc_gain_max_weight = 1; - dc_gain_on_grey = 0.2; - dc_gain_off_grey = 0.3; - exposure_time_min = 2; // with HDR, fastest ss - exposure_time_max = 0x0855; // with HDR, slowest ss, 40ms - analog_gain_min_idx = 0x1; // 0.25x - analog_gain_rec_idx = 0x6; // 0.8x - analog_gain_max_idx = 0xD; // 4.0x - analog_gain_cost_delta = 0; - analog_gain_cost_low = 0.1; - analog_gain_cost_high = 5.0; - for (int i = 0; i <= analog_gain_max_idx; i++) { - sensor_analog_gains[i] = sensor_analog_gains_AR0231[i]; - } - min_ev = exposure_time_min * sensor_analog_gains[analog_gain_min_idx]; - max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx]; - target_grey_factor = 1.0; - - black_level = 168; - color_correct_matrix = { - 0x000000af, 0x00000ff9, 0x00000fd8, - 0x00000fbc, 0x000000bb, 0x00000009, - 0x00000fb6, 0x00000fe0, 0x000000ea, - }; - for (int i = 0; i < 65; i++) { - float fx = i / 64.0; - const float gamma_k = 0.75; - const float gamma_b = 0.125; - const float mp = 0.01; // ideally midpoint should be adaptive - const float rk = 9 - 100*mp; - // poly approximation for s curve - fx = (fx > mp) ? - ((rk * (fx-mp) * (1-(gamma_k*mp+gamma_b)) * (1+1/(rk*(1-mp))) / (1+rk*(fx-mp))) + gamma_k*mp + gamma_b) : - ((rk * (fx-mp) * (gamma_k*mp+gamma_b) * (1+1/(rk*mp)) / (1-rk*(fx-mp))) + gamma_k*mp + gamma_b); - gamma_lut_rgb.push_back((uint32_t)(fx*1023.0 + 0.5)); - } - prepare_gamma_lut(); - linearization_lut = { - 0x02000000, 0x02000000, 0x02000000, 0x02000000, - 0x020007ff, 0x020007ff, 0x020007ff, 0x020007ff, - 0x02000bff, 0x02000bff, 0x02000bff, 0x02000bff, - 0x020017ff, 0x020017ff, 0x020017ff, 0x020017ff, - 0x02001bff, 0x02001bff, 0x02001bff, 0x02001bff, - 0x020023ff, 0x020023ff, 0x020023ff, 0x020023ff, - 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, - 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, - 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, - }; - linearization_pts = {0x07ff0bff, 0x17ff1bff, 0x23ff3fff, 0x3fff3fff}; - vignetting_lut = { - 0x00eaa755, 0x00cf2679, 0x00bc05e0, 0x00acc566, 0x00a1450a, 0x009984cc, 0x0095a4ad, 0x009584ac, 0x009944ca, 0x00a0c506, 0x00ac0560, 0x00bb25d9, 0x00ce2671, 0x00e90748, 0x01112889, 0x014a2a51, 0x01984cc2, - 0x00db06d8, 0x00c30618, 0x00afe57f, 0x00a0a505, 0x009524a9, 0x008d646b, 0x0089844c, 0x0089644b, 0x008d2469, 0x0094a4a5, 0x009fe4ff, 0x00af0578, 0x00c20610, 0x00d986cc, 0x00fda7ed, 0x01320990, 0x017aebd7, - 0x00d1868c, 0x00baa5d5, 0x00a7853c, 0x009844c2, 0x008cc466, 0x0085a42d, 0x0083641b, 0x0083641b, 0x0085842c, 0x008c4462, 0x0097a4bd, 0x00a6c536, 0x00b9a5cd, 0x00d06683, 0x00f1678b, 0x01226913, 0x0167ab3d, - 0x00cd0668, 0x00b625b1, 0x00a30518, 0x0093c49e, 0x00884442, 0x00830418, 0x0080e407, 0x0080c406, 0x0082e417, 0x0087c43e, 0x00932499, 0x00a22511, 0x00b525a9, 0x00cbe65f, 0x00eb0758, 0x011a68d3, 0x015daaed, - 0x00cc4662, 0x00b565ab, 0x00a24512, 0x00930498, 0x0087843c, 0x0082a415, 0x00806403, 0x00806403, 0x00828414, 0x00870438, 0x00926493, 0x00a1850c, 0x00b465a3, 0x00cb2659, 0x00ea2751, 0x011928c9, 0x015c2ae1, - 0x00cf667b, 0x00b885c4, 0x00a5652b, 0x009624b1, 0x008aa455, 0x00846423, 0x00822411, 0x00822411, 0x00844422, 0x008a2451, 0x009564ab, 0x00a48524, 0x00b785bc, 0x00ce4672, 0x00ee6773, 0x011e88f4, 0x0162eb17, - 0x00d6c6b6, 0x00bf65fb, 0x00ac4562, 0x009d04e8, 0x0091848c, 0x0089c44e, 0x00862431, 0x00860430, 0x0089844c, 0x00910488, 0x009c64e3, 0x00ab655b, 0x00be65f3, 0x00d566ab, 0x00f847c2, 0x012b2959, 0x01726b93, - 0x00e3e71f, 0x00ca0650, 0x00b705b8, 0x00a7a53d, 0x009c24e1, 0x009484a4, 0x00908484, 0x00908484, 0x009424a1, 0x009bc4de, 0x00a70538, 0x00b625b1, 0x00c90648, 0x00e26713, 0x0108e847, 0x013fe9ff, 0x018bcc5e, - 0x00f807c0, 0x00d966cb, 0x00c5862c, 0x00b625b1, 0x00aaa555, 0x00a30518, 0x009f04f8, 0x009f04f8, 0x00a2a515, 0x00aa2551, 0x00b585ac, 0x00c4a625, 0x00d846c2, 0x00f647b2, 0x0121a90d, 0x015e4af2, 0x01b8cdc6, - 0x011548aa, 0x00f1678b, 0x00d886c4, 0x00c86643, 0x00bce5e7, 0x00b545aa, 0x00b1658b, 0x00b1458a, 0x00b505a8, 0x00bc85e4, 0x00c7c63e, 0x00d786bc, 0x00efe77f, 0x0113489a, 0x0144ea27, 0x01888c44, 0x01fdcfee, - 0x013e49f2, 0x0113e89f, 0x00f5a7ad, 0x00e0c706, 0x00d30698, 0x00cb665b, 0x00c7663b, 0x00c7663b, 0x00cb0658, 0x00d2a695, 0x00dfe6ff, 0x00f467a3, 0x01122891, 0x013be9df, 0x01750ba8, 0x01cfae7d, 0x025912c8, - 0x01766bb3, 0x01446a23, 0x011fc8fe, 0x0105e82f, 0x00f467a3, 0x00e9874c, 0x00e46723, 0x00e44722, 0x00e92749, 0x00f3a79d, 0x0104c826, 0x011e48f2, 0x01424a12, 0x01738b9c, 0x01bf6dfb, 0x023611b0, 0x02ced676, - 0x01cf8e7c, 0x01866c33, 0x015aaad5, 0x013ae9d7, 0x01250928, 0x011768bb, 0x0110a885, 0x01108884, 0x0116e8b7, 0x01242921, 0x0139a9cd, 0x0158eac7, 0x01840c20, 0x01cb0e58, 0x0233719b, 0x02b9d5ce, 0x03645b22, - }; -} - -std::vector AR0231::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { - uint16_t analog_gain_reg = 0xFF00 | (new_exp_g << 4) | new_exp_g; - return { - {0x3366, analog_gain_reg}, - {0x3362, (uint16_t)(dc_gain_enabled ? 0x1 : 0x0)}, - {0x3012, (uint16_t)exposure_time}, - }; -} - -int AR0231::getSlaveAddress(int port) const { - assert(port >= 0 && port <= 2); - return (int[]){0x20, 0x30, 0x20}[port]; -} - -float AR0231::getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const { - // Cost of ev diff - float score = std::abs(desired_ev - (exp_t * exp_gain)) * 10; - // Cost of absolute gain - float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low; - score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m; - // Cost of changing gain - score += std::abs(exp_g_idx - gain_idx) * (score + 1.0) / 10.0; - return score; -} diff --git a/system/camerad/sensors/ar0231_registers.h b/system/camerad/sensors/ar0231_registers.h deleted file mode 100644 index e0872a673a..0000000000 --- a/system/camerad/sensors/ar0231_registers.h +++ /dev/null @@ -1,121 +0,0 @@ -#pragma once - -const struct i2c_random_wr_payload start_reg_array_ar0231[] = {{0x301A, 0x91C}}; -const struct i2c_random_wr_payload stop_reg_array_ar0231[] = {{0x301A, 0x918}}; - -const struct i2c_random_wr_payload init_array_ar0231[] = { - {0x301A, 0x0018}, // RESET_REGISTER - - // **NOTE**: if this is changed, readout_time_ns must be updated in the Sensor config - - // CLOCK Settings - // input clock is 19.2 / 2 * 0x37 = 528 MHz - // pixclk is 528 / 6 = 88 MHz - // full roll time is 1000/(PIXCLK/(LINE_LENGTH_PCK*FRAME_LENGTH_LINES)) = 39.99 ms - // img roll time is 1000/(PIXCLK/(LINE_LENGTH_PCK*Y_OUTPUT_CONTROL)) = 22.85 ms - {0x302A, 0x0006}, // VT_PIX_CLK_DIV - {0x302C, 0x0001}, // VT_SYS_CLK_DIV - {0x302E, 0x0002}, // PRE_PLL_CLK_DIV - {0x3030, 0x0037}, // PLL_MULTIPLIER - {0x3036, 0x000C}, // OP_PIX_CLK_DIV - {0x3038, 0x0001}, // OP_SYS_CLK_DIV - - // FORMAT - {0x3040, 0xC000}, // READ_MODE - {0x3004, 0x0000}, // X_ADDR_START_ - {0x3008, 0x0787}, // X_ADDR_END_ - {0x3002, 0x0000}, // Y_ADDR_START_ - {0x3006, 0x04B7}, // Y_ADDR_END_ - {0x3032, 0x0000}, // SCALING_MODE - {0x30A2, 0x0001}, // X_ODD_INC_ - {0x30A6, 0x0001}, // Y_ODD_INC_ - {0x3402, 0x0788}, // X_OUTPUT_CONTROL - {0x3404, 0x04B8}, // Y_OUTPUT_CONTROL - {0x3064, 0x1982}, // SMIA_TEST - {0x30BA, 0x11F2}, // DIGITAL_CTRL - - // Enable external trigger and disable GPIO outputs - {0x30CE, 0x0120}, // SLAVE_SH_SYNC_MODE | FRAME_START_MODE - {0x340A, 0xE0}, // GPIO3_INPUT_DISABLE | GPIO2_INPUT_DISABLE | GPIO1_INPUT_DISABLE - {0x340C, 0x802}, // GPIO_HIDRV_EN | GPIO0_ISEL=2 - - // Readout timing - {0x300C, 0x0672}, // LINE_LENGTH_PCK (valid for 3-exposure HDR) - {0x300A, 0x0855}, // FRAME_LENGTH_LINES - {0x3042, 0x0000}, // EXTRA_DELAY - - // Readout Settings - {0x31AE, 0x0204}, // SERIAL_FORMAT, 4-lane MIPI - {0x31AC, 0x0C0C}, // DATA_FORMAT_BITS, 12 -> 12 - {0x3342, 0x1212}, // MIPI_F1_PDT_EDT - {0x3346, 0x1212}, // MIPI_F2_PDT_EDT - {0x334A, 0x1212}, // MIPI_F3_PDT_EDT - {0x334E, 0x1212}, // MIPI_F4_PDT_EDT - {0x3344, 0x0011}, // MIPI_F1_VDT_VC - {0x3348, 0x0111}, // MIPI_F2_VDT_VC - {0x334C, 0x0211}, // MIPI_F3_VDT_VC - {0x3350, 0x0311}, // MIPI_F4_VDT_VC - {0x31B0, 0x0053}, // FRAME_PREAMBLE - {0x31B2, 0x003B}, // LINE_PREAMBLE - {0x301A, 0x001C}, // RESET_REGISTER - - // Noise Corrections - {0x3092, 0x0C24}, // ROW_NOISE_CONTROL - {0x337A, 0x0C80}, // DBLC_SCALE0 - {0x3370, 0x03B1}, // DBLC - {0x3044, 0x0400}, // DARK_CONTROL - - // Enable temperature sensor - {0x30B4, 0x0007}, // TEMPSENS0_CTRL_REG - {0x30B8, 0x0007}, // TEMPSENS1_CTRL_REG - - // Enable dead pixel correction using - // the 1D line correction scheme - {0x31E0, 0x0003}, - - // HDR Settings - {0x3082, 0x0004}, // OPERATION_MODE_CTRL - {0x3238, 0x0444}, // EXPOSURE_RATIO - - {0x1008, 0x0361}, // FINE_INTEGRATION_TIME_MIN - {0x100C, 0x0589}, // FINE_INTEGRATION_TIME2_MIN - {0x100E, 0x07B1}, // FINE_INTEGRATION_TIME3_MIN - {0x1010, 0x0139}, // FINE_INTEGRATION_TIME4_MIN - - // TODO: do these have to be lower than LINE_LENGTH_PCK? - {0x3014, 0x08CB}, // FINE_INTEGRATION_TIME_ - {0x321E, 0x0894}, // FINE_INTEGRATION_TIME2 - - {0x31D0, 0x0000}, // COMPANDING, no good in 10 bit? - {0x33DA, 0x0000}, // COMPANDING - {0x318E, 0x0200}, // PRE_HDR_GAIN_EN - - // DLO Settings - {0x3100, 0x4000}, // DLO_CONTROL0 - {0x3280, 0x0CCC}, // T1 G1 - {0x3282, 0x0CCC}, // T1 R - {0x3284, 0x0CCC}, // T1 B - {0x3286, 0x0CCC}, // T1 G2 - {0x3288, 0x0FA0}, // T2 G1 - {0x328A, 0x0FA0}, // T2 R - {0x328C, 0x0FA0}, // T2 B - {0x328E, 0x0FA0}, // T2 G2 - - // Initial Gains - {0x3022, 0x0001}, // GROUPED_PARAMETER_HOLD_ - {0x3366, 0xFF77}, // ANALOG_GAIN (1x) - - {0x3060, 0x3333}, // ANALOG_COLOR_GAIN - - {0x3362, 0x0000}, // DC GAIN - - {0x305A, 0x00F8}, // red gain - {0x3058, 0x0122}, // blue gain - {0x3056, 0x009A}, // g1 gain - {0x305C, 0x009A}, // g2 gain - - {0x3022, 0x0000}, // GROUPED_PARAMETER_HOLD_ - - // Initial Integration Time - {0x3012, 0x0005}, -}; diff --git a/system/camerad/sensors/sensor.h b/system/camerad/sensors/sensor.h index d4be3cf036..96aa8b604f 100644 --- a/system/camerad/sensors/sensor.h +++ b/system/camerad/sensors/sensor.h @@ -10,7 +10,6 @@ #include "media/cam_sensor.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" @@ -88,17 +87,6 @@ public: }; }; -class AR0231 : public SensorInfo { -public: - AR0231(); - 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; - -private: - mutable std::map> ar0231_register_lut; -}; - class OX03C10 : public SensorInfo { public: OX03C10(); diff --git a/system/hardware/base.py b/system/hardware/base.py index b457ea4e17..ce97bf294d 100644 --- a/system/hardware/base.py +++ b/system/hardware/base.py @@ -65,6 +65,10 @@ class ThermalConfig: return ret class LPABase(ABC): + @abstractmethod + def bootstrap(self) -> None: + pass + @abstractmethod def list_profiles(self) -> list[Profile]: pass @@ -89,6 +93,9 @@ class LPABase(ABC): def switch_profile(self, iccid: str) -> None: pass + def is_comma_profile(self, iccid: str) -> bool: + return any(iccid.startswith(prefix) for prefix in ('8985235',)) + class HardwareBase(ABC): @staticmethod def get_cmdline() -> dict[str, str]: diff --git a/system/hardware/esim.py b/system/hardware/esim.py index 58ead6593f..909ad41e03 100755 --- a/system/hardware/esim.py +++ b/system/hardware/esim.py @@ -3,10 +3,32 @@ import argparse import time from openpilot.system.hardware import HARDWARE +from openpilot.system.hardware.base import LPABase + + +def bootstrap(lpa: LPABase) -> None: + print('┌──────────────────────────────────────────────────────────────────────────────┐') + print('│ WARNING, PLEASE READ BEFORE PROCEEDING │') + print('│ │') + print('│ this is an irreversible operation that will remove the comma-provisioned │') + print('│ profile. │') + print('│ │') + print('│ after this operation, you must purchase a new eSIM from comma in order to │') + print('│ use the comma prime subscription again. │') + print('└──────────────────────────────────────────────────────────────────────────────┘') + print() + for severity in ('sure', '100% sure'): + print(f'are you {severity} you want to proceed? (y/N) ', end='') + confirm = input() + if confirm != 'y': + print('aborting') + exit(0) + lpa.bootstrap() if __name__ == '__main__': parser = argparse.ArgumentParser(prog='esim.py', description='manage eSIM profiles on your comma device', epilog='comma.ai') + parser.add_argument('--bootstrap', action='store_true', help='bootstrap the eUICC (required before downloading profiles)') parser.add_argument('--backend', choices=['qmi', 'at'], default='qmi', help='use the specified backend, defaults to qmi') parser.add_argument('--switch', metavar='iccid', help='switch to profile') parser.add_argument('--delete', metavar='iccid', help='delete profile (warning: this cannot be undone)') @@ -16,7 +38,10 @@ if __name__ == '__main__': mutated = False lpa = HARDWARE.get_sim_lpa() - if args.switch: + if args.bootstrap: + bootstrap(lpa) + mutated = True + elif args.switch: lpa.switch_profile(args.switch) mutated = True elif args.delete: diff --git a/system/hardware/hardwared.py b/system/hardware/hardwared.py index fad93601da..1048acfe0a 100755 --- a/system/hardware/hardwared.py +++ b/system/hardware/hardwared.py @@ -6,7 +6,6 @@ import struct import threading import time from collections import OrderedDict, namedtuple -from pathlib import Path import psutil @@ -334,12 +333,6 @@ def hardware_thread(end_event, hw_queue) -> None: # to make a different decision in your software startup_conditions["registered_device"] = PC or (params.get("DongleId") != UNREGISTERED_DONGLE_ID) - # TODO: this should move to TICI.initialize_hardware, but we currently can't import params there - if TICI and HARDWARE.get_device_type() == "tici": - if not os.path.isfile("/persist/comma/living-in-the-moment"): - if not Path("/data/media").is_mount(): - set_offroad_alert_if_changed("Offroad_StorageMissing", True) - # Handle offroad/onroad transition should_start = all(onroad_conditions.values()) if started_ts is None: diff --git a/system/hardware/tici/amplifier.py b/system/hardware/tici/amplifier.py index f6b29ec0ce..bfdcc6ddaf 100755 --- a/system/hardware/tici/amplifier.py +++ b/system/hardware/tici/amplifier.py @@ -61,18 +61,6 @@ BASE_CONFIG = [ ] CONFIGS = { - "tici": [ - AmpConfig("Right speaker output from right DAC", 0b1, 0x2C, 0, 0b11111111), - AmpConfig("Right Speaker Mixer Gain", 0b00, 0x2D, 2, 0b00001100), - AmpConfig("Right speaker output volume", 0x1c, 0x3E, 0, 0b00011111), - AmpConfig("DAI2 EQ enable", 0b1, 0x49, 1, 0b00000010), - - *configs_from_eq_params(0x84, EQParams(0x274F, 0xC0FF, 0x3BF9, 0x0B3C, 0x1656)), - *configs_from_eq_params(0x8E, EQParams(0x1009, 0xC6BF, 0x2952, 0x1C97, 0x30DF)), - *configs_from_eq_params(0x98, EQParams(0x0F75, 0xCBE5, 0x0ED2, 0x2528, 0x3E42)), - *configs_from_eq_params(0xA2, EQParams(0x091F, 0x3D4C, 0xCE11, 0x1266, 0x2807)), - *configs_from_eq_params(0xAC, EQParams(0x0A9E, 0x3F20, 0xE573, 0x0A8B, 0x3A3B)), - ], "tizi": [ AmpConfig("Left speaker output from left DAC", 0b1, 0x2B, 0, 0b11111111), AmpConfig("Right speaker output from right DAC", 0b1, 0x2C, 0, 0b11111111), diff --git a/system/hardware/tici/esim.py b/system/hardware/tici/esim.py index b489286f50..391ba45531 100644 --- a/system/hardware/tici/esim.py +++ b/system/hardware/tici/esim.py @@ -40,6 +40,7 @@ class TiciLPA(LPABase): self._process_notifications() def download_profile(self, qr: str, nickname: str | None = None) -> None: + self._check_bootstrapped() msgs = self._invoke('profile', 'download', '-a', qr) self._validate_successful(msgs) new_profile = next((m for m in msgs if m['payload']['message'] == 'es8p_meatadata_parse'), None) @@ -54,6 +55,7 @@ class TiciLPA(LPABase): self._validate_successful(self._invoke('profile', 'nickname', iccid, nickname)) def switch_profile(self, iccid: str) -> None: + self._check_bootstrapped() self._validate_profile_exists(iccid) latest = self.get_active_profile() if latest and latest.iccid == iccid: @@ -61,6 +63,33 @@ class TiciLPA(LPABase): self._validate_successful(self._invoke('profile', 'enable', iccid)) self._process_notifications() + def bootstrap(self) -> None: + """ + find all comma-provisioned profiles and delete them. they conflict with user-provisioned profiles + and must be deleted. + + **note**: this is a **very** destructive operation. you **must** purchase a new comma SIM in order + to use comma prime again. + """ + if self._is_bootstrapped(): + return + + for p in self.list_profiles(): + if self.is_comma_profile(p.iccid): + self._disable_profile(p.iccid) + self.delete_profile(p.iccid) + + def _disable_profile(self, iccid: str) -> None: + self._validate_successful(self._invoke('profile', 'disable', iccid)) + self._process_notifications() + + def _check_bootstrapped(self) -> None: + assert self._is_bootstrapped(), 'eUICC is not bootstrapped, please bootstrap before performing this operation' + + def _is_bootstrapped(self) -> bool: + """ check if any comma provisioned profiles are on the eUICC """ + return not any(self.is_comma_profile(iccid) for iccid in (p.iccid for p in self.list_profiles())) + def _invoke(self, *cmd: str): proc = subprocess.Popen(['sudo', '-E', 'lpac'] + list(cmd), stdout=subprocess.PIPE, stderr=subprocess.PIPE, env=self.env) try: diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index 35f9916c31..0f50acdc38 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -425,9 +425,6 @@ class Tici(HardwareBase): # pandad core affine_irq(3, "spi_geni") # SPI - if "tici" in self.get_device_type(): - affine_irq(3, "xhci-hcd:usb3") # aux panda USB (or potentially anything else on USB) - affine_irq(3, "xhci-hcd:usb1") # internal panda USB (also modem) try: pid = subprocess.check_output(["pgrep", "-f", "spi0"], encoding='utf8').strip() subprocess.call(["sudo", "chrt", "-f", "-p", "1", pid]) @@ -446,22 +443,20 @@ class Tici(HardwareBase): cmds = [] - if self.get_device_type() in ("tici", "tizi"): + if self.get_device_type() in ("tizi", ): # clear out old blue prime initial APN os.system('mmcli -m any --3gpp-set-initial-eps-bearer-settings="apn="') cmds += [ + # SIM hot swap + 'AT+QSIMDET=1,0', + 'AT+QSIMSTAT=1', + # configure modem as data-centric 'AT+QNVW=5280,0,"0102000000000000"', 'AT+QNVFW="/nv/item_files/ims/IMS_enable",00', 'AT+QNVFW="/nv/item_files/modem/mmode/ue_usage_setting",01', ] - if self.get_device_type() == "tizi": - # SIM hot swap, not routed on tici - cmds += [ - 'AT+QSIMDET=1,0', - 'AT+QSIMSTAT=1', - ] elif manufacturer == 'Cavli Inc.': cmds += [ 'AT^SIMSWAP=1', # use SIM slot, instead of internal eSIM @@ -492,7 +487,7 @@ class Tici(HardwareBase): # eSIM prime dest = "/etc/NetworkManager/system-connections/esim.nmconnection" - if sim_id.startswith('8985235') and not os.path.exists(dest): + if self.get_sim_lpa().is_comma_profile(sim_id) and not os.path.exists(dest): with open(Path(__file__).parent/'esim.nmconnection') as f, tempfile.NamedTemporaryFile(mode='w') as tf: dat = f.read() dat = dat.replace("sim-id=", f"sim-id={sim_id}") @@ -503,6 +498,14 @@ class Tici(HardwareBase): os.system(f"sudo cp {tf.name} {dest}") os.system(f"sudo nmcli con load {dest}") + def reboot_modem(self): + modem = self.get_modem() + for state in (0, 1): + try: + modem.Command(f'AT+CFUN={state}', math.ceil(TIMEOUT), dbus_interface=MM_MODEM, timeout=TIMEOUT) + except Exception: + pass + def get_networks(self): r = {} diff --git a/system/hardware/tici/pins.py b/system/hardware/tici/pins.py index 747278d1ec..bdbea591fb 100644 --- a/system/hardware/tici/pins.py +++ b/system/hardware/tici/pins.py @@ -1,5 +1,3 @@ -# TODO: these are also defined in a header - # GPIO pin definitions class GPIO: # both GPIO_STM_RST_N and GPIO_LTE_RST_N are misnamed, they are high to reset @@ -26,7 +24,4 @@ class GPIO: CAM2_RSTN = 12 # Sensor interrupts - BMX055_ACCEL_INT = 21 - BMX055_GYRO_INT = 23 - BMX055_MAGN_INT = 87 LSM_INT = 84 diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index db0fab884c..46b45460b5 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -32,8 +32,8 @@ class Proc: PROCS = [ Proc(['camerad'], 1.75, msgs=['roadCameraState', 'wideRoadCameraState', 'driverCameraState']), - Proc(['modeld'], 1.12, atol=0.2, msgs=['modelV2']), - Proc(['dmonitoringmodeld'], 0.6, msgs=['driverStateV2']), + Proc(['modeld'], 1.24, atol=0.2, msgs=['modelV2']), + Proc(['dmonitoringmodeld'], 0.7, msgs=['driverStateV2']), Proc(['encoderd'], 0.23, msgs=[]), ] diff --git a/system/ui/reset.py b/system/ui/reset.py index b1bf5a6b6a..a5cf1731dc 100755 --- a/system/ui/reset.py +++ b/system/ui/reset.py @@ -13,7 +13,6 @@ from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets.button import Button, ButtonStyle from openpilot.system.ui.widgets.label import gui_label, gui_text_box -NVME = "/dev/nvme0n1" USERDATA = "/dev/disk/by-partlabel/userdata" TIMEOUT = 3*60 @@ -49,10 +48,6 @@ class Reset(Widget): if PC: return - # Best effort to wipe NVME - os.system(f"sudo umount {NVME}") - os.system(f"yes | sudo mkfs.ext4 {NVME}") - # Removing data and formatting rm = os.system("sudo rm -rf /data/*") os.system(f"sudo umount {USERDATA}") diff --git a/system/updated/updated.py b/system/updated/updated.py index d1e745ec1a..a80a663ec9 100755 --- a/system/updated/updated.py +++ b/system/updated/updated.py @@ -243,12 +243,6 @@ class Updater: if b is None: b = self.get_branch(BASEDIR) b = { - ("tici", "release3"): "release-tici", - ("tici", "release3-staging"): "release-tici", - ("tici", "master"): "master-tici", - ("tici", "nightly"): "release-tici", - ("tici", "nightly-dev"): "release-tici", - ("tizi", "release3"): "release-tizi", }.get((HARDWARE.get_device_type(), b), b) return b diff --git a/tinygrad_repo b/tinygrad_repo index e146418f65..965ea59b16 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit e146418f6566301ffe8ebea093c0081409241c8d +Subproject commit 965ea59b16679793b8f48368ac24c4a0ef587e71 diff --git a/tools/auto_source.py b/tools/auto_source.py index 401929a9ad..bef6a43e53 100755 --- a/tools/auto_source.py +++ b/tools/auto_source.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 import sys -from openpilot.tools.lib.logreader import LogReader +from openpilot.tools.lib.logreader import LogReader, ReadMode def main(): @@ -9,7 +9,7 @@ def main(): sys.exit(1) log_path = sys.argv[1] - lr = LogReader(log_path, sort_by_time=True) + lr = LogReader(log_path, default_mode=ReadMode.AUTO, sort_by_time=True) print("\n".join(lr.logreader_identifiers)) diff --git a/tools/op.sh b/tools/op.sh index e83b46b2d2..54ff8e97e9 100755 --- a/tools/op.sh +++ b/tools/op.sh @@ -365,6 +365,7 @@ function op_switch() { fi BRANCH="$1" + git config --replace-all remote.origin.fetch "+refs/heads/*:refs/remotes/origin/*" git fetch "$REMOTE" "$BRANCH" git checkout -f FETCH_HEAD git checkout -B "$BRANCH" --track "$REMOTE"/"$BRANCH" diff --git a/tools/replay/SConscript b/tools/replay/SConscript index 18849407cf..99c8263a8c 100644 --- a/tools/replay/SConscript +++ b/tools/replay/SConscript @@ -12,7 +12,7 @@ else: base_libs.append('OpenCL') replay_lib_src = ["replay.cc", "consoleui.cc", "camera.cc", "filereader.cc", "logreader.cc", "framereader.cc", - "route.cc", "util.cc", "seg_mgr.cc", "timeline.cc", "api.cc"] + "route.cc", "util.cc", "seg_mgr.cc", "timeline.cc", "api.cc", "qcom_decoder.cc"] replay_lib = replay_env.Library("replay", replay_lib_src, LIBS=base_libs, FRAMEWORKS=base_frameworks) Export('replay_lib') replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'zstd', 'curl', 'yuv', 'ncurses'] + base_libs diff --git a/tools/replay/framereader.cc b/tools/replay/framereader.cc index ed88626be3..f2b1faf2c4 100644 --- a/tools/replay/framereader.cc +++ b/tools/replay/framereader.cc @@ -8,6 +8,7 @@ #include "common/util.h" #include "third_party/libyuv/include/libyuv.h" #include "tools/replay/util.h" +#include "system/hardware/hw.h" #ifdef __APPLE__ #define HW_DEVICE_TYPE AV_HWDEVICE_TYPE_VIDEOTOOLBOX @@ -37,7 +38,13 @@ struct DecoderManager { return it->second.get(); } - auto decoder = std::make_unique(); + std::unique_ptr decoder; + if (Hardware::TICI() && hw_decoder) { + decoder = std::make_unique(); + } else { + decoder = std::make_unique(); + } + if (!decoder->open(codecpar, hw_decoder)) { decoder.reset(nullptr); } @@ -114,19 +121,19 @@ bool FrameReader::get(int idx, VisionBuf *buf) { // class VideoDecoder -VideoDecoder::VideoDecoder() { +FFmpegVideoDecoder::FFmpegVideoDecoder() { av_frame_ = av_frame_alloc(); hw_frame_ = av_frame_alloc(); } -VideoDecoder::~VideoDecoder() { +FFmpegVideoDecoder::~FFmpegVideoDecoder() { if (hw_device_ctx) av_buffer_unref(&hw_device_ctx); if (decoder_ctx) avcodec_free_context(&decoder_ctx); av_frame_free(&av_frame_); av_frame_free(&hw_frame_); } -bool VideoDecoder::open(AVCodecParameters *codecpar, bool hw_decoder) { +bool FFmpegVideoDecoder::open(AVCodecParameters *codecpar, bool hw_decoder) { const AVCodec *decoder = avcodec_find_decoder(codecpar->codec_id); if (!decoder) return false; @@ -149,7 +156,7 @@ bool VideoDecoder::open(AVCodecParameters *codecpar, bool hw_decoder) { return true; } -bool VideoDecoder::initHardwareDecoder(AVHWDeviceType hw_device_type) { +bool FFmpegVideoDecoder::initHardwareDecoder(AVHWDeviceType hw_device_type) { const AVCodecHWConfig *config = nullptr; for (int i = 0; (config = avcodec_get_hw_config(decoder_ctx->codec, i)) != nullptr; i++) { if (config->methods & AV_CODEC_HW_CONFIG_METHOD_HW_DEVICE_CTX && config->device_type == hw_device_type) { @@ -175,7 +182,7 @@ bool VideoDecoder::initHardwareDecoder(AVHWDeviceType hw_device_type) { return true; } -bool VideoDecoder::decode(FrameReader *reader, int idx, VisionBuf *buf) { +bool FFmpegVideoDecoder::decode(FrameReader *reader, int idx, VisionBuf *buf) { int current_idx = idx; if (idx != reader->prev_idx + 1) { // seeking to the nearest key frame @@ -219,7 +226,7 @@ bool VideoDecoder::decode(FrameReader *reader, int idx, VisionBuf *buf) { return false; } -AVFrame *VideoDecoder::decodeFrame(AVPacket *pkt) { +AVFrame *FFmpegVideoDecoder::decodeFrame(AVPacket *pkt) { int ret = avcodec_send_packet(decoder_ctx, pkt); if (ret < 0) { rError("Error sending a packet for decoding: %d", ret); @@ -239,7 +246,7 @@ AVFrame *VideoDecoder::decodeFrame(AVPacket *pkt) { return (av_frame_->format == hw_pix_fmt) ? hw_frame_ : av_frame_; } -bool VideoDecoder::copyBuffer(AVFrame *f, VisionBuf *buf) { +bool FFmpegVideoDecoder::copyBuffer(AVFrame *f, VisionBuf *buf) { if (hw_pix_fmt == HW_PIX_FMT) { for (int i = 0; i < height/2; i++) { memcpy(buf->y + (i*2 + 0)*buf->stride, f->data[0] + (i*2 + 0)*f->linesize[0], width); @@ -256,3 +263,45 @@ bool VideoDecoder::copyBuffer(AVFrame *f, VisionBuf *buf) { } return true; } + +bool QcomVideoDecoder::open(AVCodecParameters *codecpar, bool hw_decoder) { + if (codecpar->codec_id != AV_CODEC_ID_HEVC) { + rError("Hardware decoder only supports HEVC codec"); + return false; + } + width = codecpar->width; + height = codecpar->height; + msm_vidc.init(VIDEO_DEVICE, width, height, V4L2_PIX_FMT_HEVC); + return true; +} + +bool QcomVideoDecoder::decode(FrameReader *reader, int idx, VisionBuf *buf) { + int from_idx = idx; + if (idx != reader->prev_idx + 1) { + // seeking to the nearest key frame + for (int i = idx; i >= 0; --i) { + if (reader->packets_info[i].flags & AV_PKT_FLAG_KEY) { + from_idx = i; + break; + } + } + + auto pos = reader->packets_info[from_idx].pos; + int ret = avformat_seek_file(reader->input_ctx, 0, pos, pos, pos, AVSEEK_FLAG_BYTE); + if (ret < 0) { + rError("Failed to seek to byte position %lld: %d", pos, AVERROR(ret)); + return false; + } + } + reader->prev_idx = idx; + bool result = false; + AVPacket pkt; + msm_vidc.avctx = reader->input_ctx; + for (int i = from_idx; i <= idx; ++i) { + if (av_read_frame(reader->input_ctx, &pkt) == 0) { + result = msm_vidc.decodeFrame(&pkt, buf) && (i == idx); + av_packet_unref(&pkt); + } + } + return result; +} diff --git a/tools/replay/framereader.h b/tools/replay/framereader.h index a15847e311..1fb3cdfeb1 100644 --- a/tools/replay/framereader.h +++ b/tools/replay/framereader.h @@ -6,6 +6,7 @@ #include "msgq/visionipc/visionbuf.h" #include "tools/replay/filereader.h" #include "tools/replay/util.h" +#include "tools/replay/qcom_decoder.h" extern "C" { #include @@ -40,11 +41,18 @@ public: class VideoDecoder { public: - VideoDecoder(); - ~VideoDecoder(); - bool open(AVCodecParameters *codecpar, bool hw_decoder); - bool decode(FrameReader *reader, int idx, VisionBuf *buf); + virtual ~VideoDecoder() = default; + virtual bool open(AVCodecParameters *codecpar, bool hw_decoder) = 0; + virtual bool decode(FrameReader *reader, int idx, VisionBuf *buf) = 0; int width = 0, height = 0; +}; + +class FFmpegVideoDecoder : public VideoDecoder { +public: + FFmpegVideoDecoder(); + ~FFmpegVideoDecoder() override; + bool open(AVCodecParameters *codecpar, bool hw_decoder) override; + bool decode(FrameReader *reader, int idx, VisionBuf *buf) override; private: bool initHardwareDecoder(AVHWDeviceType hw_device_type); @@ -56,3 +64,14 @@ private: AVPixelFormat hw_pix_fmt = AV_PIX_FMT_NONE; AVBufferRef *hw_device_ctx = nullptr; }; + +class QcomVideoDecoder : public VideoDecoder { +public: + QcomVideoDecoder() {}; + ~QcomVideoDecoder() override {}; + bool open(AVCodecParameters *codecpar, bool hw_decoder) override; + bool decode(FrameReader *reader, int idx, VisionBuf *buf) override; + +private: + MsmVidc msm_vidc = MsmVidc(); +}; diff --git a/tools/replay/qcom_decoder.cc b/tools/replay/qcom_decoder.cc new file mode 100644 index 0000000000..eb5409daa3 --- /dev/null +++ b/tools/replay/qcom_decoder.cc @@ -0,0 +1,346 @@ +#include "qcom_decoder.h" + +#include +#include "third_party/linux/include/v4l2-controls.h" +#include + + +#include "common/swaglog.h" +#include "common/util.h" + +// echo "0xFFFF" > /sys/kernel/debug/msm_vidc/debug_level + +static void copyBuffer(VisionBuf *src_buf, VisionBuf *dst_buf) { + // Copy Y plane + memcpy(dst_buf->y, src_buf->y, src_buf->height * src_buf->stride); + // Copy UV plane + memcpy(dst_buf->uv, src_buf->uv, src_buf->height / 2 * src_buf->stride); +} + +static void request_buffers(int fd, v4l2_buf_type buf_type, unsigned int count) { + struct v4l2_requestbuffers reqbuf = { + .count = count, + .type = buf_type, + .memory = V4L2_MEMORY_USERPTR + }; + util::safe_ioctl(fd, VIDIOC_REQBUFS, &reqbuf, "VIDIOC_REQBUFS failed"); +} + +MsmVidc::~MsmVidc() { + if (fd > 0) { + close(fd); + } +} + +bool MsmVidc::init(const char* dev, size_t width, size_t height, uint64_t codec) { + LOG("Initializing msm_vidc device %s", dev); + this->w = width; + this->h = height; + this->fd = open(dev, O_RDWR, 0); + if (fd < 0) { + LOGE("failed to open video device %s", dev); + return false; + } + subscribeEvents(); + v4l2_buf_type out_type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE; + setPlaneFormat(out_type, V4L2_PIX_FMT_HEVC); // Also allocates the output buffer + setFPS(FPS); + request_buffers(fd, out_type, OUTPUT_BUFFER_COUNT); + util::safe_ioctl(fd, VIDIOC_STREAMON, &out_type, "VIDIOC_STREAMON OUTPUT failed"); + restartCapture(); + setupPolling(); + + this->initialized = true; + return true; +} + +VisionBuf* MsmVidc::decodeFrame(AVPacket *pkt, VisionBuf *buf) { + assert(initialized && (pkt != nullptr) && (buf != nullptr)); + + this->frame_ready = false; + this->current_output_buf = buf; + bool sent_packet = false; + + while (!this->frame_ready) { + if (!sent_packet) { + int buf_index = getBufferUnlocked(); + if (buf_index >= 0) { + assert(buf_index < out_buf_cnt); + sendPacket(buf_index, pkt); + sent_packet = true; + } + } + + if (poll(pfd, nfds, -1) < 0) { + LOGE("poll() error: %d", errno); + return nullptr; + } + + if (VisionBuf* result = processEvents()) { + return result; + } + } + + return buf; +} + +VisionBuf* MsmVidc::processEvents() { + for (int idx = 0; idx < nfds; idx++) { + short revents = pfd[idx].revents; + if (!revents) continue; + + if (idx == ev[EV_VIDEO]) { + if (revents & (POLLIN | POLLRDNORM)) { + VisionBuf *result = handleCapture(); + if (result == this->current_output_buf) { + this->frame_ready = true; + } + } + if (revents & (POLLOUT | POLLWRNORM)) { + handleOutput(); + } + if (revents & POLLPRI) { + handleEvent(); + } + } else { + LOGE("Unexpected event on fd %d", pfd[idx].fd); + } + } + return nullptr; +} + +VisionBuf* MsmVidc::handleCapture() { + struct v4l2_buffer buf = {0}; + struct v4l2_plane planes[1] = {0}; + buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE; + buf.memory = V4L2_MEMORY_USERPTR; + buf.m.planes = planes; + buf.length = 1; + util::safe_ioctl(this->fd, VIDIOC_DQBUF, &buf, "VIDIOC_DQBUF CAPTURE failed"); + + if (this->reconfigure_pending || buf.m.planes[0].bytesused == 0) { + return nullptr; + } + + copyBuffer(&cap_bufs[buf.index], this->current_output_buf); + queueCaptureBuffer(buf.index); + return this->current_output_buf; +} + +bool MsmVidc::subscribeEvents() { + for (uint32_t event : subscriptions) { + struct v4l2_event_subscription sub = { .type = event}; + util::safe_ioctl(fd, VIDIOC_SUBSCRIBE_EVENT, &sub, "VIDIOC_SUBSCRIBE_EVENT failed"); + } + return true; +} + +bool MsmVidc::setPlaneFormat(enum v4l2_buf_type type, uint32_t fourcc) { + struct v4l2_format fmt = {.type = type}; + struct v4l2_pix_format_mplane *pix = &fmt.fmt.pix_mp; + *pix = { + .width = (__u32)this->w, + .height = (__u32)this->h, + .pixelformat = fourcc + }; + util::safe_ioctl(fd, VIDIOC_S_FMT, &fmt, "VIDIOC_S_FMT failed"); + if (type == V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE) { + this->out_buf_size = pix->plane_fmt[0].sizeimage; + int ion_size = this->out_buf_size * OUTPUT_BUFFER_COUNT; // Output (input) buffers are ION buffer. + this->out_buf.allocate(ion_size); // mmap rw + for (int i = 0; i < OUTPUT_BUFFER_COUNT; i++) { + this->out_buf_off[i] = i * this->out_buf_size; + this->out_buf_addr[i] = (char *)this->out_buf.addr + this->out_buf_off[i]; + this->out_buf_flag[i] = false; + } + LOGD("Set output buffer size to %d, count %d, addr %p", this->out_buf_size, OUTPUT_BUFFER_COUNT, this->out_buf.addr); + } else if (type == V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE) { + request_buffers(this->fd, type, CAPTURE_BUFFER_COUNT); + util::safe_ioctl(fd, VIDIOC_G_FMT, &fmt, "VIDIOC_G_FMT failed"); + const __u32 y_size = pix->plane_fmt[0].sizeimage; + const __u32 y_stride = pix->plane_fmt[0].bytesperline; + for (int i = 0; i < CAPTURE_BUFFER_COUNT; i++) { + size_t uv_offset = (size_t)y_stride * pix->height; + size_t required = uv_offset + (y_stride * pix->height / 2); // enough for Y + UV. For linear NV12, UV plane starts at y_stride * height. + size_t alloc_size = std::max(y_size, required); + this->cap_bufs[i].allocate(alloc_size); + this->cap_bufs[i].init_yuv(pix->width, pix->height, y_stride, uv_offset); + } + LOGD("Set capture buffer size to %d, count %d, addr %p, extradata size %d", + pix->plane_fmt[0].sizeimage, CAPTURE_BUFFER_COUNT, this->cap_bufs[0].addr, pix->plane_fmt[1].sizeimage); + } + return true; +} + +bool MsmVidc::setFPS(uint32_t fps) { + struct v4l2_streamparm streamparam = { + .type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, + .parm.output.timeperframe = {1, fps} + }; + util::safe_ioctl(fd, VIDIOC_S_PARM, &streamparam, "VIDIOC_S_PARM failed"); + return true; +} + +bool MsmVidc::restartCapture() { + // stop if already initialized + enum v4l2_buf_type type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE; + if (this->initialized) { + LOGD("Restarting capture, flushing buffers..."); + util::safe_ioctl(this->fd, VIDIOC_STREAMOFF, &type, "VIDIOC_STREAMOFF CAPTURE failed"); + struct v4l2_requestbuffers reqbuf = {.type = type, .memory = V4L2_MEMORY_USERPTR}; + util::safe_ioctl(this->fd, VIDIOC_REQBUFS, &reqbuf, "VIDIOC_REQBUFS failed"); + for (size_t i = 0; i < CAPTURE_BUFFER_COUNT; ++i) { + this->cap_bufs[i].free(); + this->cap_buf_flag[i] = false; // mark as not queued + cap_bufs[i].~VisionBuf(); + new (&cap_bufs[i]) VisionBuf(); + } + } + // setup, start and queue capture buffers + setDBP(); + setPlaneFormat(type, V4L2_PIX_FMT_NV12); + util::safe_ioctl(this->fd, VIDIOC_STREAMON, &type, "VIDIOC_STREAMON CAPTURE failed"); + for (size_t i = 0; i < CAPTURE_BUFFER_COUNT; ++i) { + queueCaptureBuffer(i); + } + + return true; +} + +bool MsmVidc::queueCaptureBuffer(int i) { + struct v4l2_buffer buf = {0}; + struct v4l2_plane planes[1] = {0}; + + buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE; + buf.memory = V4L2_MEMORY_USERPTR; + buf.index = i; + buf.m.planes = planes; + buf.length = 1; + // decoded frame plane + planes[0].m.userptr = (unsigned long)this->cap_bufs[i].addr; // no security + planes[0].length = this->cap_bufs[i].len; + planes[0].reserved[0] = this->cap_bufs[i].fd; // ION fd + planes[0].reserved[1] = 0; + planes[0].bytesused = this->cap_bufs[i].len; + planes[0].data_offset = 0; + util::safe_ioctl(this->fd, VIDIOC_QBUF, &buf, "VIDIOC_QBUF failed"); + this->cap_buf_flag[i] = true; // mark as queued + return true; +} + +bool MsmVidc::queueOutputBuffer(int i, size_t size) { + struct v4l2_buffer buf = {0}; + struct v4l2_plane planes[1] = {0}; + + buf.type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE; + buf.memory = V4L2_MEMORY_USERPTR; + buf.index = i; + buf.m.planes = planes; + buf.length = 1; + // decoded frame plane + planes[0].m.userptr = (unsigned long)this->out_buf_off[i]; // check this + planes[0].length = this->out_buf_size; + planes[0].reserved[0] = this->out_buf.fd; // ION fd + planes[0].reserved[1] = 0; + planes[0].bytesused = size; + planes[0].data_offset = 0; + assert((this->out_buf_off[i] & 0xfff) == 0); // must be 4 KiB aligned + assert(this->out_buf_size % 4096 == 0); // ditto for size + + util::safe_ioctl(this->fd, VIDIOC_QBUF, &buf, "VIDIOC_QBUF failed"); + this->out_buf_flag[i] = true; // mark as queued + return true; +} + +bool MsmVidc::setDBP() { + struct v4l2_ext_control control[2] = {0}; + struct v4l2_ext_controls controls = {0}; + control[0].id = V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_MODE; + control[0].value = 1; // V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_SECONDARY + control[1].id = V4L2_CID_MPEG_VIDC_VIDEO_DPB_COLOR_FORMAT; + control[1].value = 0; // V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_NONE + controls.count = 2; + controls.ctrl_class = V4L2_CTRL_CLASS_MPEG; + controls.controls = control; + util::safe_ioctl(fd, VIDIOC_S_EXT_CTRLS, &controls, "VIDIOC_S_EXT_CTRLS failed"); + return true; +} + +bool MsmVidc::setupPolling() { + // Initialize poll array + pfd[EV_VIDEO] = {fd, POLLIN | POLLOUT | POLLWRNORM | POLLRDNORM | POLLPRI, 0}; + ev[EV_VIDEO] = EV_VIDEO; + nfds = 1; + return true; +} + +bool MsmVidc::sendPacket(int buf_index, AVPacket *pkt) { + assert(buf_index >= 0 && buf_index < out_buf_cnt); + assert(pkt != nullptr && pkt->data != nullptr && pkt->size > 0); + // Prepare output buffer + memset(this->out_buf_addr[buf_index], 0, this->out_buf_size); + uint8_t * data = (uint8_t *)this->out_buf_addr[buf_index]; + memcpy(data, pkt->data, pkt->size); + queueOutputBuffer(buf_index, pkt->size); + return true; +} + +int MsmVidc::getBufferUnlocked() { + for (int i = 0; i < this->out_buf_cnt; i++) { + if (!out_buf_flag[i]) { + return i; + } + } + return -1; +} + + +bool MsmVidc::handleOutput() { + struct v4l2_buffer buf = {0}; + struct v4l2_plane planes[1]; + buf.type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE; + buf.memory = V4L2_MEMORY_USERPTR; + buf.m.planes = planes; + buf.length = 1; + util::safe_ioctl(this->fd, VIDIOC_DQBUF, &buf, "VIDIOC_DQBUF OUTPUT failed"); + this->out_buf_flag[buf.index] = false; // mark as not queued + return true; +} + +bool MsmVidc::handleEvent() { + // dequeue event + struct v4l2_event event = {0}; + util::safe_ioctl(this->fd, VIDIOC_DQEVENT, &event, "VIDIOC_DQEVENT failed"); + switch (event.type) { + case V4L2_EVENT_MSM_VIDC_PORT_SETTINGS_CHANGED_INSUFFICIENT: { + unsigned int *ptr = (unsigned int *)event.u.data; + unsigned int height = ptr[0]; + unsigned int width = ptr[1]; + this->w = width; + this->h = height; + LOGD("Port Reconfig received insufficient, new size %ux%u, flushing capture bufs...", width, height); // This is normal + struct v4l2_decoder_cmd dec; + dec.flags = V4L2_QCOM_CMD_FLUSH_CAPTURE; + dec.cmd = V4L2_QCOM_CMD_FLUSH; + util::safe_ioctl(this->fd, VIDIOC_DECODER_CMD, &dec, "VIDIOC_DECODER_CMD FLUSH_CAPTURE failed"); + this->reconfigure_pending = true; + LOGD("Waiting for flush done event to reconfigure capture queue"); + break; + } + + case V4L2_EVENT_MSM_VIDC_FLUSH_DONE: { + unsigned int *ptr = (unsigned int *)event.u.data; + unsigned int flags = ptr[0]; + if (flags & V4L2_QCOM_CMD_FLUSH_CAPTURE) { + if (this->reconfigure_pending) { + this->restartCapture(); + this->reconfigure_pending = false; + } + } + break; + } + default: + break; + } + return true; +} \ No newline at end of file diff --git a/tools/replay/qcom_decoder.h b/tools/replay/qcom_decoder.h new file mode 100644 index 0000000000..1d7522cc70 --- /dev/null +++ b/tools/replay/qcom_decoder.h @@ -0,0 +1,88 @@ +#pragma once + +#include +#include + +#include "msgq/visionipc/visionbuf.h" + +extern "C" { + #include + #include +} + +#define V4L2_EVENT_MSM_VIDC_START (V4L2_EVENT_PRIVATE_START + 0x00001000) +#define V4L2_EVENT_MSM_VIDC_FLUSH_DONE (V4L2_EVENT_MSM_VIDC_START + 1) +#define V4L2_EVENT_MSM_VIDC_PORT_SETTINGS_CHANGED_INSUFFICIENT (V4L2_EVENT_MSM_VIDC_START + 3) +#define V4L2_CID_MPEG_MSM_VIDC_BASE 0x00992000 +#define V4L2_CID_MPEG_VIDC_VIDEO_DPB_COLOR_FORMAT (V4L2_CID_MPEG_MSM_VIDC_BASE + 44) +#define V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_MODE (V4L2_CID_MPEG_MSM_VIDC_BASE + 22) +#define V4L2_QCOM_CMD_FLUSH_CAPTURE (1 << 1) +#define V4L2_QCOM_CMD_FLUSH (4) + +#define VIDEO_DEVICE "/dev/video32" +#define OUTPUT_BUFFER_COUNT 8 +#define CAPTURE_BUFFER_COUNT 8 +#define FPS 20 + + +class MsmVidc { +public: + MsmVidc() = default; + ~MsmVidc(); + + bool init(const char* dev, size_t width, size_t height, uint64_t codec); + VisionBuf* decodeFrame(AVPacket* pkt, VisionBuf* buf); + + AVFormatContext* avctx = nullptr; + int fd = 0; + +private: + bool initialized = false; + bool reconfigure_pending = false; + bool frame_ready = false; + + VisionBuf* current_output_buf = nullptr; + VisionBuf out_buf; // Single input buffer + VisionBuf cap_bufs[CAPTURE_BUFFER_COUNT]; // Capture (output) buffers + + size_t w = 1928, h = 1208; + size_t cap_height = 0, cap_width = 0; + + int cap_buf_size = 0; + int out_buf_size = 0; + + size_t cap_plane_off[CAPTURE_BUFFER_COUNT] = {0}; + size_t cap_plane_stride[CAPTURE_BUFFER_COUNT] = {0}; + bool cap_buf_flag[CAPTURE_BUFFER_COUNT] = {false}; + + size_t out_buf_off[OUTPUT_BUFFER_COUNT] = {0}; + void* out_buf_addr[OUTPUT_BUFFER_COUNT] = {0}; + bool out_buf_flag[OUTPUT_BUFFER_COUNT] = {false}; + const int out_buf_cnt = OUTPUT_BUFFER_COUNT; + + const int subscriptions[2] = { + V4L2_EVENT_MSM_VIDC_FLUSH_DONE, + V4L2_EVENT_MSM_VIDC_PORT_SETTINGS_CHANGED_INSUFFICIENT + }; + + enum { EV_VIDEO, EV_COUNT }; + struct pollfd pfd[EV_COUNT] = {0}; + int ev[EV_COUNT] = {-1}; + int nfds = 0; + + VisionBuf* processEvents(); + bool setupOutput(); + bool subscribeEvents(); + bool setPlaneFormat(v4l2_buf_type type, uint32_t fourcc); + bool setFPS(uint32_t fps); + bool restartCapture(); + bool queueCaptureBuffer(int i); + bool queueOutputBuffer(int i, size_t size); + bool setDBP(); + bool setupPolling(); + bool sendPacket(int buf_index, AVPacket* pkt); + int getBufferUnlocked(); + VisionBuf* handleCapture(); + bool handleOutput(); + bool handleEvent(); +}; diff --git a/uv.lock b/uv.lock index 95a60715b5..e1678029cf 100644 --- a/uv.lock +++ b/uv.lock @@ -510,27 +510,27 @@ wheels = [ [[package]] name = "fonttools" -version = "4.59.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/11/7f/29c9c3fe4246f6ad96fee52b88d0dc3a863c7563b0afc959e36d78b965dc/fonttools-4.59.1.tar.gz", hash = "sha256:74995b402ad09822a4c8002438e54940d9f1ecda898d2bb057729d7da983e4cb", size = 3534394, upload-time = "2025-08-14T16:28:14.266Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/34/62/9667599561f623d4a523cc9eb4f66f3b94b6155464110fa9aebbf90bbec7/fonttools-4.59.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4909cce2e35706f3d18c54d3dcce0414ba5e0fb436a454dffec459c61653b513", size = 2778815, upload-time = "2025-08-14T16:26:28.484Z" }, - { url = "https://files.pythonhosted.org/packages/8f/78/cc25bcb2ce86033a9df243418d175e58f1956a35047c685ef553acae67d6/fonttools-4.59.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:efbec204fa9f877641747f2d9612b2b656071390d7a7ef07a9dbf0ecf9c7195c", size = 2341631, upload-time = "2025-08-14T16:26:30.396Z" }, - { url = "https://files.pythonhosted.org/packages/a4/cc/fcbb606dd6871f457ac32f281c20bcd6cc77d9fce77b5a4e2b2afab1f500/fonttools-4.59.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:39dfd42cc2dc647b2c5469bc7a5b234d9a49e72565b96dd14ae6f11c2c59ef15", size = 5022222, upload-time = "2025-08-14T16:26:32.447Z" }, - { url = "https://files.pythonhosted.org/packages/61/96/c0b1cf2b74d08eb616a80dbf5564351fe4686147291a25f7dce8ace51eb3/fonttools-4.59.1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:b11bc177a0d428b37890825d7d025040d591aa833f85f8d8878ed183354f47df", size = 4966512, upload-time = "2025-08-14T16:26:34.621Z" }, - { url = "https://files.pythonhosted.org/packages/a4/26/51ce2e3e0835ffc2562b1b11d1fb9dafd0aca89c9041b64a9e903790a761/fonttools-4.59.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:5b9b4c35b3be45e5bc774d3fc9608bbf4f9a8d371103b858c80edbeed31dd5aa", size = 5001645, upload-time = "2025-08-14T16:26:36.876Z" }, - { url = "https://files.pythonhosted.org/packages/36/11/ef0b23f4266349b6d5ccbd1a07b7adc998d5bce925792aa5d1ec33f593e3/fonttools-4.59.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:01158376b8a418a0bae9625c476cebfcfcb5e6761e9d243b219cd58341e7afbb", size = 5113777, upload-time = "2025-08-14T16:26:39.002Z" }, - { url = "https://files.pythonhosted.org/packages/d0/da/b398fe61ef433da0a0472cdb5d4399124f7581ffe1a31b6242c91477d802/fonttools-4.59.1-cp311-cp311-win32.whl", hash = "sha256:cf7c5089d37787387123f1cb8f1793a47c5e1e3d1e4e7bfbc1cc96e0f925eabe", size = 2215076, upload-time = "2025-08-14T16:26:41.196Z" }, - { url = "https://files.pythonhosted.org/packages/94/bd/e2624d06ab94e41c7c77727b2941f1baed7edb647e63503953e6888020c9/fonttools-4.59.1-cp311-cp311-win_amd64.whl", hash = "sha256:c866eef7a0ba320486ade6c32bfc12813d1a5db8567e6904fb56d3d40acc5116", size = 2262779, upload-time = "2025-08-14T16:26:43.483Z" }, - { url = "https://files.pythonhosted.org/packages/ac/fe/6e069cc4cb8881d164a9bd956e9df555bc62d3eb36f6282e43440200009c/fonttools-4.59.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:43ab814bbba5f02a93a152ee61a04182bb5809bd2bc3609f7822e12c53ae2c91", size = 2769172, upload-time = "2025-08-14T16:26:45.729Z" }, - { url = "https://files.pythonhosted.org/packages/b9/98/ec4e03f748fefa0dd72d9d95235aff6fef16601267f4a2340f0e16b9330f/fonttools-4.59.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:4f04c3ffbfa0baafcbc550657cf83657034eb63304d27b05cff1653b448ccff6", size = 2337281, upload-time = "2025-08-14T16:26:47.921Z" }, - { url = "https://files.pythonhosted.org/packages/8b/b1/890360a7e3d04a30ba50b267aca2783f4c1364363797e892e78a4f036076/fonttools-4.59.1-cp312-cp312-manylinux1_x86_64.manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:d601b153e51a5a6221f0d4ec077b6bfc6ac35bfe6c19aeaa233d8990b2b71726", size = 4909215, upload-time = "2025-08-14T16:26:49.682Z" }, - { url = "https://files.pythonhosted.org/packages/8a/ec/2490599550d6c9c97a44c1e36ef4de52d6acf742359eaa385735e30c05c4/fonttools-4.59.1-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c735e385e30278c54f43a0d056736942023c9043f84ee1021eff9fd616d17693", size = 4951958, upload-time = "2025-08-14T16:26:51.616Z" }, - { url = "https://files.pythonhosted.org/packages/d1/40/bd053f6f7634234a9b9805ff8ae4f32df4f2168bee23cafd1271ba9915a9/fonttools-4.59.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1017413cdc8555dce7ee23720da490282ab7ec1cf022af90a241f33f9a49afc4", size = 4894738, upload-time = "2025-08-14T16:26:53.836Z" }, - { url = "https://files.pythonhosted.org/packages/ac/a1/3cd12a010d288325a7cfcf298a84825f0f9c29b01dee1baba64edfe89257/fonttools-4.59.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:5c6d8d773470a5107052874341ed3c487c16ecd179976d81afed89dea5cd7406", size = 5045983, upload-time = "2025-08-14T16:26:56.153Z" }, - { url = "https://files.pythonhosted.org/packages/a2/af/8a2c3f6619cc43cf87951405337cc8460d08a4e717bb05eaa94b335d11dc/fonttools-4.59.1-cp312-cp312-win32.whl", hash = "sha256:2a2d0d33307f6ad3a2086a95dd607c202ea8852fa9fb52af9b48811154d1428a", size = 2203407, upload-time = "2025-08-14T16:26:58.165Z" }, - { url = "https://files.pythonhosted.org/packages/8e/f2/a19b874ddbd3ebcf11d7e25188ef9ac3f68b9219c62263acb34aca8cde05/fonttools-4.59.1-cp312-cp312-win_amd64.whl", hash = "sha256:0b9e4fa7eaf046ed6ac470f6033d52c052481ff7a6e0a92373d14f556f298dc0", size = 2251561, upload-time = "2025-08-14T16:27:00.646Z" }, - { url = "https://files.pythonhosted.org/packages/0f/64/9d606e66d498917cd7a2ff24f558010d42d6fd4576d9dd57f0bd98333f5a/fonttools-4.59.1-py3-none-any.whl", hash = "sha256:647db657073672a8330608970a984d51573557f328030566521bc03415535042", size = 1130094, upload-time = "2025-08-14T16:28:12.048Z" }, +version = "4.59.2" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/0d/a5/fba25f9fbdab96e26dedcaeeba125e5f05a09043bf888e0305326e55685b/fonttools-4.59.2.tar.gz", hash = "sha256:e72c0749b06113f50bcb80332364c6be83a9582d6e3db3fe0b280f996dc2ef22", size = 3540889, upload-time = "2025-08-27T16:40:30.97Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/f8/53/742fcd750ae0bdc74de4c0ff923111199cc2f90a4ee87aaddad505b6f477/fonttools-4.59.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:511946e8d7ea5c0d6c7a53c4cb3ee48eda9ab9797cd9bf5d95829a398400354f", size = 2774961, upload-time = "2025-08-27T16:38:47.536Z" }, + { url = "https://files.pythonhosted.org/packages/57/2a/976f5f9fa3b4dd911dc58d07358467bec20e813d933bc5d3db1a955dd456/fonttools-4.59.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:8e5e2682cf7be766d84f462ba8828d01e00c8751a8e8e7ce12d7784ccb69a30d", size = 2344690, upload-time = "2025-08-27T16:38:49.723Z" }, + { url = "https://files.pythonhosted.org/packages/c1/8f/b7eefc274fcf370911e292e95565c8253b0b87c82a53919ab3c795a4f50e/fonttools-4.59.2-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5729e12a982dba3eeae650de48b06f3b9ddb51e9aee2fcaf195b7d09a96250e2", size = 5026910, upload-time = "2025-08-27T16:38:51.904Z" }, + { url = "https://files.pythonhosted.org/packages/69/95/864726eaa8f9d4e053d0c462e64d5830ec7c599cbdf1db9e40f25ca3972e/fonttools-4.59.2-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:c52694eae5d652361d59ecdb5a2246bff7cff13b6367a12da8499e9df56d148d", size = 4971031, upload-time = "2025-08-27T16:38:53.676Z" }, + { url = "https://files.pythonhosted.org/packages/24/4c/b8c4735ebdea20696277c70c79e0de615dbe477834e5a7c2569aa1db4033/fonttools-4.59.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:f1f1bbc23ba1312bd8959896f46f667753b90216852d2a8cfa2d07e0cb234144", size = 5006112, upload-time = "2025-08-27T16:38:55.69Z" }, + { url = "https://files.pythonhosted.org/packages/3b/23/f9ea29c292aa2fc1ea381b2e5621ac436d5e3e0a5dee24ffe5404e58eae8/fonttools-4.59.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1a1bfe5378962825dabe741720885e8b9ae9745ec7ecc4a5ec1f1ce59a6062bf", size = 5117671, upload-time = "2025-08-27T16:38:58.984Z" }, + { url = "https://files.pythonhosted.org/packages/ba/07/cfea304c555bf06e86071ff2a3916bc90f7c07ec85b23bab758d4908c33d/fonttools-4.59.2-cp311-cp311-win32.whl", hash = "sha256:e937790f3c2c18a1cbc7da101550a84319eb48023a715914477d2e7faeaba570", size = 2218157, upload-time = "2025-08-27T16:39:00.75Z" }, + { url = "https://files.pythonhosted.org/packages/d7/de/35d839aa69db737a3f9f3a45000ca24721834d40118652a5775d5eca8ebb/fonttools-4.59.2-cp311-cp311-win_amd64.whl", hash = "sha256:9836394e2f4ce5f9c0a7690ee93bd90aa1adc6b054f1a57b562c5d242c903104", size = 2265846, upload-time = "2025-08-27T16:39:02.453Z" }, + { url = "https://files.pythonhosted.org/packages/ba/3d/1f45db2df51e7bfa55492e8f23f383d372200be3a0ded4bf56a92753dd1f/fonttools-4.59.2-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:82906d002c349cad647a7634b004825a7335f8159d0d035ae89253b4abf6f3ea", size = 2769711, upload-time = "2025-08-27T16:39:04.423Z" }, + { url = "https://files.pythonhosted.org/packages/29/df/cd236ab32a8abfd11558f296e064424258db5edefd1279ffdbcfd4fd8b76/fonttools-4.59.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:a10c1bd7644dc58f8862d8ba0cf9fb7fef0af01ea184ba6ce3f50ab7dfe74d5a", size = 2340225, upload-time = "2025-08-27T16:39:06.143Z" }, + { url = "https://files.pythonhosted.org/packages/98/12/b6f9f964fe6d4b4dd4406bcbd3328821c3de1f909ffc3ffa558fe72af48c/fonttools-4.59.2-cp312-cp312-manylinux1_x86_64.manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:738f31f23e0339785fd67652a94bc69ea49e413dfdb14dcb8c8ff383d249464e", size = 4912766, upload-time = "2025-08-27T16:39:08.138Z" }, + { url = "https://files.pythonhosted.org/packages/73/78/82bde2f2d2c306ef3909b927363170b83df96171f74e0ccb47ad344563cd/fonttools-4.59.2-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0ec99f9bdfee9cdb4a9172f9e8fd578cce5feb231f598909e0aecf5418da4f25", size = 4955178, upload-time = "2025-08-27T16:39:10.094Z" }, + { url = "https://files.pythonhosted.org/packages/92/77/7de766afe2d31dda8ee46d7e479f35c7d48747e558961489a2d6e3a02bd4/fonttools-4.59.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:0476ea74161322e08c7a982f83558a2b81b491509984523a1a540baf8611cc31", size = 4897898, upload-time = "2025-08-27T16:39:12.087Z" }, + { url = "https://files.pythonhosted.org/packages/c5/77/ce0e0b905d62a06415fda9f2b2e109a24a5db54a59502b769e9e297d2242/fonttools-4.59.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:95922a922daa1f77cc72611747c156cfb38030ead72436a2c551d30ecef519b9", size = 5049144, upload-time = "2025-08-27T16:39:13.84Z" }, + { url = "https://files.pythonhosted.org/packages/d9/ea/870d93aefd23fff2e07cbeebdc332527868422a433c64062c09d4d5e7fe6/fonttools-4.59.2-cp312-cp312-win32.whl", hash = "sha256:39ad9612c6a622726a6a130e8ab15794558591f999673f1ee7d2f3d30f6a3e1c", size = 2206473, upload-time = "2025-08-27T16:39:15.854Z" }, + { url = "https://files.pythonhosted.org/packages/61/c4/e44bad000c4a4bb2e9ca11491d266e857df98ab6d7428441b173f0fe2517/fonttools-4.59.2-cp312-cp312-win_amd64.whl", hash = "sha256:980fd7388e461b19a881d35013fec32c713ffea1fc37aef2f77d11f332dfd7da", size = 2254706, upload-time = "2025-08-27T16:39:17.893Z" }, + { url = "https://files.pythonhosted.org/packages/65/a4/d2f7be3c86708912c02571db0b550121caab8cd88a3c0aacb9cfa15ea66e/fonttools-4.59.2-py3-none-any.whl", hash = "sha256:8bd0f759020e87bb5d323e6283914d9bf4ae35a7307dafb2cbd1e379e720ad37", size = 1132315, upload-time = "2025-08-27T16:40:28.984Z" }, ] [[package]] @@ -855,7 +855,7 @@ wheels = [ [[package]] name = "matplotlib" -version = "3.10.5" +version = "3.10.6" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "contourpy" }, @@ -868,25 +868,25 @@ dependencies = [ { name = "pyparsing" }, { name = "python-dateutil" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/43/91/f2939bb60b7ebf12478b030e0d7f340247390f402b3b189616aad790c366/matplotlib-3.10.5.tar.gz", hash = "sha256:352ed6ccfb7998a00881692f38b4ca083c691d3e275b4145423704c34c909076", size = 34804044, upload-time = "2025-07-31T18:09:33.805Z" } +sdist = { url = "https://files.pythonhosted.org/packages/a0/59/c3e6453a9676ffba145309a73c462bb407f4400de7de3f2b41af70720a3c/matplotlib-3.10.6.tar.gz", hash = "sha256:ec01b645840dd1996df21ee37f208cd8ba57644779fa20464010638013d3203c", size = 34804264, upload-time = "2025-08-30T00:14:25.137Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/aa/c7/1f2db90a1d43710478bb1e9b57b162852f79234d28e4f48a28cc415aa583/matplotlib-3.10.5-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:dcfc39c452c6a9f9028d3e44d2d721484f665304857188124b505b2c95e1eecf", size = 8239216, upload-time = "2025-07-31T18:07:51.947Z" }, - { url = "https://files.pythonhosted.org/packages/82/6d/ca6844c77a4f89b1c9e4d481c412e1d1dbabf2aae2cbc5aa2da4a1d6683e/matplotlib-3.10.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:903352681b59f3efbf4546985142a9686ea1d616bb054b09a537a06e4b892ccf", size = 8102130, upload-time = "2025-07-31T18:07:53.65Z" }, - { url = "https://files.pythonhosted.org/packages/1d/1e/5e187a30cc673a3e384f3723e5f3c416033c1d8d5da414f82e4e731128ea/matplotlib-3.10.5-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:080c3676a56b8ee1c762bcf8fca3fe709daa1ee23e6ef06ad9f3fc17332f2d2a", size = 8666471, upload-time = "2025-07-31T18:07:55.304Z" }, - { url = "https://files.pythonhosted.org/packages/03/c0/95540d584d7d645324db99a845ac194e915ef75011a0d5e19e1b5cee7e69/matplotlib-3.10.5-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:4b4984d5064a35b6f66d2c11d668565f4389b1119cc64db7a4c1725bc11adffc", size = 9500518, upload-time = "2025-07-31T18:07:57.199Z" }, - { url = "https://files.pythonhosted.org/packages/ba/2e/e019352099ea58b4169adb9c6e1a2ad0c568c6377c2b677ee1f06de2adc7/matplotlib-3.10.5-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:3967424121d3a46705c9fa9bdb0931de3228f13f73d7bb03c999c88343a89d89", size = 9552372, upload-time = "2025-07-31T18:07:59.41Z" }, - { url = "https://files.pythonhosted.org/packages/b7/81/3200b792a5e8b354f31f4101ad7834743ad07b6d620259f2059317b25e4d/matplotlib-3.10.5-cp311-cp311-win_amd64.whl", hash = "sha256:33775bbeb75528555a15ac29396940128ef5613cf9a2d31fb1bfd18b3c0c0903", size = 8100634, upload-time = "2025-07-31T18:08:01.801Z" }, - { url = "https://files.pythonhosted.org/packages/52/46/a944f6f0c1f5476a0adfa501969d229ce5ae60cf9a663be0e70361381f89/matplotlib-3.10.5-cp311-cp311-win_arm64.whl", hash = "sha256:c61333a8e5e6240e73769d5826b9a31d8b22df76c0778f8480baf1b4b01c9420", size = 7978880, upload-time = "2025-07-31T18:08:03.407Z" }, - { url = "https://files.pythonhosted.org/packages/66/1e/c6f6bcd882d589410b475ca1fc22e34e34c82adff519caf18f3e6dd9d682/matplotlib-3.10.5-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:00b6feadc28a08bd3c65b2894f56cf3c94fc8f7adcbc6ab4516ae1e8ed8f62e2", size = 8253056, upload-time = "2025-07-31T18:08:05.385Z" }, - { url = "https://files.pythonhosted.org/packages/53/e6/d6f7d1b59413f233793dda14419776f5f443bcccb2dfc84b09f09fe05dbe/matplotlib-3.10.5-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ee98a5c5344dc7f48dc261b6ba5d9900c008fc12beb3fa6ebda81273602cc389", size = 8110131, upload-time = "2025-07-31T18:08:07.293Z" }, - { url = "https://files.pythonhosted.org/packages/66/2b/bed8a45e74957549197a2ac2e1259671cd80b55ed9e1fe2b5c94d88a9202/matplotlib-3.10.5-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:a17e57e33de901d221a07af32c08870ed4528db0b6059dce7d7e65c1122d4bea", size = 8669603, upload-time = "2025-07-31T18:08:09.064Z" }, - { url = "https://files.pythonhosted.org/packages/7e/a7/315e9435b10d057f5e52dfc603cd353167ae28bb1a4e033d41540c0067a4/matplotlib-3.10.5-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:97b9d6443419085950ee4a5b1ee08c363e5c43d7176e55513479e53669e88468", size = 9508127, upload-time = "2025-07-31T18:08:10.845Z" }, - { url = "https://files.pythonhosted.org/packages/7f/d9/edcbb1f02ca99165365d2768d517898c22c6040187e2ae2ce7294437c413/matplotlib-3.10.5-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ceefe5d40807d29a66ae916c6a3915d60ef9f028ce1927b84e727be91d884369", size = 9566926, upload-time = "2025-07-31T18:08:13.186Z" }, - { url = "https://files.pythonhosted.org/packages/3b/d9/6dd924ad5616c97b7308e6320cf392c466237a82a2040381163b7500510a/matplotlib-3.10.5-cp312-cp312-win_amd64.whl", hash = "sha256:c04cba0f93d40e45b3c187c6c52c17f24535b27d545f757a2fffebc06c12b98b", size = 8107599, upload-time = "2025-07-31T18:08:15.116Z" }, - { url = "https://files.pythonhosted.org/packages/0e/f3/522dc319a50f7b0279fbe74f86f7a3506ce414bc23172098e8d2bdf21894/matplotlib-3.10.5-cp312-cp312-win_arm64.whl", hash = "sha256:a41bcb6e2c8e79dc99c5511ae6f7787d2fb52efd3d805fff06d5d4f667db16b2", size = 7978173, upload-time = "2025-07-31T18:08:21.518Z" }, - { url = "https://files.pythonhosted.org/packages/dc/d6/e921be4e1a5f7aca5194e1f016cb67ec294548e530013251f630713e456d/matplotlib-3.10.5-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:160e125da27a749481eaddc0627962990f6029811dbeae23881833a011a0907f", size = 8233224, upload-time = "2025-07-31T18:09:27.512Z" }, - { url = "https://files.pythonhosted.org/packages/ec/74/a2b9b04824b9c349c8f1b2d21d5af43fa7010039427f2b133a034cb09e59/matplotlib-3.10.5-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:ac3d50760394d78a3c9be6b28318fe22b494c4fcf6407e8fd4794b538251899b", size = 8098539, upload-time = "2025-07-31T18:09:29.629Z" }, - { url = "https://files.pythonhosted.org/packages/fc/66/cd29ebc7f6c0d2a15d216fb572573e8fc38bd5d6dec3bd9d7d904c0949f7/matplotlib-3.10.5-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:6c49465bf689c4d59d174d0c7795fb42a21d4244d11d70e52b8011987367ac61", size = 8672192, upload-time = "2025-07-31T18:09:31.407Z" }, + { url = "https://files.pythonhosted.org/packages/80/d6/5d3665aa44c49005aaacaa68ddea6fcb27345961cd538a98bb0177934ede/matplotlib-3.10.6-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:905b60d1cb0ee604ce65b297b61cf8be9f4e6cfecf95a3fe1c388b5266bc8f4f", size = 8257527, upload-time = "2025-08-30T00:12:45.31Z" }, + { url = "https://files.pythonhosted.org/packages/8c/af/30ddefe19ca67eebd70047dabf50f899eaff6f3c5e6a1a7edaecaf63f794/matplotlib-3.10.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:7bac38d816637343e53d7185d0c66677ff30ffb131044a81898b5792c956ba76", size = 8119583, upload-time = "2025-08-30T00:12:47.236Z" }, + { url = "https://files.pythonhosted.org/packages/d3/29/4a8650a3dcae97fa4f375d46efcb25920d67b512186f8a6788b896062a81/matplotlib-3.10.6-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:942a8de2b5bfff1de31d95722f702e2966b8a7e31f4e68f7cd963c7cd8861cf6", size = 8692682, upload-time = "2025-08-30T00:12:48.781Z" }, + { url = "https://files.pythonhosted.org/packages/aa/d3/b793b9cb061cfd5d42ff0f69d1822f8d5dbc94e004618e48a97a8373179a/matplotlib-3.10.6-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a3276c85370bc0dfca051ec65c5817d1e0f8f5ce1b7787528ec8ed2d524bbc2f", size = 9521065, upload-time = "2025-08-30T00:12:50.602Z" }, + { url = "https://files.pythonhosted.org/packages/f7/c5/53de5629f223c1c66668d46ac2621961970d21916a4bc3862b174eb2a88f/matplotlib-3.10.6-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:9df5851b219225731f564e4b9e7f2ac1e13c9e6481f941b5631a0f8e2d9387ce", size = 9576888, upload-time = "2025-08-30T00:12:52.92Z" }, + { url = "https://files.pythonhosted.org/packages/fc/8e/0a18d6d7d2d0a2e66585032a760d13662e5250c784d53ad50434e9560991/matplotlib-3.10.6-cp311-cp311-win_amd64.whl", hash = "sha256:abb5d9478625dd9c9eb51a06d39aae71eda749ae9b3138afb23eb38824026c7e", size = 8115158, upload-time = "2025-08-30T00:12:54.863Z" }, + { url = "https://files.pythonhosted.org/packages/07/b3/1a5107bb66c261e23b9338070702597a2d374e5aa7004b7adfc754fbed02/matplotlib-3.10.6-cp311-cp311-win_arm64.whl", hash = "sha256:886f989ccfae63659183173bb3fced7fd65e9eb793c3cc21c273add368536951", size = 7992444, upload-time = "2025-08-30T00:12:57.067Z" }, + { url = "https://files.pythonhosted.org/packages/ea/1a/7042f7430055d567cc3257ac409fcf608599ab27459457f13772c2d9778b/matplotlib-3.10.6-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:31ca662df6a80bd426f871105fdd69db7543e28e73a9f2afe80de7e531eb2347", size = 8272404, upload-time = "2025-08-30T00:12:59.112Z" }, + { url = "https://files.pythonhosted.org/packages/a9/5d/1d5f33f5b43f4f9e69e6a5fe1fb9090936ae7bc8e2ff6158e7a76542633b/matplotlib-3.10.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:1678bb61d897bb4ac4757b5ecfb02bfb3fddf7f808000fb81e09c510712fda75", size = 8128262, upload-time = "2025-08-30T00:13:01.141Z" }, + { url = "https://files.pythonhosted.org/packages/67/c3/135fdbbbf84e0979712df58e5e22b4f257b3f5e52a3c4aacf1b8abec0d09/matplotlib-3.10.6-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:56cd2d20842f58c03d2d6e6c1f1cf5548ad6f66b91e1e48f814e4fb5abd1cb95", size = 8697008, upload-time = "2025-08-30T00:13:03.24Z" }, + { url = "https://files.pythonhosted.org/packages/9c/be/c443ea428fb2488a3ea7608714b1bd85a82738c45da21b447dc49e2f8e5d/matplotlib-3.10.6-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:662df55604a2f9a45435566d6e2660e41efe83cd94f4288dfbf1e6d1eae4b0bb", size = 9530166, upload-time = "2025-08-30T00:13:05.951Z" }, + { url = "https://files.pythonhosted.org/packages/a9/35/48441422b044d74034aea2a3e0d1a49023f12150ebc58f16600132b9bbaf/matplotlib-3.10.6-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:08f141d55148cd1fc870c3387d70ca4df16dee10e909b3b038782bd4bda6ea07", size = 9593105, upload-time = "2025-08-30T00:13:08.356Z" }, + { url = "https://files.pythonhosted.org/packages/45/c3/994ef20eb4154ab84cc08d033834555319e4af970165e6c8894050af0b3c/matplotlib-3.10.6-cp312-cp312-win_amd64.whl", hash = "sha256:590f5925c2d650b5c9d813c5b3b5fc53f2929c3f8ef463e4ecfa7e052044fb2b", size = 8122784, upload-time = "2025-08-30T00:13:10.367Z" }, + { url = "https://files.pythonhosted.org/packages/57/b8/5c85d9ae0e40f04e71bedb053aada5d6bab1f9b5399a0937afb5d6b02d98/matplotlib-3.10.6-cp312-cp312-win_arm64.whl", hash = "sha256:f44c8d264a71609c79a78d50349e724f5d5fc3684ead7c2a473665ee63d868aa", size = 7992823, upload-time = "2025-08-30T00:13:12.24Z" }, + { url = "https://files.pythonhosted.org/packages/12/bb/02c35a51484aae5f49bd29f091286e7af5f3f677a9736c58a92b3c78baeb/matplotlib-3.10.6-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:f2d684c3204fa62421bbf770ddfebc6b50130f9cad65531eeba19236d73bb488", size = 8252296, upload-time = "2025-08-30T00:14:19.49Z" }, + { url = "https://files.pythonhosted.org/packages/7d/85/41701e3092005aee9a2445f5ee3904d9dbd4a7df7a45905ffef29b7ef098/matplotlib-3.10.6-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:6f4a69196e663a41d12a728fab8751177215357906436804217d6d9cf0d4d6cf", size = 8116749, upload-time = "2025-08-30T00:14:21.344Z" }, + { url = "https://files.pythonhosted.org/packages/16/53/8d8fa0ea32a8c8239e04d022f6c059ee5e1b77517769feccd50f1df43d6d/matplotlib-3.10.6-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:4d6ca6ef03dfd269f4ead566ec6f3fb9becf8dab146fb999022ed85ee9f6b3eb", size = 8693933, upload-time = "2025-08-30T00:14:22.942Z" }, ] [[package]] @@ -990,6 +990,27 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9f/d4/029f984e8d3f3b6b726bd33cafc473b75e9e44c0f7e80a5b29abc466bdea/mkdocs_get_deps-0.2.0-py3-none-any.whl", hash = "sha256:2bf11d0b133e77a0dd036abeeb06dec8775e46efa526dc70667d8863eefc6134", size = 9521, upload-time = "2023-11-20T17:51:08.587Z" }, ] +[[package]] +name = "ml-dtypes" +version = "0.5.3" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "numpy" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/78/a7/aad060393123cfb383956dca68402aff3db1e1caffd5764887ed5153f41b/ml_dtypes-0.5.3.tar.gz", hash = "sha256:95ce33057ba4d05df50b1f3cfefab22e351868a843b3b15a46c65836283670c9", size = 692316, upload-time = "2025-07-29T18:39:19.454Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/af/f1/720cb1409b5d0c05cff9040c0e9fba73fa4c67897d33babf905d5d46a070/ml_dtypes-0.5.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4a177b882667c69422402df6ed5c3428ce07ac2c1f844d8a1314944651439458", size = 667412, upload-time = "2025-07-29T18:38:25.275Z" }, + { url = "https://files.pythonhosted.org/packages/6a/d5/05861ede5d299f6599f86e6bc1291714e2116d96df003cfe23cc54bcc568/ml_dtypes-0.5.3-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:9849ce7267444c0a717c80c6900997de4f36e2815ce34ac560a3edb2d9a64cd2", size = 4964606, upload-time = "2025-07-29T18:38:27.045Z" }, + { url = "https://files.pythonhosted.org/packages/db/dc/72992b68de367741bfab8df3b3fe7c29f982b7279d341aa5bf3e7ef737ea/ml_dtypes-0.5.3-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:c3f5ae0309d9f888fd825c2e9d0241102fadaca81d888f26f845bc8c13c1e4ee", size = 4938435, upload-time = "2025-07-29T18:38:29.193Z" }, + { url = "https://files.pythonhosted.org/packages/81/1c/d27a930bca31fb07d975a2d7eaf3404f9388114463b9f15032813c98f893/ml_dtypes-0.5.3-cp311-cp311-win_amd64.whl", hash = "sha256:58e39349d820b5702bb6f94ea0cb2dc8ec62ee81c0267d9622067d8333596a46", size = 206334, upload-time = "2025-07-29T18:38:30.687Z" }, + { url = "https://files.pythonhosted.org/packages/1a/d8/6922499effa616012cb8dc445280f66d100a7ff39b35c864cfca019b3f89/ml_dtypes-0.5.3-cp311-cp311-win_arm64.whl", hash = "sha256:66c2756ae6cfd7f5224e355c893cfd617fa2f747b8bbd8996152cbdebad9a184", size = 157584, upload-time = "2025-07-29T18:38:32.187Z" }, + { url = "https://files.pythonhosted.org/packages/0d/eb/bc07c88a6ab002b4635e44585d80fa0b350603f11a2097c9d1bfacc03357/ml_dtypes-0.5.3-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:156418abeeda48ea4797db6776db3c5bdab9ac7be197c1233771e0880c304057", size = 663864, upload-time = "2025-07-29T18:38:33.777Z" }, + { url = "https://files.pythonhosted.org/packages/cf/89/11af9b0f21b99e6386b6581ab40fb38d03225f9de5f55cf52097047e2826/ml_dtypes-0.5.3-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1db60c154989af253f6c4a34e8a540c2c9dce4d770784d426945e09908fbb177", size = 4951313, upload-time = "2025-07-29T18:38:36.45Z" }, + { url = "https://files.pythonhosted.org/packages/d8/a9/b98b86426c24900b0c754aad006dce2863df7ce0bb2bcc2c02f9cc7e8489/ml_dtypes-0.5.3-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1b255acada256d1fa8c35ed07b5f6d18bc21d1556f842fbc2d5718aea2cd9e55", size = 4928805, upload-time = "2025-07-29T18:38:38.29Z" }, + { url = "https://files.pythonhosted.org/packages/50/c1/85e6be4fc09c6175f36fb05a45917837f30af9a5146a5151cb3a3f0f9e09/ml_dtypes-0.5.3-cp312-cp312-win_amd64.whl", hash = "sha256:da65e5fd3eea434ccb8984c3624bc234ddcc0d9f4c81864af611aaebcc08a50e", size = 208182, upload-time = "2025-07-29T18:38:39.72Z" }, + { url = "https://files.pythonhosted.org/packages/9e/17/cf5326d6867be057f232d0610de1458f70a8ce7b6290e4b4a277ea62b4cd/ml_dtypes-0.5.3-cp312-cp312-win_arm64.whl", hash = "sha256:8bb9cd1ce63096567f5f42851f5843b5a0ea11511e50039a7649619abfb4ba6d", size = 161560, upload-time = "2025-07-29T18:38:41.072Z" }, +] + [[package]] name = "mouseinfo" version = "0.1.3" @@ -1164,27 +1185,28 @@ wheels = [ [[package]] name = "onnx" -version = "1.18.0" +version = "1.19.0" source = { registry = "https://pypi.org/simple" } dependencies = [ + { name = "ml-dtypes" }, { name = "numpy" }, { name = "protobuf" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/3d/60/e56e8ec44ed34006e6d4a73c92a04d9eea6163cc12440e35045aec069175/onnx-1.18.0.tar.gz", hash = "sha256:3d8dbf9e996629131ba3aa1afd1d8239b660d1f830c6688dd7e03157cccd6b9c", size = 12563009, upload-time = "2025-05-12T22:03:09.626Z" } +sdist = { url = "https://files.pythonhosted.org/packages/5b/bf/b0a63ee9f3759dcd177b28c6f2cb22f2aecc6d9b3efecaabc298883caa5f/onnx-1.19.0.tar.gz", hash = "sha256:aa3f70b60f54a29015e41639298ace06adf1dd6b023b9b30f1bca91bb0db9473", size = 11949859, upload-time = "2025-08-27T02:34:27.107Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ed/3a/a336dac4db1eddba2bf577191e5b7d3e4c26fcee5ec518a5a5b11d13540d/onnx-1.18.0-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:735e06d8d0cf250dc498f54038831401063c655a8d6e5975b2527a4e7d24be3e", size = 18281831, upload-time = "2025-05-12T22:02:06.429Z" }, - { url = "https://files.pythonhosted.org/packages/02/3a/56475a111120d1e5d11939acbcbb17c92198c8e64a205cd68e00bdfd8a1f/onnx-1.18.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:73160799472e1a86083f786fecdf864cf43d55325492a9b5a1cfa64d8a523ecc", size = 17424359, upload-time = "2025-05-12T22:02:09.866Z" }, - { url = "https://files.pythonhosted.org/packages/cf/03/5eb5e9ef446ed9e78c4627faf3c1bc25e0f707116dd00e9811de232a8df5/onnx-1.18.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6acafb3823238bbe8f4340c7ac32fb218689442e074d797bee1c5c9a02fdae75", size = 17586006, upload-time = "2025-05-12T22:02:13.217Z" }, - { url = "https://files.pythonhosted.org/packages/b0/4e/70943125729ce453271a6e46bb847b4a612496f64db6cbc6cb1f49f41ce1/onnx-1.18.0-cp311-cp311-win32.whl", hash = "sha256:4c8c4bbda760c654e65eaffddb1a7de71ec02e60092d33f9000521f897c99be9", size = 15734988, upload-time = "2025-05-12T22:02:16.561Z" }, - { url = "https://files.pythonhosted.org/packages/44/b0/435fd764011911e8f599e3361f0f33425b1004662c1ea33a0ad22e43db2d/onnx-1.18.0-cp311-cp311-win_amd64.whl", hash = "sha256:a5810194f0f6be2e58c8d6dedc6119510df7a14280dd07ed5f0f0a85bd74816a", size = 15849576, upload-time = "2025-05-12T22:02:19.569Z" }, - { url = "https://files.pythonhosted.org/packages/6c/f0/9e31f4b4626d60f1c034f71b411810bc9fafe31f4e7dd3598effd1b50e05/onnx-1.18.0-cp311-cp311-win_arm64.whl", hash = "sha256:aa1b7483fac6cdec26922174fc4433f8f5c2f239b1133c5625063bb3b35957d0", size = 15822961, upload-time = "2025-05-12T22:02:22.735Z" }, - { url = "https://files.pythonhosted.org/packages/a7/fe/16228aca685392a7114625b89aae98b2dc4058a47f0f467a376745efe8d0/onnx-1.18.0-cp312-cp312-macosx_12_0_universal2.whl", hash = "sha256:521bac578448667cbb37c50bf05b53c301243ede8233029555239930996a625b", size = 18285770, upload-time = "2025-05-12T22:02:26.116Z" }, - { url = "https://files.pythonhosted.org/packages/1e/77/ba50a903a9b5e6f9be0fa50f59eb2fca4a26ee653375408fbc72c3acbf9f/onnx-1.18.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e4da451bf1c5ae381f32d430004a89f0405bc57a8471b0bddb6325a5b334aa40", size = 17421291, upload-time = "2025-05-12T22:02:29.645Z" }, - { url = "https://files.pythonhosted.org/packages/11/23/25ec2ba723ac62b99e8fed6d7b59094dadb15e38d4c007331cc9ae3dfa5f/onnx-1.18.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:99afac90b4cdb1471432203c3c1f74e16549c526df27056d39f41a9a47cfb4af", size = 17584084, upload-time = "2025-05-12T22:02:32.789Z" }, - { url = "https://files.pythonhosted.org/packages/6a/4d/2c253a36070fb43f340ff1d2c450df6a9ef50b938adcd105693fee43c4ee/onnx-1.18.0-cp312-cp312-win32.whl", hash = "sha256:ee159b41a3ae58d9c7341cf432fc74b96aaf50bd7bb1160029f657b40dc69715", size = 15734892, upload-time = "2025-05-12T22:02:35.527Z" }, - { url = "https://files.pythonhosted.org/packages/e8/92/048ba8fafe6b2b9a268ec2fb80def7e66c0b32ab2cae74de886981f05a27/onnx-1.18.0-cp312-cp312-win_amd64.whl", hash = "sha256:102c04edc76b16e9dfeda5a64c1fccd7d3d2913b1544750c01d38f1ac3c04e05", size = 15850336, upload-time = "2025-05-12T22:02:38.545Z" }, - { url = "https://files.pythonhosted.org/packages/a1/66/bbc4ffedd44165dcc407a51ea4c592802a5391ce3dc94aa5045350f64635/onnx-1.18.0-cp312-cp312-win_arm64.whl", hash = "sha256:911b37d724a5d97396f3c2ef9ea25361c55cbc9aa18d75b12a52b620b67145af", size = 15823802, upload-time = "2025-05-12T22:02:42.037Z" }, + { url = "https://files.pythonhosted.org/packages/db/5c/b959b17608cfb6ccf6359b39fe56a5b0b7d965b3d6e6a3c0add90812c36e/onnx-1.19.0-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:206f00c47b85b5c7af79671e3307147407991a17994c26974565aadc9e96e4e4", size = 18312580, upload-time = "2025-08-27T02:33:03.081Z" }, + { url = "https://files.pythonhosted.org/packages/2c/ee/ac052bbbc832abe0debb784c2c57f9582444fb5f51d63c2967fd04432444/onnx-1.19.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:4d7bee94abaac28988b50da675ae99ef8dd3ce16210d591fbd0b214a5930beb3", size = 18029165, upload-time = "2025-08-27T02:33:05.771Z" }, + { url = "https://files.pythonhosted.org/packages/5c/c9/8687ba0948d46fd61b04e3952af9237883bbf8f16d716e7ed27e688d73b8/onnx-1.19.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:7730b96b68c0c354bbc7857961bb4909b9aaa171360a8e3708d0a4c749aaadeb", size = 18202125, upload-time = "2025-08-27T02:33:09.325Z" }, + { url = "https://files.pythonhosted.org/packages/e2/16/6249c013e81bd689f46f96c7236d7677f1af5dd9ef22746716b48f10e506/onnx-1.19.0-cp311-cp311-win32.whl", hash = "sha256:7cb7a3ad8059d1a0dfdc5e0a98f71837d82002e441f112825403b137227c2c97", size = 16332738, upload-time = "2025-08-27T02:33:12.448Z" }, + { url = "https://files.pythonhosted.org/packages/6a/28/34a1e2166e418c6a78e5c82e66f409d9da9317832f11c647f7d4e23846a6/onnx-1.19.0-cp311-cp311-win_amd64.whl", hash = "sha256:d75452a9be868bd30c3ef6aa5991df89bbfe53d0d90b2325c5e730fbd91fff85", size = 16452303, upload-time = "2025-08-27T02:33:15.176Z" }, + { url = "https://files.pythonhosted.org/packages/e6/b7/639664626e5ba8027860c4d2a639ee02b37e9c322215c921e9222513c3aa/onnx-1.19.0-cp311-cp311-win_arm64.whl", hash = "sha256:23c7959370d7b3236f821e609b0af7763cff7672a758e6c1fc877bac099e786b", size = 16425340, upload-time = "2025-08-27T02:33:17.78Z" }, + { url = "https://files.pythonhosted.org/packages/0d/94/f56f6ca5e2f921b28c0f0476705eab56486b279f04e1d568ed64c14e7764/onnx-1.19.0-cp312-cp312-macosx_12_0_universal2.whl", hash = "sha256:61d94e6498ca636756f8f4ee2135708434601b2892b7c09536befb19bc8ca007", size = 18322331, upload-time = "2025-08-27T02:33:20.373Z" }, + { url = "https://files.pythonhosted.org/packages/c8/00/8cc3f3c40b54b28f96923380f57c9176872e475face726f7d7a78bd74098/onnx-1.19.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:224473354462f005bae985c72028aaa5c85ab11de1b71d55b06fdadd64a667dd", size = 18027513, upload-time = "2025-08-27T02:33:23.44Z" }, + { url = "https://files.pythonhosted.org/packages/61/90/17c4d2566fd0117a5e412688c9525f8950d467f477fbd574e6b32bc9cb8d/onnx-1.19.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1ae475c85c89bc4d1f16571006fd21a3e7c0e258dd2c091f6e8aafb083d1ed9b", size = 18202278, upload-time = "2025-08-27T02:33:26.103Z" }, + { url = "https://files.pythonhosted.org/packages/bc/6e/a9383d9cf6db4ac761a129b081e9fa5d0cd89aad43cf1e3fc6285b915c7d/onnx-1.19.0-cp312-cp312-win32.whl", hash = "sha256:323f6a96383a9cdb3960396cffea0a922593d221f3929b17312781e9f9b7fb9f", size = 16333080, upload-time = "2025-08-27T02:33:28.559Z" }, + { url = "https://files.pythonhosted.org/packages/a7/2e/3ff480a8c1fa7939662bdc973e41914add2d4a1f2b8572a3c39c2e4982e5/onnx-1.19.0-cp312-cp312-win_amd64.whl", hash = "sha256:50220f3499a499b1a15e19451a678a58e22ad21b34edf2c844c6ef1d9febddc2", size = 16453927, upload-time = "2025-08-27T02:33:31.177Z" }, + { url = "https://files.pythonhosted.org/packages/57/37/ad500945b1b5c154fe9d7b826b30816ebd629d10211ea82071b5bcc30aa4/onnx-1.19.0-cp312-cp312-win_arm64.whl", hash = "sha256:efb768299580b786e21abe504e1652ae6189f0beed02ab087cd841cb4bb37e43", size = 16426022, upload-time = "2025-08-27T02:33:33.515Z" }, ] [[package]] @@ -4605,28 +4627,28 @@ wheels = [ [[package]] name = "ruff" -version = "0.12.10" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/3b/eb/8c073deb376e46ae767f4961390d17545e8535921d2f65101720ed8bd434/ruff-0.12.10.tar.gz", hash = "sha256:189ab65149d11ea69a2d775343adf5f49bb2426fc4780f65ee33b423ad2e47f9", size = 5310076, upload-time = "2025-08-21T18:23:22.595Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/24/e7/560d049d15585d6c201f9eeacd2fd130def3741323e5ccf123786e0e3c95/ruff-0.12.10-py3-none-linux_armv6l.whl", hash = "sha256:8b593cb0fb55cc8692dac7b06deb29afda78c721c7ccfed22db941201b7b8f7b", size = 11935161, upload-time = "2025-08-21T18:22:26.965Z" }, - { url = "https://files.pythonhosted.org/packages/d1/b0/ad2464922a1113c365d12b8f80ed70fcfb39764288ac77c995156080488d/ruff-0.12.10-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:ebb7333a45d56efc7c110a46a69a1b32365d5c5161e7244aaf3aa20ce62399c1", size = 12660884, upload-time = "2025-08-21T18:22:30.925Z" }, - { url = "https://files.pythonhosted.org/packages/d7/f1/97f509b4108d7bae16c48389f54f005b62ce86712120fd8b2d8e88a7cb49/ruff-0.12.10-py3-none-macosx_11_0_arm64.whl", hash = "sha256:d59e58586829f8e4a9920788f6efba97a13d1fa320b047814e8afede381c6839", size = 11872754, upload-time = "2025-08-21T18:22:34.035Z" }, - { url = "https://files.pythonhosted.org/packages/12/ad/44f606d243f744a75adc432275217296095101f83f966842063d78eee2d3/ruff-0.12.10-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:822d9677b560f1fdeab69b89d1f444bf5459da4aa04e06e766cf0121771ab844", size = 12092276, upload-time = "2025-08-21T18:22:36.764Z" }, - { url = "https://files.pythonhosted.org/packages/06/1f/ed6c265e199568010197909b25c896d66e4ef2c5e1c3808caf461f6f3579/ruff-0.12.10-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:37b4a64f4062a50c75019c61c7017ff598cb444984b638511f48539d3a1c98db", size = 11734700, upload-time = "2025-08-21T18:22:39.822Z" }, - { url = "https://files.pythonhosted.org/packages/63/c5/b21cde720f54a1d1db71538c0bc9b73dee4b563a7dd7d2e404914904d7f5/ruff-0.12.10-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2c6f4064c69d2542029b2a61d39920c85240c39837599d7f2e32e80d36401d6e", size = 13468783, upload-time = "2025-08-21T18:22:42.559Z" }, - { url = "https://files.pythonhosted.org/packages/02/9e/39369e6ac7f2a1848f22fb0b00b690492f20811a1ac5c1fd1d2798329263/ruff-0.12.10-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:059e863ea3a9ade41407ad71c1de2badfbe01539117f38f763ba42a1206f7559", size = 14436642, upload-time = "2025-08-21T18:22:45.612Z" }, - { url = "https://files.pythonhosted.org/packages/e3/03/5da8cad4b0d5242a936eb203b58318016db44f5c5d351b07e3f5e211bb89/ruff-0.12.10-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1bef6161e297c68908b7218fa6e0e93e99a286e5ed9653d4be71e687dff101cf", size = 13859107, upload-time = "2025-08-21T18:22:48.886Z" }, - { url = "https://files.pythonhosted.org/packages/19/19/dd7273b69bf7f93a070c9cec9494a94048325ad18fdcf50114f07e6bf417/ruff-0.12.10-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4f1345fbf8fb0531cd722285b5f15af49b2932742fc96b633e883da8d841896b", size = 12886521, upload-time = "2025-08-21T18:22:51.567Z" }, - { url = "https://files.pythonhosted.org/packages/c0/1d/b4207ec35e7babaee62c462769e77457e26eb853fbdc877af29417033333/ruff-0.12.10-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1f68433c4fbc63efbfa3ba5db31727db229fa4e61000f452c540474b03de52a9", size = 13097528, upload-time = "2025-08-21T18:22:54.609Z" }, - { url = "https://files.pythonhosted.org/packages/ff/00/58f7b873b21114456e880b75176af3490d7a2836033779ca42f50de3b47a/ruff-0.12.10-py3-none-manylinux_2_31_riscv64.whl", hash = "sha256:141ce3d88803c625257b8a6debf4a0473eb6eed9643a6189b68838b43e78165a", size = 13080443, upload-time = "2025-08-21T18:22:57.413Z" }, - { url = "https://files.pythonhosted.org/packages/12/8c/9e6660007fb10189ccb78a02b41691288038e51e4788bf49b0a60f740604/ruff-0.12.10-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:f3fc21178cd44c98142ae7590f42ddcb587b8e09a3b849cbc84edb62ee95de60", size = 11896759, upload-time = "2025-08-21T18:23:00.473Z" }, - { url = "https://files.pythonhosted.org/packages/67/4c/6d092bb99ea9ea6ebda817a0e7ad886f42a58b4501a7e27cd97371d0ba54/ruff-0.12.10-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:7d1a4e0bdfafcd2e3e235ecf50bf0176f74dd37902f241588ae1f6c827a36c56", size = 11701463, upload-time = "2025-08-21T18:23:03.211Z" }, - { url = "https://files.pythonhosted.org/packages/59/80/d982c55e91df981f3ab62559371380616c57ffd0172d96850280c2b04fa8/ruff-0.12.10-py3-none-musllinux_1_2_i686.whl", hash = "sha256:e67d96827854f50b9e3e8327b031647e7bcc090dbe7bb11101a81a3a2cbf1cc9", size = 12691603, upload-time = "2025-08-21T18:23:06.935Z" }, - { url = "https://files.pythonhosted.org/packages/ad/37/63a9c788bbe0b0850611669ec6b8589838faf2f4f959647f2d3e320383ae/ruff-0.12.10-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:ae479e1a18b439c59138f066ae79cc0f3ee250712a873d00dbafadaad9481e5b", size = 13164356, upload-time = "2025-08-21T18:23:10.225Z" }, - { url = "https://files.pythonhosted.org/packages/47/d4/1aaa7fb201a74181989970ebccd12f88c0fc074777027e2a21de5a90657e/ruff-0.12.10-py3-none-win32.whl", hash = "sha256:9de785e95dc2f09846c5e6e1d3a3d32ecd0b283a979898ad427a9be7be22b266", size = 11896089, upload-time = "2025-08-21T18:23:14.232Z" }, - { url = "https://files.pythonhosted.org/packages/ad/14/2ad38fd4037daab9e023456a4a40ed0154e9971f8d6aed41bdea390aabd9/ruff-0.12.10-py3-none-win_amd64.whl", hash = "sha256:7837eca8787f076f67aba2ca559cefd9c5cbc3a9852fd66186f4201b87c1563e", size = 13004616, upload-time = "2025-08-21T18:23:17.422Z" }, - { url = "https://files.pythonhosted.org/packages/24/3c/21cf283d67af33a8e6ed242396863af195a8a6134ec581524fd22b9811b6/ruff-0.12.10-py3-none-win_arm64.whl", hash = "sha256:cc138cc06ed9d4bfa9d667a65af7172b47840e1a98b02ce7011c391e54635ffc", size = 12074225, upload-time = "2025-08-21T18:23:20.137Z" }, +version = "0.12.11" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/de/55/16ab6a7d88d93001e1ae4c34cbdcfb376652d761799459ff27c1dc20f6fa/ruff-0.12.11.tar.gz", hash = "sha256:c6b09ae8426a65bbee5425b9d0b82796dbb07cb1af045743c79bfb163001165d", size = 5347103, upload-time = "2025-08-28T13:59:08.87Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/d6/a2/3b3573e474de39a7a475f3fbaf36a25600bfeb238e1a90392799163b64a0/ruff-0.12.11-py3-none-linux_armv6l.whl", hash = "sha256:93fce71e1cac3a8bf9200e63a38ac5c078f3b6baebffb74ba5274fb2ab276065", size = 11979885, upload-time = "2025-08-28T13:58:26.654Z" }, + { url = "https://files.pythonhosted.org/packages/76/e4/235ad6d1785a2012d3ded2350fd9bc5c5af8c6f56820e696b0118dfe7d24/ruff-0.12.11-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:b8e33ac7b28c772440afa80cebb972ffd823621ded90404f29e5ab6d1e2d4b93", size = 12742364, upload-time = "2025-08-28T13:58:30.256Z" }, + { url = "https://files.pythonhosted.org/packages/2c/0d/15b72c5fe6b1e402a543aa9d8960e0a7e19dfb079f5b0b424db48b7febab/ruff-0.12.11-py3-none-macosx_11_0_arm64.whl", hash = "sha256:d69fb9d4937aa19adb2e9f058bc4fbfe986c2040acb1a4a9747734834eaa0bfd", size = 11920111, upload-time = "2025-08-28T13:58:33.677Z" }, + { url = "https://files.pythonhosted.org/packages/3e/c0/f66339d7893798ad3e17fa5a1e587d6fd9806f7c1c062b63f8b09dda6702/ruff-0.12.11-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:411954eca8464595077a93e580e2918d0a01a19317af0a72132283e28ae21bee", size = 12160060, upload-time = "2025-08-28T13:58:35.74Z" }, + { url = "https://files.pythonhosted.org/packages/03/69/9870368326db26f20c946205fb2d0008988aea552dbaec35fbacbb46efaa/ruff-0.12.11-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:6a2c0a2e1a450f387bf2c6237c727dd22191ae8c00e448e0672d624b2bbd7fb0", size = 11799848, upload-time = "2025-08-28T13:58:38.051Z" }, + { url = "https://files.pythonhosted.org/packages/25/8c/dd2c7f990e9b3a8a55eee09d4e675027d31727ce33cdb29eab32d025bdc9/ruff-0.12.11-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8ca4c3a7f937725fd2413c0e884b5248a19369ab9bdd850b5781348ba283f644", size = 13536288, upload-time = "2025-08-28T13:58:40.046Z" }, + { url = "https://files.pythonhosted.org/packages/7a/30/d5496fa09aba59b5e01ea76775a4c8897b13055884f56f1c35a4194c2297/ruff-0.12.11-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:4d1df0098124006f6a66ecf3581a7f7e754c4df7644b2e6704cd7ca80ff95211", size = 14490633, upload-time = "2025-08-28T13:58:42.285Z" }, + { url = "https://files.pythonhosted.org/packages/9b/2f/81f998180ad53445d403c386549d6946d0748e536d58fce5b5e173511183/ruff-0.12.11-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5a8dd5f230efc99a24ace3b77e3555d3fbc0343aeed3fc84c8d89e75ab2ff793", size = 13888430, upload-time = "2025-08-28T13:58:44.641Z" }, + { url = "https://files.pythonhosted.org/packages/87/71/23a0d1d5892a377478c61dbbcffe82a3476b050f38b5162171942a029ef3/ruff-0.12.11-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4dc75533039d0ed04cd33fb8ca9ac9620b99672fe7ff1533b6402206901c34ee", size = 12913133, upload-time = "2025-08-28T13:58:47.039Z" }, + { url = "https://files.pythonhosted.org/packages/80/22/3c6cef96627f89b344c933781ed38329bfb87737aa438f15da95907cbfd5/ruff-0.12.11-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4fc58f9266d62c6eccc75261a665f26b4ef64840887fc6cbc552ce5b29f96cc8", size = 13169082, upload-time = "2025-08-28T13:58:49.157Z" }, + { url = "https://files.pythonhosted.org/packages/05/b5/68b3ff96160d8b49e8dd10785ff3186be18fd650d356036a3770386e6c7f/ruff-0.12.11-py3-none-manylinux_2_31_riscv64.whl", hash = "sha256:5a0113bd6eafd545146440225fe60b4e9489f59eb5f5f107acd715ba5f0b3d2f", size = 13139490, upload-time = "2025-08-28T13:58:51.593Z" }, + { url = "https://files.pythonhosted.org/packages/59/b9/050a3278ecd558f74f7ee016fbdf10591d50119df8d5f5da45a22c6afafc/ruff-0.12.11-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:0d737b4059d66295c3ea5720e6efc152623bb83fde5444209b69cd33a53e2000", size = 11958928, upload-time = "2025-08-28T13:58:53.943Z" }, + { url = "https://files.pythonhosted.org/packages/f9/bc/93be37347db854806904a43b0493af8d6873472dfb4b4b8cbb27786eb651/ruff-0.12.11-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:916fc5defee32dbc1fc1650b576a8fed68f5e8256e2180d4d9855aea43d6aab2", size = 11764513, upload-time = "2025-08-28T13:58:55.976Z" }, + { url = "https://files.pythonhosted.org/packages/7a/a1/1471751e2015a81fd8e166cd311456c11df74c7e8769d4aabfbc7584c7ac/ruff-0.12.11-py3-none-musllinux_1_2_i686.whl", hash = "sha256:c984f07d7adb42d3ded5be894fb4007f30f82c87559438b4879fe7aa08c62b39", size = 12745154, upload-time = "2025-08-28T13:58:58.16Z" }, + { url = "https://files.pythonhosted.org/packages/68/ab/2542b14890d0f4872dd81b7b2a6aed3ac1786fae1ce9b17e11e6df9e31e3/ruff-0.12.11-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:e07fbb89f2e9249f219d88331c833860489b49cdf4b032b8e4432e9b13e8a4b9", size = 13227653, upload-time = "2025-08-28T13:59:00.276Z" }, + { url = "https://files.pythonhosted.org/packages/22/16/2fbfc61047dbfd009c58a28369a693a1484ad15441723be1cd7fe69bb679/ruff-0.12.11-py3-none-win32.whl", hash = "sha256:c792e8f597c9c756e9bcd4d87cf407a00b60af77078c96f7b6366ea2ce9ba9d3", size = 11944270, upload-time = "2025-08-28T13:59:02.347Z" }, + { url = "https://files.pythonhosted.org/packages/08/a5/34276984705bfe069cd383101c45077ee029c3fe3b28225bf67aa35f0647/ruff-0.12.11-py3-none-win_amd64.whl", hash = "sha256:a3283325960307915b6deb3576b96919ee89432ebd9c48771ca12ee8afe4a0fd", size = 13046600, upload-time = "2025-08-28T13:59:04.751Z" }, + { url = "https://files.pythonhosted.org/packages/84/a8/001d4a7c2b37623a3fd7463208267fb906df40ff31db496157549cfd6e72/ruff-0.12.11-py3-none-win_arm64.whl", hash = "sha256:bae4d6e6a2676f8fb0f98b74594a048bae1b944aab17e9f5d504062303c6dbea", size = 12135290, upload-time = "2025-08-28T13:59:06.933Z" }, ] [[package]] @@ -4640,15 +4662,15 @@ wheels = [ [[package]] name = "sentry-sdk" -version = "2.35.1" +version = "2.35.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "certifi" }, { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/72/75/6223b9ffa0bf5a79ece08055469be73c18034e46ed082742a0899cc58351/sentry_sdk-2.35.1.tar.gz", hash = "sha256:241b41e059632fe1f7c54ae6e1b93af9456aebdfc297be9cf7ecfd6da5167e8e", size = 343145, upload-time = "2025-08-26T08:23:32.429Z" } +sdist = { url = "https://files.pythonhosted.org/packages/bd/79/0ecb942f3f1ad26c40c27f81ff82392d85c01d26a45e3c72c2b37807e680/sentry_sdk-2.35.2.tar.gz", hash = "sha256:e9e8f3c795044beb59f2c8f4c6b9b0f9779e5e604099882df05eec525e782cc6", size = 343377, upload-time = "2025-09-01T11:00:58.633Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/62/1f/5feb6c42cc30126e9574eabc28139f8c626b483a47c537f648d133628df0/sentry_sdk-2.35.1-py2.py3-none-any.whl", hash = "sha256:13b6d6cfdae65d61fe1396a061cf9113b20f0ec1bcb257f3826b88f01bb55720", size = 363887, upload-time = "2025-08-26T08:23:30.335Z" }, + { url = "https://files.pythonhosted.org/packages/c0/91/a43308dc82a0e32d80cd0dfdcfca401ecbd0f431ab45f24e48bb97b7800d/sentry_sdk-2.35.2-py2.py3-none-any.whl", hash = "sha256:38c98e3cbb620dd3dd80a8d6e39c753d453dd41f8a9df581b0584c19a52bc926", size = 363975, upload-time = "2025-09-01T11:00:56.574Z" }, ] [[package]]