From a7dfd36c00c910b694dfd3e2b3f6e0a8cc892802 Mon Sep 17 00:00:00 2001 From: Lukas <61192133+lukasloetkolben@users.noreply.github.com> Date: Wed, 21 Jan 2026 00:15:12 +0100 Subject: [PATCH 01/46] docs: comma 3X to comma four (#37009) * comma 3X -> comma four * add comma four ports image --- README.md | 8 ++++---- docs/CONTRIBUTING.md | 8 ++++---- docs/assets/four-ports.svg | 3 +++ docs/concepts/glossary.md | 2 +- docs/getting-started/what-is-openpilot.md | 2 +- docs/how-to/connect-to-comma.md | 17 +++++++++-------- docs/how-to/replay-a-drive.md | 2 +- mkdocs.yml | 2 +- selfdrive/debug/README.md | 2 +- tools/camerastream/README.md | 2 +- tools/joystick/joystick_control.py | 4 ++-- tools/replay/README.md | 2 +- 12 files changed, 29 insertions(+), 25 deletions(-) create mode 100644 docs/assets/four-ports.svg diff --git a/README.md b/README.md index a77a80935d..158bb08c49 100644 --- a/README.md +++ b/README.md @@ -17,7 +17,7 @@ · Community · - Try it on a comma 3X + Try it on a comma four Quick start: `bash <(curl -fsSL openpilot.comma.ai)` @@ -42,10 +42,10 @@ Using openpilot in a car ------ To use openpilot in a car, you need four things: -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. +1. **Supported Device:** a comma four, available at [comma.ai/shop](https://comma.ai/shop/comma-3x). +2. **Software:** The setup procedure for the comma four 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 3X to your car. +4. **Car Harness:** You will also need a [car harness](https://comma.ai/shop/car-harness) to connect your comma four 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/docs/CONTRIBUTING.md b/docs/CONTRIBUTING.md index 7583095eaf..d189324ff7 100644 --- a/docs/CONTRIBUTING.md +++ b/docs/CONTRIBUTING.md @@ -13,13 +13,13 @@ Development is coordinated through [Discord](https://discord.comma.ai) and GitHu ## What contributions are we looking for? **openpilot's priorities are [safety](SAFETY.md), stability, quality, and features, in that order.** -openpilot is part of comma's mission to *solve self-driving cars while delivering shippable intermediaries*, and all development is towards that goal. +openpilot is part of comma's mission to *solve self-driving cars while delivering shippable intermediaries*, and all development is towards that goal. ### What gets merged? The probability of a pull request being merged is a function of its value to the project and the effort it will take us to get it merged. If a PR offers *some* value but will take lots of time to get merged, it will be closed. -Simple, well-tested bug fixes are the easiest to merge, and new features are the hardest to get merged. +Simple, well-tested bug fixes are the easiest to merge, and new features are the hardest to get merged. All of these are examples of good PRs: * typo fix: https://github.com/commaai/openpilot/pull/30678 @@ -29,7 +29,7 @@ All of these are examples of good PRs: ### What doesn't get merged? -* **style changes**: code is art, and it's up to the author to make it beautiful +* **style changes**: code is art, and it's up to the author to make it beautiful * **500+ line PRs**: clean it up, break it up into smaller PRs, or both * **PRs without a clear goal**: every PR must have a singular and clear goal * **UI design**: we do not have a good review process for this yet @@ -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 3X or a car. +There's lot of bounties that don't require a comma four or a car. ## Pull Requests diff --git a/docs/assets/four-ports.svg b/docs/assets/four-ports.svg new file mode 100644 index 0000000000..7bab31abf3 --- /dev/null +++ b/docs/assets/four-ports.svg @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:494bd79c4d81d8bf766845cb451fa14e5b9ad931ff8aa90daea0ba67e164abe3 +size 105562 diff --git a/docs/concepts/glossary.md b/docs/concepts/glossary.md index a09b0f0785..df9e9aa080 100644 --- a/docs/concepts/glossary.md +++ b/docs/concepts/glossary.md @@ -6,4 +6,4 @@ * **segment**: routes are split into one minute chunks called segments. * **comma connect**: the web viewer for all your routes; check it out at [connect.comma.ai](https://connect.comma.ai). * **panda**: this is the secondary processor on the device that implements the functional safety and directly talks to the car over CAN. See the [panda repo](https://github.com/commaai/panda). -* **comma 3X**: the latest hardware by comma.ai for running openpilot. more info at [comma.ai/shop](https://comma.ai/shop). +* **comma four**: the latest hardware by comma.ai for running openpilot. more info at [comma.ai/shop](https://comma.ai/shop). diff --git a/docs/getting-started/what-is-openpilot.md b/docs/getting-started/what-is-openpilot.md index b3c56c8410..6fab2b979b 100644 --- a/docs/getting-started/what-is-openpilot.md +++ b/docs/getting-started/what-is-openpilot.md @@ -5,7 +5,7 @@ ## How do I use it? -openpilot is designed to be used on the comma 3X. +openpilot is designed to be used on the comma four. ## How does it work? diff --git a/docs/how-to/connect-to-comma.md b/docs/how-to/connect-to-comma.md index 5f02e11599..f0e45b19af 100644 --- a/docs/how-to/connect-to-comma.md +++ b/docs/how-to/connect-to-comma.md @@ -1,19 +1,20 @@ -# connect to a comma 3X +# Connect to comma 3X or comma four -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). +A comma four 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. +On the comma 3X, the serial console is accessible from the main OBD-C port. 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. - -On the comma 3X, the serial console is accessible through the [panda](https://github.com/commaai/panda) using the `panda/tests/som_debug.sh` script. +The serial console is accessible through the [panda](https://github.com/commaai/panda) using the `panda/tests/som_debug.sh` script. * Username: `comma` * Password: `comma` +> [!NOTE] +> Serial console access through the OBD-C port is not available on the comma four. On comma four devices, serial access requires opening the device to access the internal debug connector. + ## SSH In order to SSH into your device, you'll need a GitHub account with SSH keys. See this [GitHub article](https://docs.github.com/en/github/authenticating-to-github/connecting-to-github-with-ssh) for getting your account setup with SSH keys. @@ -34,7 +35,7 @@ For doing development work on device, it's recommended to use [SSH agent forward In order to use ADB on your device, you'll need to perform the following steps using the image below for reference: -![comma 3/3x back](../assets/three-back.svg) +![comma four ports](../assets/four-ports.svg) * Plug your device into constant power using port 2, letting the device boot up * Enable ADB in your device's settings @@ -45,7 +46,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 3X. +> The default port for ADB is 5555 on the comma four. 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 b0db36a46f..a11b29dcc4 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 3X* +*Hardware required: jungle and comma four* 1. Connect your PC to a jungle. 2. diff --git a/mkdocs.yml b/mkdocs.yml index 550f807aca..f54c6e39bb 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 3X: how-to/connect-to-comma.md + - Connect to a comma 3X or comma four: 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/selfdrive/debug/README.md b/selfdrive/debug/README.md index 83b8a994db..172cf700e4 100644 --- a/selfdrive/debug/README.md +++ b/selfdrive/debug/README.md @@ -52,7 +52,7 @@ optional arguments: -h, --help show this help message and exit --debug enable ISO-TP/UDS stack debugging output -This tool is meant to run directly on a vehicle-installed comma three, with +This tool is meant to run directly on a vehicle-installed comma four, with the openpilot/tmux processes stopped. It should also work on a separate PC with a USB- attached comma panda. Vehicle ignition must be on. Recommend engine not be running when making changes. Must turn ignition off and on again for any changes to take effect. diff --git a/tools/camerastream/README.md b/tools/camerastream/README.md index 2f7498a07c..f75ebbf0fb 100644 --- a/tools/camerastream/README.md +++ b/tools/camerastream/README.md @@ -49,7 +49,7 @@ usage: compressed_vipc.py [-h] [--nvidia] [--cams CAMS] [--silent] addr Decode video streams and broadcast on VisionIPC positional arguments: - addr Address of comma three + addr Address of comma four options: -h, --help show this help message and exit diff --git a/tools/joystick/joystick_control.py b/tools/joystick/joystick_control.py index 11d17e587e..8fe28ec0f0 100755 --- a/tools/joystick/joystick_control.py +++ b/tools/joystick/joystick_control.py @@ -42,7 +42,7 @@ class Keyboard: class Joystick: def __init__(self): - # This class supports a PlayStation 5 DualSense controller on the comma 3X + # This class supports a PlayStation 5 DualSense controller on the comma four # TODO: find a way to get this from API or detect gamepad/PC, perhaps "inputs" doesn't support it self.cancel_button = 'BTN_NORTH' # BTN_NORTH=X/triangle if HARDWARE.get_device_type() == 'pc': @@ -123,7 +123,7 @@ def main(): if __name__ == '__main__': parser = argparse.ArgumentParser(description='Publishes events from your joystick to control your car.\n' + 'openpilot must be offroad before starting joystick_control. This tool supports ' + - 'a PlayStation 5 DualSense controller on the comma 3X.', + 'a PlayStation 5 DualSense controller on the comma four.', formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument('--keyboard', action='store_true', help='Use your keyboard instead of a joystick') args = parser.parse_args() diff --git a/tools/replay/README.md b/tools/replay/README.md index 794c08f6a3..97ee91d988 100644 --- a/tools/replay/README.md +++ b/tools/replay/README.md @@ -101,7 +101,7 @@ tools/plotjuggler/juggle.py --stream ## watch3 -watch all three cameras simultaneously from your comma three routes with watch3 +watch all three cameras simultaneously from your comma four routes with watch3 simply replay a route using the `--dcam` and `--ecam` flags: From adf6f28ebf31fc3dcc502a5d761bf113d0d46546 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Tue, 20 Jan 2026 15:34:57 -0800 Subject: [PATCH 02/46] LatcontrolTorque: always fill buffer (#36991) --- selfdrive/controls/lib/latcontrol_torque.py | 17 +++++++++-------- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 0ba38736db..1f7fb4dfa4 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -59,27 +59,28 @@ class LatControlTorque(LatControl): def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, curvature_limited, lat_delay): pid_log = log.ControlsState.LateralTorqueState.new_message() pid_log.version = VERSION + measured_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) + measurement = measured_curvature * CS.vEgo ** 2 + future_desired_lateral_accel = desired_curvature * CS.vEgo ** 2 + self.lat_accel_request_buffer.append(future_desired_lateral_accel) + if not active: output_torque = 0.0 pid_log.active = False else: - measured_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)) lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 - delay_frames = int(np.clip(lat_delay / self.dt, 1, self.lat_accel_request_buffer_len)) + delay_frames = int(np.clip(lat_delay / self.dt + 1, 1, self.lat_accel_request_buffer_len)) expected_lateral_accel = self.lat_accel_request_buffer[-delay_frames] + setpoint = expected_lateral_accel + error = setpoint - measurement + lookahead_idx = int(np.clip(-delay_frames + self.lookahead_frames, -self.lat_accel_request_buffer_len+1, -2)) raw_lateral_jerk = (self.lat_accel_request_buffer[lookahead_idx+1] - self.lat_accel_request_buffer[lookahead_idx-1]) / (2 * self.dt) desired_lateral_jerk = self.jerk_filter.update(raw_lateral_jerk) - future_desired_lateral_accel = desired_curvature * CS.vEgo ** 2 - self.lat_accel_request_buffer.append(future_desired_lateral_accel) gravity_adjusted_future_lateral_accel = future_desired_lateral_accel - roll_compensation - setpoint = expected_lateral_accel - - measurement = measured_curvature * CS.vEgo ** 2 - error = setpoint - measurement # do error correction in lateral acceleration space, convert at end to handle non-linear torque responses correctly pid_log.error = float(error) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index c109bf49f1..274bec8b4f 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -b259f6f8f099a9d82e4c65dd5deae2e4e293007b \ No newline at end of file +cdd8ecaf03b0581d6a4df7659b916f3d22167a23 \ No newline at end of file From 79472cdf83c65345e666f40069ac34082bb4be84 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 20 Jan 2026 16:04:05 -0800 Subject: [PATCH 03/46] Revert "docs: comma 3X to comma four (#37009)" This reverts commit a7dfd36c00c910b694dfd3e2b3f6e0a8cc892802. --- README.md | 8 ++++---- docs/CONTRIBUTING.md | 8 ++++---- docs/assets/four-ports.svg | 3 --- docs/concepts/glossary.md | 2 +- docs/getting-started/what-is-openpilot.md | 2 +- docs/how-to/connect-to-comma.md | 17 ++++++++--------- docs/how-to/replay-a-drive.md | 2 +- mkdocs.yml | 2 +- selfdrive/debug/README.md | 2 +- tools/camerastream/README.md | 2 +- tools/joystick/joystick_control.py | 4 ++-- tools/replay/README.md | 2 +- 12 files changed, 25 insertions(+), 29 deletions(-) delete mode 100644 docs/assets/four-ports.svg diff --git a/README.md b/README.md index 158bb08c49..a77a80935d 100644 --- a/README.md +++ b/README.md @@ -17,7 +17,7 @@ · Community · - Try it on a comma four + Try it on a comma 3X Quick start: `bash <(curl -fsSL openpilot.comma.ai)` @@ -42,10 +42,10 @@ Using openpilot in a car ------ To use openpilot in a car, you need four things: -1. **Supported Device:** a comma four, available at [comma.ai/shop](https://comma.ai/shop/comma-3x). -2. **Software:** The setup procedure for the comma four 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 four 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/docs/CONTRIBUTING.md b/docs/CONTRIBUTING.md index d189324ff7..7583095eaf 100644 --- a/docs/CONTRIBUTING.md +++ b/docs/CONTRIBUTING.md @@ -13,13 +13,13 @@ Development is coordinated through [Discord](https://discord.comma.ai) and GitHu ## What contributions are we looking for? **openpilot's priorities are [safety](SAFETY.md), stability, quality, and features, in that order.** -openpilot is part of comma's mission to *solve self-driving cars while delivering shippable intermediaries*, and all development is towards that goal. +openpilot is part of comma's mission to *solve self-driving cars while delivering shippable intermediaries*, and all development is towards that goal. ### What gets merged? The probability of a pull request being merged is a function of its value to the project and the effort it will take us to get it merged. If a PR offers *some* value but will take lots of time to get merged, it will be closed. -Simple, well-tested bug fixes are the easiest to merge, and new features are the hardest to get merged. +Simple, well-tested bug fixes are the easiest to merge, and new features are the hardest to get merged. All of these are examples of good PRs: * typo fix: https://github.com/commaai/openpilot/pull/30678 @@ -29,7 +29,7 @@ All of these are examples of good PRs: ### What doesn't get merged? -* **style changes**: code is art, and it's up to the author to make it beautiful +* **style changes**: code is art, and it's up to the author to make it beautiful * **500+ line PRs**: clean it up, break it up into smaller PRs, or both * **PRs without a clear goal**: every PR must have a singular and clear goal * **UI design**: we do not have a good review process for this yet @@ -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 four or a car. +There's lot of bounties that don't require a comma 3X or a car. ## Pull Requests diff --git a/docs/assets/four-ports.svg b/docs/assets/four-ports.svg deleted file mode 100644 index 7bab31abf3..0000000000 --- a/docs/assets/four-ports.svg +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:494bd79c4d81d8bf766845cb451fa14e5b9ad931ff8aa90daea0ba67e164abe3 -size 105562 diff --git a/docs/concepts/glossary.md b/docs/concepts/glossary.md index df9e9aa080..a09b0f0785 100644 --- a/docs/concepts/glossary.md +++ b/docs/concepts/glossary.md @@ -6,4 +6,4 @@ * **segment**: routes are split into one minute chunks called segments. * **comma connect**: the web viewer for all your routes; check it out at [connect.comma.ai](https://connect.comma.ai). * **panda**: this is the secondary processor on the device that implements the functional safety and directly talks to the car over CAN. See the [panda repo](https://github.com/commaai/panda). -* **comma four**: the latest hardware by comma.ai for running openpilot. more info at [comma.ai/shop](https://comma.ai/shop). +* **comma 3X**: the latest hardware by comma.ai for running openpilot. more info at [comma.ai/shop](https://comma.ai/shop). diff --git a/docs/getting-started/what-is-openpilot.md b/docs/getting-started/what-is-openpilot.md index 6fab2b979b..b3c56c8410 100644 --- a/docs/getting-started/what-is-openpilot.md +++ b/docs/getting-started/what-is-openpilot.md @@ -5,7 +5,7 @@ ## How do I use it? -openpilot is designed to be used on the comma four. +openpilot is designed to be used on the comma 3X. ## How does it work? diff --git a/docs/how-to/connect-to-comma.md b/docs/how-to/connect-to-comma.md index f0e45b19af..5f02e11599 100644 --- a/docs/how-to/connect-to-comma.md +++ b/docs/how-to/connect-to-comma.md @@ -1,20 +1,19 @@ -# Connect to comma 3X or comma four +# connect to a comma 3X -A comma four 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 the comma 3X, the serial console is accessible from the main OBD-C port. +On both the comma three and 3X, the serial console is accessible from the main OBD-C port. 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. -The serial console is accessible through the [panda](https://github.com/commaai/panda) using the `panda/tests/som_debug.sh` script. +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. + +On the comma 3X, the serial console is accessible through the [panda](https://github.com/commaai/panda) using the `panda/tests/som_debug.sh` script. * Username: `comma` * Password: `comma` -> [!NOTE] -> Serial console access through the OBD-C port is not available on the comma four. On comma four devices, serial access requires opening the device to access the internal debug connector. - ## SSH In order to SSH into your device, you'll need a GitHub account with SSH keys. See this [GitHub article](https://docs.github.com/en/github/authenticating-to-github/connecting-to-github-with-ssh) for getting your account setup with SSH keys. @@ -35,7 +34,7 @@ For doing development work on device, it's recommended to use [SSH agent forward In order to use ADB on your device, you'll need to perform the following steps using the image below for reference: -![comma four ports](../assets/four-ports.svg) +![comma 3/3x back](../assets/three-back.svg) * Plug your device into constant power using port 2, letting the device boot up * Enable ADB in your device's settings @@ -46,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 four. +> 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 a11b29dcc4..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 four* +*Hardware required: jungle and comma 3X* 1. Connect your PC to a jungle. 2. diff --git a/mkdocs.yml b/mkdocs.yml index f54c6e39bb..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 3X or comma four: 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/selfdrive/debug/README.md b/selfdrive/debug/README.md index 172cf700e4..83b8a994db 100644 --- a/selfdrive/debug/README.md +++ b/selfdrive/debug/README.md @@ -52,7 +52,7 @@ optional arguments: -h, --help show this help message and exit --debug enable ISO-TP/UDS stack debugging output -This tool is meant to run directly on a vehicle-installed comma four, with +This tool is meant to run directly on a vehicle-installed comma three, with the openpilot/tmux processes stopped. It should also work on a separate PC with a USB- attached comma panda. Vehicle ignition must be on. Recommend engine not be running when making changes. Must turn ignition off and on again for any changes to take effect. diff --git a/tools/camerastream/README.md b/tools/camerastream/README.md index f75ebbf0fb..2f7498a07c 100644 --- a/tools/camerastream/README.md +++ b/tools/camerastream/README.md @@ -49,7 +49,7 @@ usage: compressed_vipc.py [-h] [--nvidia] [--cams CAMS] [--silent] addr Decode video streams and broadcast on VisionIPC positional arguments: - addr Address of comma four + addr Address of comma three options: -h, --help show this help message and exit diff --git a/tools/joystick/joystick_control.py b/tools/joystick/joystick_control.py index 8fe28ec0f0..11d17e587e 100755 --- a/tools/joystick/joystick_control.py +++ b/tools/joystick/joystick_control.py @@ -42,7 +42,7 @@ class Keyboard: class Joystick: def __init__(self): - # This class supports a PlayStation 5 DualSense controller on the comma four + # This class supports a PlayStation 5 DualSense controller on the comma 3X # TODO: find a way to get this from API or detect gamepad/PC, perhaps "inputs" doesn't support it self.cancel_button = 'BTN_NORTH' # BTN_NORTH=X/triangle if HARDWARE.get_device_type() == 'pc': @@ -123,7 +123,7 @@ def main(): if __name__ == '__main__': parser = argparse.ArgumentParser(description='Publishes events from your joystick to control your car.\n' + 'openpilot must be offroad before starting joystick_control. This tool supports ' + - 'a PlayStation 5 DualSense controller on the comma four.', + 'a PlayStation 5 DualSense controller on the comma 3X.', formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument('--keyboard', action='store_true', help='Use your keyboard instead of a joystick') args = parser.parse_args() diff --git a/tools/replay/README.md b/tools/replay/README.md index 97ee91d988..794c08f6a3 100644 --- a/tools/replay/README.md +++ b/tools/replay/README.md @@ -101,7 +101,7 @@ tools/plotjuggler/juggle.py --stream ## watch3 -watch all three cameras simultaneously from your comma four routes with watch3 +watch all three cameras simultaneously from your comma three routes with watch3 simply replay a route using the `--dcam` and `--ecam` flags: From bc979ea6aa858a811b8ecb75485577ecf10f251d Mon Sep 17 00:00:00 2001 From: felsager <76905857+felsager@users.noreply.github.com> Date: Tue, 20 Jan 2026 16:16:38 -0800 Subject: [PATCH 04/46] Latcontrol torque test: ensure desired lateral accel buffer is consistent (#37004) --- .../tests/test_latcontrol_torque_buffer.py | 36 +++++++++++++++++++ 1 file changed, 36 insertions(+) create mode 100644 selfdrive/controls/tests/test_latcontrol_torque_buffer.py diff --git a/selfdrive/controls/tests/test_latcontrol_torque_buffer.py b/selfdrive/controls/tests/test_latcontrol_torque_buffer.py new file mode 100644 index 0000000000..76d0c28423 --- /dev/null +++ b/selfdrive/controls/tests/test_latcontrol_torque_buffer.py @@ -0,0 +1,36 @@ +from parameterized import parameterized + +from cereal import car, log +from opendbc.car.car_helpers import interfaces +from opendbc.car.toyota.values import CAR as TOYOTA +from opendbc.car.vehicle_model import VehicleModel +from openpilot.common.realtime import DT_CTRL +from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque, LAT_ACCEL_REQUEST_BUFFER_SECONDS + +def get_controller(car_name): + CarInterface = interfaces[car_name] + CP = CarInterface.get_non_essential_params(car_name) + CI = CarInterface(CP) + VM = VehicleModel(CP) + controller = LatControlTorque(CP.as_reader(), CI, DT_CTRL) + return controller, VM + +class TestLatControlTorqueBuffer: + + @parameterized.expand([(TOYOTA.TOYOTA_COROLLA_TSS2,)]) + def test_request_buffer_consistency(self, car_name): + buffer_steps = int(LAT_ACCEL_REQUEST_BUFFER_SECONDS / DT_CTRL) + controller, VM = get_controller(car_name) + + CS = car.CarState.new_message() + CS.vEgo = 30 + CS.steeringPressed = False + params = log.LiveParametersData.new_message() + + for _ in range(buffer_steps): + controller.update(True, CS, VM, params, False, 0.001, False, 0.2) + assert all(val != 0 for val in controller.lat_accel_request_buffer) + + for _ in range(buffer_steps): + controller.update(False, CS, VM, params, False, 0.0, False, 0.2) + assert all(val == 0 for val in controller.lat_accel_request_buffer) From c9cfe2c7273074a350a39fd4d78d16933cb6a81f Mon Sep 17 00:00:00 2001 From: felsager <76905857+felsager@users.noreply.github.com> Date: Wed, 21 Jan 2026 12:32:56 -0800 Subject: [PATCH 05/46] LatcontrolTorque: move jerk calculation and filtering outside if else (#37011) --- selfdrive/controls/lib/latcontrol_torque.py | 36 ++++++++++----------- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 19 insertions(+), 19 deletions(-) diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 1f7fb4dfa4..903700d4b3 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -64,30 +64,30 @@ class LatControlTorque(LatControl): future_desired_lateral_accel = desired_curvature * CS.vEgo ** 2 self.lat_accel_request_buffer.append(future_desired_lateral_accel) + 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)) + lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 + + delay_frames = int(np.clip(lat_delay / self.dt + 1, 1, self.lat_accel_request_buffer_len)) + expected_lateral_accel = self.lat_accel_request_buffer[-delay_frames] + setpoint = expected_lateral_accel + error = setpoint - measurement + + lookahead_idx = int(np.clip(-delay_frames + self.lookahead_frames, -self.lat_accel_request_buffer_len+1, -2)) + raw_lateral_jerk = (self.lat_accel_request_buffer[lookahead_idx+1] - self.lat_accel_request_buffer[lookahead_idx-1]) / (2 * self.dt) + desired_lateral_jerk = self.jerk_filter.update(raw_lateral_jerk) + gravity_adjusted_future_lateral_accel = future_desired_lateral_accel - roll_compensation + ff = gravity_adjusted_future_lateral_accel + # latAccelOffset corrects roll compensation bias from device roll misalignment relative to car roll + ff -= self.torque_params.latAccelOffset + ff += get_friction(error + JERK_GAIN * desired_lateral_jerk, lateral_accel_deadzone, FRICTION_THRESHOLD, self.torque_params) + if not active: output_torque = 0.0 pid_log.active = False else: - 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)) - lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 - - delay_frames = int(np.clip(lat_delay / self.dt + 1, 1, self.lat_accel_request_buffer_len)) - expected_lateral_accel = self.lat_accel_request_buffer[-delay_frames] - setpoint = expected_lateral_accel - error = setpoint - measurement - - lookahead_idx = int(np.clip(-delay_frames + self.lookahead_frames, -self.lat_accel_request_buffer_len+1, -2)) - raw_lateral_jerk = (self.lat_accel_request_buffer[lookahead_idx+1] - self.lat_accel_request_buffer[lookahead_idx-1]) / (2 * self.dt) - desired_lateral_jerk = self.jerk_filter.update(raw_lateral_jerk) - gravity_adjusted_future_lateral_accel = future_desired_lateral_accel - roll_compensation - # do error correction in lateral acceleration space, convert at end to handle non-linear torque responses correctly pid_log.error = float(error) - ff = gravity_adjusted_future_lateral_accel - # latAccelOffset corrects roll compensation bias from device roll misalignment relative to car roll - ff -= self.torque_params.latAccelOffset - ff += get_friction(error + JERK_GAIN * desired_lateral_jerk, lateral_accel_deadzone, FRICTION_THRESHOLD, self.torque_params) freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5 output_lataccel = self.pid.update(pid_log.error, speed=CS.vEgo, feedforward=ff, freeze_integrator=freeze_integrator) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 274bec8b4f..7b9039180c 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -cdd8ecaf03b0581d6a4df7659b916f3d22167a23 \ No newline at end of file +77951c4ccd0916b87c8dfda9faa33cd2d5d2cc11 \ No newline at end of file From 1459d3519da2fdb2d981baf7811c2eaa2127eb80 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Thu, 22 Jan 2026 18:41:08 -0800 Subject: [PATCH 06/46] DM: Ford GT model (#37013) * b483cec4-7816-4570-a774-be3a2c100098/50 * shipfest * da4b8724-8998-45da-aa36-d8fb390492b9 * revert * typo * deprecates --- cereal/log.capnp | 4 +-- .../modeld/models/dmonitoring_model.onnx | 4 +-- selfdrive/monitoring/helpers.py | 25 +++---------------- 3 files changed, 8 insertions(+), 25 deletions(-) diff --git a/cereal/log.capnp b/cereal/log.capnp index 2f300881b1..12bef17b95 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -2227,9 +2227,9 @@ struct DriverMonitoringState @0xb83cda094a1da284 { isActiveMode @16 :Bool; isRHD @4 :Bool; uncertainCount @19 :UInt32; - phoneProbOffset @20 :Float32; - phoneProbValidCount @21 :UInt32; + phoneProbOffsetDEPRECATED @20 :Float32; + phoneProbValidCountDEPRECATED @21 :UInt32; isPreviewDEPRECATED @15 :Bool; rhdCheckedDEPRECATED @5 :Bool; eventsDEPRECATED @0 :List(Car.OnroadEventDEPRECATED); diff --git a/selfdrive/modeld/models/dmonitoring_model.onnx b/selfdrive/modeld/models/dmonitoring_model.onnx index 9b1c4a1834..4052a15481 100644 --- a/selfdrive/modeld/models/dmonitoring_model.onnx +++ b/selfdrive/modeld/models/dmonitoring_model.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3446bf8b22e50e47669a25bf32460ae8baf8547037f346753e19ecbfcf6d4e59 -size 6954368 +oid sha256:35e4a5d4c4d481f915e42358af4665b2c92b8f5c1efd1c0731f21b876ad1d856 +size 6954249 diff --git a/selfdrive/monitoring/helpers.py b/selfdrive/monitoring/helpers.py index 3377ce6c68..0b54504b64 100644 --- a/selfdrive/monitoring/helpers.py +++ b/selfdrive/monitoring/helpers.py @@ -35,14 +35,7 @@ class DRIVER_MONITOR_SETTINGS: self._EYE_THRESHOLD = 0.65 self._SG_THRESHOLD = 0.9 self._BLINK_THRESHOLD = 0.865 - - self._PHONE_THRESH = 0.75 if device_type == 'mici' else 0.4 - self._PHONE_THRESH2 = 15.0 - self._PHONE_MAX_OFFSET = 0.06 - self._PHONE_MIN_OFFSET = 0.025 - self._PHONE_DATA_AVG = 0.05 - self._PHONE_DATA_VAR = 3*0.005 - self._PHONE_MAX_COUNT = int(360 / self._DT_DMON) + self._PHONE_THRESH = 0.5 self._POSE_PITCH_THRESHOLD = 0.3133 self._POSE_PITCH_THRESHOLD_SLACK = 0.3237 @@ -152,11 +145,10 @@ class DriverMonitoring: # init driver status wheelpos_filter_raw_priors = (self.settings._WHEELPOS_DATA_AVG, self.settings._WHEELPOS_DATA_VAR, 2) - phone_filter_raw_priors = (self.settings._PHONE_DATA_AVG, self.settings._PHONE_DATA_VAR, 2) self.wheelpos = DriverProb(raw_priors=wheelpos_filter_raw_priors, max_trackable=self.settings._WHEELPOS_MAX_COUNT) - self.phone = DriverProb(raw_priors=phone_filter_raw_priors, max_trackable=self.settings._PHONE_MAX_COUNT) self.pose = DriverPose(settings=self.settings) self.blink = DriverBlink() + self.phone_prob = 0. self.always_on = always_on self.distracted_types = [] @@ -257,12 +249,7 @@ class DriverMonitoring: if (self.blink.left + self.blink.right)*0.5 > self.settings._BLINK_THRESHOLD: distracted_types.append(DistractedType.DISTRACTED_BLINK) - if self.phone.prob_calibrated: - using_phone = self.phone.prob > max(min(self.phone.prob_offseter.filtered_stat.M, self.settings._PHONE_MAX_OFFSET), self.settings._PHONE_MIN_OFFSET) \ - * self.settings._PHONE_THRESH2 - else: - using_phone = self.phone.prob > self.settings._PHONE_THRESH - if using_phone: + if self.phone_prob > self.settings._PHONE_THRESH: distracted_types.append(DistractedType.DISTRACTED_PHONE) return distracted_types @@ -301,7 +288,7 @@ class DriverMonitoring: * (driver_data.sunglassesProb < self.settings._SG_THRESHOLD) self.blink.right = driver_data.rightBlinkProb * (driver_data.rightEyeProb > self.settings._EYE_THRESHOLD) \ * (driver_data.sunglassesProb < self.settings._SG_THRESHOLD) - self.phone.prob = driver_data.phoneProb + self.phone_prob = driver_data.phoneProb self.distracted_types = self._get_distracted_types() self.driver_distracted = (DistractedType.DISTRACTED_PHONE in self.distracted_types @@ -315,11 +302,9 @@ class DriverMonitoring: if self.face_detected and car_speed > self.settings._POSE_CALIB_MIN_SPEED and self.pose.low_std and (not op_engaged or not self.driver_distracted): self.pose.pitch_offseter.push_and_update(self.pose.pitch) self.pose.yaw_offseter.push_and_update(self.pose.yaw) - self.phone.prob_offseter.push_and_update(self.phone.prob) self.pose.calibrated = self.pose.pitch_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT and \ self.pose.yaw_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT - self.phone.prob_calibrated = self.phone.prob_offseter.filtered_stat.n > self.settings._POSE_OFFSET_MIN_COUNT if self.face_detected and not self.driver_distracted: if model_std_max > self.settings._DCAM_UNCERTAIN_ALERT_THRESHOLD: @@ -425,8 +410,6 @@ class DriverMonitoring: "posePitchValidCount": self.pose.pitch_offseter.filtered_stat.n, "poseYawOffset": self.pose.yaw_offseter.filtered_stat.mean(), "poseYawValidCount": self.pose.yaw_offseter.filtered_stat.n, - "phoneProbOffset": self.phone.prob_offseter.filtered_stat.mean(), - "phoneProbValidCount": self.phone.prob_offseter.filtered_stat.n, "stepChange": self.step_change, "awarenessActive": self.awareness_active, "awarenessPassive": self.awareness_passive, From ba6e5f125dfa2f1e3fa3cd2a57be77de989fe3d6 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 23 Jan 2026 00:24:15 -0800 Subject: [PATCH 07/46] Fix bridge w/ ZMQ (#37018) * fix * can also do this * 1 less +lines but more diff - Revert "can also do this" This reverts commit 8e18218099af6d3bc852d8ef0069b80d9322d6ca. --- cereal/messaging/bridge.cc | 3 ++- cereal/messaging/msgq_to_zmq.cc | 4 +++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/cereal/messaging/bridge.cc b/cereal/messaging/bridge.cc index 69ecd188e1..fb92c575c9 100644 --- a/cereal/messaging/bridge.cc +++ b/cereal/messaging/bridge.cc @@ -33,7 +33,8 @@ void zmq_to_msgq(const std::vector &endpoints, const std::string &i for (auto endpoint : endpoints) { auto pub_sock = new MSGQPubSocket(); auto sub_sock = new ZMQSubSocket(); - pub_sock->connect(pub_context.get(), endpoint); + size_t queue_size = services.at(endpoint).queue_size; + pub_sock->connect(pub_context.get(), endpoint, true, queue_size); sub_sock->connect(sub_context.get(), endpoint, ip, false); poller->registerSocket(sub_sock); diff --git a/cereal/messaging/msgq_to_zmq.cc b/cereal/messaging/msgq_to_zmq.cc index ce626f2aad..7f8c738d4d 100644 --- a/cereal/messaging/msgq_to_zmq.cc +++ b/cereal/messaging/msgq_to_zmq.cc @@ -2,6 +2,7 @@ #include +#include "cereal/services.h" #include "common/util.h" extern ExitHandler do_exit; @@ -108,7 +109,8 @@ void MsgqToZmq::zmqMonitorThread() { if (++pair.connected_clients == 1) { // Create new MSGQ subscriber socket and map to ZMQ publisher pair.sub_sock = std::make_unique(); - pair.sub_sock->connect(msgq_context.get(), pair.endpoint, "127.0.0.1"); + size_t queue_size = services.at(pair.endpoint).queue_size; + pair.sub_sock->connect(msgq_context.get(), pair.endpoint, "127.0.0.1", false, true, queue_size); sub2pub[pair.sub_sock.get()] = pair.pub_sock.get(); registerSockets(); } From 3715fe85aa76506e3be33505ef5dab64979d24e8 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 23 Jan 2026 00:55:12 -0800 Subject: [PATCH 08/46] bump opendbc (#37019) --- opendbc_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc_repo b/opendbc_repo index 796ece26ac..1908668b05 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 796ece26acd8b9255810ca71941ed72626589ee7 +Subproject commit 1908668b05691564ea5fc80bc11b784a9dee0714 From 12220ec82dc50cd12e9df57e6c350ab0d774443e Mon Sep 17 00:00:00 2001 From: Matt Purnell <65473602+mpurnell1@users.noreply.github.com> Date: Fri, 23 Jan 2026 19:11:23 -0600 Subject: [PATCH 09/46] cereal: update msgq imports (#36833) Update outdated reference Co-authored-by: Adeeb Shihadeh --- cereal/messaging/__init__.py | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/cereal/messaging/__init__.py b/cereal/messaging/__init__.py index d5033cd634..2c925b4cc4 100644 --- a/cereal/messaging/__init__.py +++ b/cereal/messaging/__init__.py @@ -1,10 +1,8 @@ # must be built with scons -from msgq.ipc_pyx import Context, Poller, SubSocket, PubSocket, SocketEventHandle, toggle_fake_events, \ - set_fake_prefix, get_fake_prefix, delete_fake_prefix, wait_for_one_event -from msgq.ipc_pyx import MultiplePublishersError, IpcError -from msgq import fake_event_handle, drain_sock_raw +from msgq import fake_event_handle, drain_sock_raw, MultiplePublishersError, IpcError, \ + Context, Poller, SubSocket, PubSocket, SocketEventHandle, toggle_fake_events, \ + set_fake_prefix, get_fake_prefix, delete_fake_prefix, wait_for_one_event import msgq - import os import capnp import time From 560ed80123caa15ee9a7f81ecd57f05815ba857e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Kacper=20R=C4=85czy?= Date: Sat, 24 Jan 2026 04:04:54 +0000 Subject: [PATCH 10/46] tools: seekable URLFile (#37022) * Make URLFile seekable * Return value in seek --- tools/lib/url_file.py | 21 +++++++++++++++++++-- 1 file changed, 19 insertions(+), 2 deletions(-) diff --git a/tools/lib/url_file.py b/tools/lib/url_file.py index 790fa7e8fb..8e2f0a9222 100644 --- a/tools/lib/url_file.py +++ b/tools/lib/url_file.py @@ -192,8 +192,25 @@ class URLFile: raise URLFileException(f"Expected {len(ranges)} parts, got {len(parts)} ({self._url})") return parts - def seek(self, pos: int) -> None: - self._pos = int(pos) + def seekable(self) -> bool: + return True + + def seek(self, pos: int, whence: int = 0) -> int: + pos = int(pos) + if whence == os.SEEK_SET: + self._pos = pos + elif whence == os.SEEK_CUR: + self._pos += pos + elif whence == os.SEEK_END: + length = self.get_length() + assert length != -1, "Cannot seek from end on unknown length file" + self._pos = length + pos + else: + raise URLFileException("Invalid whence value") + return self._pos + + def tell(self) -> int: + return self._pos @property def name(self) -> str: From 7c90c0669a8257fb9e086d9ae392950cc511ce82 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 24 Jan 2026 10:51:41 -0800 Subject: [PATCH 11/46] script for CI results (#37024) --- scripts/ci_results.py | 209 ++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 209 insertions(+) create mode 100755 scripts/ci_results.py diff --git a/scripts/ci_results.py b/scripts/ci_results.py new file mode 100755 index 0000000000..c3d53f222a --- /dev/null +++ b/scripts/ci_results.py @@ -0,0 +1,209 @@ +#!/usr/bin/env python3 +"""Fetch CI results from GitHub Actions and Jenkins.""" + +import argparse +import json +import subprocess +import time +import urllib.error +import urllib.request +from datetime import datetime + +JENKINS_URL = "https://jenkins.comma.life" +DEFAULT_TIMEOUT = 1800 # 30 minutes +POLL_INTERVAL = 30 # seconds +LOG_TAIL_LINES = 10 # lines of log to include for failed jobs + + +def get_git_info(): + branch = subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"], text=True).strip() + commit = subprocess.check_output(["git", "rev-parse", "HEAD"], text=True).strip() + return branch, commit + + +def get_github_actions_status(commit_sha): + result = subprocess.run( + ["gh", "run", "list", "--commit", commit_sha, "--workflow", "tests.yaml", "--json", "databaseId,status,conclusion"], + capture_output=True, text=True, check=True + ) + runs = json.loads(result.stdout) + if not runs: + return None, None + + run_id = runs[0]["databaseId"] + result = subprocess.run( + ["gh", "run", "view", str(run_id), "--json", "jobs"], + capture_output=True, text=True, check=True + ) + data = json.loads(result.stdout) + jobs = {job["name"]: {"status": job["status"], "conclusion": job["conclusion"], + "duration": format_duration(job) if job["conclusion"] not in ("skipped", None) and job.get("startedAt") else "", + "id": job["databaseId"]} + for job in data.get("jobs", [])} + return jobs, run_id + + +def get_github_job_log(run_id, job_id): + result = subprocess.run( + ["gh", "run", "view", str(run_id), "--job", str(job_id), "--log-failed"], + capture_output=True, text=True + ) + lines = result.stdout.strip().split('\n') + return '\n'.join(lines[-LOG_TAIL_LINES:]) if len(lines) > LOG_TAIL_LINES else result.stdout.strip() + + +def format_duration(job): + start = datetime.fromisoformat(job["startedAt"].replace("Z", "+00:00")) + end = datetime.fromisoformat(job["completedAt"].replace("Z", "+00:00")) + secs = int((end - start).total_seconds()) + return f"{secs // 60}m {secs % 60}s" + + +def get_jenkins_status(branch, commit_sha): + base_url = f"{JENKINS_URL}/job/openpilot/job/{branch}" + try: + # Get list of recent builds + with urllib.request.urlopen(f"{base_url}/api/json?tree=builds[number,url]", timeout=10) as resp: + builds = json.loads(resp.read().decode()).get("builds", []) + + # Find build matching commit + for build in builds[:20]: # check last 20 builds + with urllib.request.urlopen(f"{build['url']}api/json", timeout=10) as resp: + data = json.loads(resp.read().decode()) + for action in data.get("actions", []): + if action.get("_class") == "hudson.plugins.git.util.BuildData": + build_sha = action.get("lastBuiltRevision", {}).get("SHA1", "") + if build_sha.startswith(commit_sha) or commit_sha.startswith(build_sha): + # Get stages info + stages = [] + try: + with urllib.request.urlopen(f"{build['url']}wfapi/describe", timeout=10) as resp2: + wf_data = json.loads(resp2.read().decode()) + stages = [{"name": s["name"], "status": s["status"]} for s in wf_data.get("stages", [])] + except urllib.error.HTTPError: + pass + return { + "number": data["number"], + "in_progress": data.get("inProgress", False), + "result": data.get("result"), + "url": data.get("url", ""), + "stages": stages, + } + return None # no build found for this commit + except urllib.error.HTTPError: + return None # branch doesn't exist on Jenkins + + +def get_jenkins_log(build_url): + url = f"{build_url}consoleText" + with urllib.request.urlopen(url, timeout=30) as resp: + text = resp.read().decode(errors='replace') + lines = text.strip().split('\n') + return '\n'.join(lines[-LOG_TAIL_LINES:]) if len(lines) > LOG_TAIL_LINES else text.strip() + + +def is_complete(gh_status, jenkins_status): + gh_done = gh_status is None or all(j["status"] == "completed" for j in gh_status.values()) + jenkins_done = jenkins_status is None or not jenkins_status.get("in_progress", True) + return gh_done and jenkins_done + + +def status_icon(status, conclusion=None): + if status == "completed": + return ":white_check_mark:" if conclusion == "success" else ":x:" + return ":hourglass:" if status == "in_progress" else ":grey_question:" + + +def format_markdown(gh_status, gh_run_id, jenkins_status, commit_sha, branch): + lines = ["# CI Results", "", + f"**Branch**: {branch}", + f"**Commit**: {commit_sha[:7]}", + f"**Generated**: {datetime.now().strftime('%Y-%m-%d %H:%M:%S')}", ""] + + lines.extend(["## GitHub Actions", "", "| Job | Status | Duration |", "|-----|--------|----------|"]) + failed_gh_jobs = [] + if gh_status: + for job_name, job in gh_status.items(): + icon = status_icon(job["status"], job.get("conclusion")) + conclusion = job.get("conclusion") or job["status"] + lines.append(f"| {job_name} | {icon} {conclusion} | {job.get('duration', '')} |") + if job.get("conclusion") == "failure": + failed_gh_jobs.append((job_name, job.get("id"))) + else: + lines.append("| - | No workflow runs found | |") + + lines.extend(["", "## Jenkins", "", "| Stage | Status |", "|-------|--------|"]) + failed_jenkins_stages = [] + if jenkins_status: + stages = jenkins_status.get("stages", []) + if stages: + for stage in stages: + icon = ":white_check_mark:" if stage["status"] == "SUCCESS" else ( + ":x:" if stage["status"] == "FAILED" else ":hourglass:") + lines.append(f"| {stage['name']} | {icon} {stage['status'].lower()} |") + if stage["status"] == "FAILED": + failed_jenkins_stages.append(stage["name"]) + else: + icon = ":hourglass:" if jenkins_status["in_progress"] else ( + ":white_check_mark:" if jenkins_status["result"] == "SUCCESS" else ":x:") + status = "in progress" if jenkins_status["in_progress"] else (jenkins_status["result"] or "unknown") + lines.append(f"| #{jenkins_status['number']} | {icon} {status.lower()} |") + if jenkins_status.get("url"): + lines.append(f"\n[View build]({jenkins_status['url']})") + else: + lines.append("| - | No builds found for branch |") + + if failed_gh_jobs or failed_jenkins_stages: + lines.extend(["", "## Failure Logs", ""]) + + for job_name, job_id in failed_gh_jobs: + lines.append(f"### GitHub Actions: {job_name}") + log = get_github_job_log(gh_run_id, job_id) + lines.extend(["", "```", log, "```", ""]) + + for stage_name in failed_jenkins_stages: + lines.append(f"### Jenkins: {stage_name}") + log = get_jenkins_log(jenkins_status["url"]) + lines.extend(["", "```", log, "```", ""]) + + return "\n".join(lines) + "\n" + + +def main(): + parser = argparse.ArgumentParser(description="Fetch CI results from GitHub Actions and Jenkins") + parser.add_argument("--wait", action="store_true", help="Wait for CI to complete") + parser.add_argument("--timeout", type=int, default=DEFAULT_TIMEOUT, help="Timeout in seconds (default: 1800)") + parser.add_argument("-o", "--output", default="ci_results.md", help="Output file (default: ci_results.md)") + parser.add_argument("--branch", help="Branch to check (default: current branch)") + parser.add_argument("--commit", help="Commit SHA to check (default: HEAD)") + args = parser.parse_args() + + branch, commit = get_git_info() + branch = args.branch or branch + commit = args.commit or commit + print(f"Fetching CI results for {branch} @ {commit[:7]}") + + start_time = time.monotonic() + while True: + gh_status, gh_run_id = get_github_actions_status(commit) + jenkins_status = get_jenkins_status(branch, commit) if branch != "HEAD" else None + + if not args.wait or is_complete(gh_status, jenkins_status): + break + + elapsed = time.monotonic() - start_time + if elapsed >= args.timeout: + print(f"Timeout after {int(elapsed)}s") + break + + print(f"CI still running, waiting {POLL_INTERVAL}s... ({int(elapsed)}s elapsed)") + time.sleep(POLL_INTERVAL) + + content = format_markdown(gh_status, gh_run_id, jenkins_status, commit, branch) + with open(args.output, "w") as f: + f.write(content) + print(f"Results written to {args.output}") + + +if __name__ == "__main__": + main() From de024fd4a7f7d92a825dbbf614078d123c2fc25c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 24 Jan 2026 12:02:33 -0800 Subject: [PATCH 12/46] pandad: pure Python capnp helpers (#37025) * pandad: pure Python capnp helpers * cleanup --- .../lib/longitudinal_mpc_lib/SConscript | 4 +- selfdrive/pandad/SConscript | 6 +- selfdrive/pandad/__init__.py | 1 - selfdrive/pandad/can_list_to_can_capnp.cc | 50 ----------- selfdrive/pandad/can_types.h | 15 ---- selfdrive/pandad/pandad_api_impl.py | 88 +++++++++++++++++++ selfdrive/pandad/pandad_api_impl.pyx | 56 ------------ 7 files changed, 91 insertions(+), 129 deletions(-) delete mode 100644 selfdrive/pandad/can_list_to_can_capnp.cc delete mode 100644 selfdrive/pandad/can_types.h create mode 100644 selfdrive/pandad/pandad_api_impl.py delete mode 100644 selfdrive/pandad/pandad_api_impl.pyx diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript index 164b965142..7a6c02a538 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript @@ -1,4 +1,4 @@ -Import('env', 'envCython', 'arch', 'msgq_python', 'common_python', 'pandad_python', 'np_version') +Import('env', 'envCython', 'arch', 'msgq_python', 'common_python', 'np_version') gen = "c_generated_code" @@ -67,7 +67,7 @@ lenv.Clean(generated_files, Dir(gen)) generated_long = lenv.Command(generated_files, source_list, f"cd {Dir('.').abspath} && python3 long_mpc.py") -lenv.Depends(generated_long, [msgq_python, common_python, pandad_python]) +lenv.Depends(generated_long, [msgq_python, common_python]) lenv["CFLAGS"].append("-DACADOS_WITH_QPOASES") lenv["CXXFLAGS"].append("-DACADOS_WITH_QPOASES") diff --git a/selfdrive/pandad/SConscript b/selfdrive/pandad/SConscript index 58777cafe9..5e0b782c1e 100644 --- a/selfdrive/pandad/SConscript +++ b/selfdrive/pandad/SConscript @@ -1,13 +1,9 @@ -Import('env', 'envCython', 'common', 'messaging') +Import('env', 'common', 'messaging') libs = ['usb-1.0', common, messaging, 'pthread'] panda = env.Library('panda', ['panda.cc', 'panda_comms.cc', 'spi.cc']) env.Program('pandad', ['main.cc', 'pandad.cc', 'panda_safety.cc'], LIBS=[panda] + libs) -env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) - -pandad_python = envCython.Program('pandad_api_impl.so', 'pandad_api_impl.pyx', LIBS=["can_list_to_can_capnp", 'capnp', 'kj'] + envCython["LIBS"]) -Export('pandad_python') if GetOption('extras'): env.Program('tests/test_pandad_usbprotocol', ['tests/test_pandad_usbprotocol.cc'], LIBS=[panda] + libs) diff --git a/selfdrive/pandad/__init__.py b/selfdrive/pandad/__init__.py index cc680e1676..0c17e886a2 100644 --- a/selfdrive/pandad/__init__.py +++ b/selfdrive/pandad/__init__.py @@ -1,4 +1,3 @@ -# Cython, now uses scons to build from openpilot.selfdrive.pandad.pandad_api_impl import can_list_to_can_capnp, can_capnp_to_list assert can_list_to_can_capnp assert can_capnp_to_list diff --git a/selfdrive/pandad/can_list_to_can_capnp.cc b/selfdrive/pandad/can_list_to_can_capnp.cc deleted file mode 100644 index f2cf153453..0000000000 --- a/selfdrive/pandad/can_list_to_can_capnp.cc +++ /dev/null @@ -1,50 +0,0 @@ -#include "cereal/messaging/messaging.h" -#include "selfdrive/pandad/can_types.h" - -void can_list_to_can_capnp_cpp(const std::vector &can_list, std::string &out, bool sendcan, bool valid) { - MessageBuilder msg; - auto event = msg.initEvent(valid); - - auto canData = sendcan ? event.initSendcan(can_list.size()) : event.initCan(can_list.size()); - int j = 0; - for (auto it = can_list.begin(); it != can_list.end(); it++, j++) { - auto c = canData[j]; - c.setAddress(it->address); - c.setDat(kj::arrayPtr((uint8_t*)it->dat.data(), it->dat.size())); - c.setSrc(it->src); - } - const uint64_t msg_size = capnp::computeSerializedSizeInWords(msg) * sizeof(capnp::word); - out.resize(msg_size); - kj::ArrayOutputStream output_stream(kj::ArrayPtr((unsigned char *)out.data(), msg_size)); - capnp::writeMessage(output_stream, msg); -} - -// Converts a vector of Cap'n Proto serialized can strings into a vector of CanData structures. -void can_capnp_to_can_list_cpp(const std::vector &strings, std::vector &can_list, bool sendcan) { - AlignedBuffer aligned_buf; - can_list.reserve(strings.size()); - - for (const auto &str : strings) { - // extract the messages - capnp::FlatArrayMessageReader reader(aligned_buf.align(str.data(), str.size())); - cereal::Event::Reader event = reader.getRoot(); - - auto frames = sendcan ? event.getSendcan() : event.getCan(); - - // Add new CanData entry - CanData &can_data = can_list.emplace_back(); - can_data.nanos = event.getLogMonoTime(); - can_data.frames.reserve(frames.size()); - - // Populate CAN frames - for (const auto &frame : frames) { - CanFrame &can_frame = can_data.frames.emplace_back(); - can_frame.src = frame.getSrc(); - can_frame.address = frame.getAddress(); - - // Copy CAN data - auto dat = frame.getDat(); - can_frame.dat.assign(dat.begin(), dat.end()); - } - } -} diff --git a/selfdrive/pandad/can_types.h b/selfdrive/pandad/can_types.h deleted file mode 100644 index 5fae581cfa..0000000000 --- a/selfdrive/pandad/can_types.h +++ /dev/null @@ -1,15 +0,0 @@ -#pragma once - -#include -#include - -struct CanFrame { - long src; - uint32_t address; - std::vector dat; -}; - -struct CanData { - uint64_t nanos; - std::vector frames; -}; \ No newline at end of file diff --git a/selfdrive/pandad/pandad_api_impl.py b/selfdrive/pandad/pandad_api_impl.py new file mode 100644 index 0000000000..75a7ba484e --- /dev/null +++ b/selfdrive/pandad/pandad_api_impl.py @@ -0,0 +1,88 @@ +import time +from cereal import log + +NO_TRAVERSAL_LIMIT = 2**64 - 1 + +# Cache schema fields for faster access (avoids string lookup on each field access) +_cached_reader_fields = None # (address_field, dat_field, src_field) for reading +_cached_writer_fields = None # (address_field, dat_field, src_field) for writing + + +def _get_reader_fields(schema): + """Get cached schema field objects for reading.""" + global _cached_reader_fields + if _cached_reader_fields is None: + fields = schema.fields + _cached_reader_fields = (fields['address'], fields['dat'], fields['src']) + return _cached_reader_fields + + +def _get_writer_fields(schema): + """Get cached schema field objects for writing.""" + global _cached_writer_fields + if _cached_writer_fields is None: + fields = schema.fields + _cached_writer_fields = (fields['address'], fields['dat'], fields['src']) + return _cached_writer_fields + + +def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): + """Convert list of CAN messages to Cap'n Proto serialized bytes. + + Args: + can_msgs: List of tuples [(address, data_bytes, src), ...] + msgtype: 'can' or 'sendcan' + valid: Whether the event is valid + + Returns: + Cap'n Proto serialized bytes + """ + global _cached_writer_fields + + dat = log.Event.new_message(valid=valid, logMonoTime=int(time.monotonic() * 1e9)) + can_data = dat.init(msgtype, len(can_msgs)) + + # Cache schema fields on first call + if _cached_writer_fields is None and len(can_msgs) > 0: + _cached_writer_fields = _get_writer_fields(can_data[0].schema) + + if _cached_writer_fields is not None: + addr_f, dat_f, src_f = _cached_writer_fields + for i, msg in enumerate(can_msgs): + f = can_data[i] + f._set_by_field(addr_f, msg[0]) + f._set_by_field(dat_f, msg[1]) + f._set_by_field(src_f, msg[2]) + + return dat.to_bytes() + + +def can_capnp_to_list(strings, msgtype='can'): + """Convert Cap'n Proto serialized bytes to list of CAN messages. + + Args: + strings: Tuple/list of serialized Cap'n Proto bytes + msgtype: 'can' or 'sendcan' + + Returns: + List of tuples [(nanos, [(address, data, src), ...]), ...] + """ + global _cached_reader_fields + result = [] + + for s in strings: + with log.Event.from_bytes(s, traversal_limit_in_words=NO_TRAVERSAL_LIMIT) as event: + frames = getattr(event, msgtype) + + # Cache schema fields on first frame for faster access + if _cached_reader_fields is None and len(frames) > 0: + _cached_reader_fields = _get_reader_fields(frames[0].schema) + + if _cached_reader_fields is not None: + addr_f, dat_f, src_f = _cached_reader_fields + frame_list = [(f._get_by_field(addr_f), f._get_by_field(dat_f), f._get_by_field(src_f)) for f in frames] + else: + frame_list = [] + + result.append((event.logMonoTime, frame_list)) + return result diff --git a/selfdrive/pandad/pandad_api_impl.pyx b/selfdrive/pandad/pandad_api_impl.pyx deleted file mode 100644 index aaecb8a594..0000000000 --- a/selfdrive/pandad/pandad_api_impl.pyx +++ /dev/null @@ -1,56 +0,0 @@ -# distutils: language = c++ -# cython: language_level=3 -from cython.operator cimport dereference as deref, preincrement as preinc -from libcpp.vector cimport vector -from libcpp.string cimport string -from libcpp cimport bool -from libc.stdint cimport uint8_t, uint32_t, uint64_t - -cdef extern from "selfdrive/pandad/can_types.h": - cdef struct CanFrame: - long src - uint32_t address - vector[uint8_t] dat - - cdef struct CanData: - uint64_t nanos - vector[CanFrame] frames - -cdef extern from "can_list_to_can_capnp.cc": - void can_list_to_can_capnp_cpp(const vector[CanFrame] &can_list, string &out, bool sendcan, bool valid) nogil - void can_capnp_to_can_list_cpp(const vector[string] &strings, vector[CanData] &can_data, bool sendcan) - -def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): - cdef CanFrame *f - cdef vector[CanFrame] can_list - cdef uint32_t cpp_can_msgs_len = len(can_msgs) - - with nogil: - can_list.reserve(cpp_can_msgs_len) - - for can_msg in can_msgs: - f = &(can_list.emplace_back()) - f.address = can_msg[0] - f.dat = can_msg[1] - f.src = can_msg[2] - - cdef string out - cdef bool is_sendcan = (msgtype == 'sendcan') - cdef bool is_valid = valid - with nogil: - can_list_to_can_capnp_cpp(can_list, out, is_sendcan, is_valid) - return out - -def can_capnp_to_list(strings, msgtype='can'): - cdef vector[CanData] data - can_capnp_to_can_list_cpp(strings, data, msgtype == 'sendcan') - - result = [] - cdef CanData *d - cdef vector[CanData].iterator it = data.begin() - while it != data.end(): - d = &deref(it) - frames = [(f.address, (&f.dat[0])[:f.dat.size()], f.src) for f in d.frames] - result.append((d.nanos, frames)) - preinc(it) - return result From 71a418d166d00d86226c02453a70c57776f46009 Mon Sep 17 00:00:00 2001 From: commaci-public <60409688+commaci-public@users.noreply.github.com> Date: Mon, 26 Jan 2026 09:14:57 -0800 Subject: [PATCH 13/46] [bot] Update Python packages (#37028) Update Python packages Co-authored-by: Vehicle Researcher --- docs/CARS.md | 3 +- opendbc_repo | 2 +- panda | 2 +- tinygrad_repo | 2 +- uv.lock | 262 +++++++++++++++++++++++++------------------------- 5 files changed, 136 insertions(+), 135 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 08c06b2303..b349679395 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,7 +4,7 @@ A supported vehicle is one that just works when you install a comma device. All supported cars provide a better experience than any stock system. Supported vehicles reference the US market unless otherwise specified. -# 326 Supported Cars +# 327 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Hardware Needed
 |Video|Setup Video| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:|:---:| @@ -14,6 +14,7 @@ A supported vehicle is one that just works when you install a comma device. All |Acura|RDX 2016-18|AcuraWatch Plus or Advance Package|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Acura|RDX 2019-21|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Acura|TLX 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| +|Acura|TLX 2025|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch C connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,14](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 VW J533 connector
- 1 comma four
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
Buy Here
||| |Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,14](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 VW J533 connector
- 1 comma four
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
Buy Here
||| |Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,14](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 VW J533 connector
- 1 comma four
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
Buy Here
||| diff --git a/opendbc_repo b/opendbc_repo index 1908668b05..d424d1f247 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 1908668b05691564ea5fc80bc11b784a9dee0714 +Subproject commit d424d1f247384b68923b8093875e1a370ef8221d diff --git a/panda b/panda index 3dd38b76b4..81615ad9d5 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 3dd38b76b48903efb4705f55752e9719ba2f5564 +Subproject commit 81615ad9d53aef5583e064f340e9cdeb23d4119c diff --git a/tinygrad_repo b/tinygrad_repo index 7cb7abeeb0..774a454bb5 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit 7cb7abeeb02c681a463f252179354db4bb5e3809 +Subproject commit 774a454bb5e6d0fe3756a8add9302c0a3d592bd9 diff --git a/uv.lock b/uv.lock index 674b18b7ea..b221995b85 100644 --- a/uv.lock +++ b/uv.lock @@ -378,37 +378,37 @@ wheels = [ [[package]] name = "coverage" -version = "7.13.1" +version = "7.13.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/23/f9/e92df5e07f3fc8d4c7f9a0f146ef75446bf870351cd37b788cf5897f8079/coverage-7.13.1.tar.gz", hash = "sha256:b7593fe7eb5feaa3fbb461ac79aac9f9fc0387a5ca8080b0c6fe2ca27b091afd", size = 825862, upload-time = "2025-12-28T15:42:56.969Z" } +sdist = { url = "https://files.pythonhosted.org/packages/ad/49/349848445b0e53660e258acbcc9b0d014895b6739237920886672240f84b/coverage-7.13.2.tar.gz", hash = "sha256:044c6951ec37146b72a50cc81ef02217d27d4c3640efd2640311393cbbf143d3", size = 826523, upload-time = "2026-01-25T13:00:04.889Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b4/9b/77baf488516e9ced25fc215a6f75d803493fc3f6a1a1227ac35697910c2a/coverage-7.13.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:1a55d509a1dc5a5b708b5dad3b5334e07a16ad4c2185e27b40e4dba796ab7f88", size = 218755, upload-time = "2025-12-28T15:40:30.812Z" }, - { url = "https://files.pythonhosted.org/packages/d7/cd/7ab01154e6eb79ee2fab76bf4d89e94c6648116557307ee4ebbb85e5c1bf/coverage-7.13.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:4d010d080c4888371033baab27e47c9df7d6fb28d0b7b7adf85a4a49be9298b3", size = 219257, upload-time = "2025-12-28T15:40:32.333Z" }, - { url = "https://files.pythonhosted.org/packages/01/d5/b11ef7863ffbbdb509da0023fad1e9eda1c0eaea61a6d2ea5b17d4ac706e/coverage-7.13.1-cp311-cp311-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:d938b4a840fb1523b9dfbbb454f652967f18e197569c32266d4d13f37244c3d9", size = 249657, upload-time = "2025-12-28T15:40:34.1Z" }, - { url = "https://files.pythonhosted.org/packages/f7/7c/347280982982383621d29b8c544cf497ae07ac41e44b1ca4903024131f55/coverage-7.13.1-cp311-cp311-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:bf100a3288f9bb7f919b87eb84f87101e197535b9bd0e2c2b5b3179633324fee", size = 251581, upload-time = "2025-12-28T15:40:36.131Z" }, - { url = "https://files.pythonhosted.org/packages/82/f6/ebcfed11036ade4c0d75fa4453a6282bdd225bc073862766eec184a4c643/coverage-7.13.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ef6688db9bf91ba111ae734ba6ef1a063304a881749726e0d3575f5c10a9facf", size = 253691, upload-time = "2025-12-28T15:40:37.626Z" }, - { url = "https://files.pythonhosted.org/packages/02/92/af8f5582787f5d1a8b130b2dcba785fa5e9a7a8e121a0bb2220a6fdbdb8a/coverage-7.13.1-cp311-cp311-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:0b609fc9cdbd1f02e51f67f51e5aee60a841ef58a68d00d5ee2c0faf357481a3", size = 249799, upload-time = "2025-12-28T15:40:39.47Z" }, - { url = "https://files.pythonhosted.org/packages/24/aa/0e39a2a3b16eebf7f193863323edbff38b6daba711abaaf807d4290cf61a/coverage-7.13.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:c43257717611ff5e9a1d79dce8e47566235ebda63328718d9b65dd640bc832ef", size = 251389, upload-time = "2025-12-28T15:40:40.954Z" }, - { url = "https://files.pythonhosted.org/packages/73/46/7f0c13111154dc5b978900c0ccee2e2ca239b910890e674a77f1363d483e/coverage-7.13.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:e09fbecc007f7b6afdfb3b07ce5bd9f8494b6856dd4f577d26c66c391b829851", size = 249450, upload-time = "2025-12-28T15:40:42.489Z" }, - { url = "https://files.pythonhosted.org/packages/ac/ca/e80da6769e8b669ec3695598c58eef7ad98b0e26e66333996aee6316db23/coverage-7.13.1-cp311-cp311-musllinux_1_2_riscv64.whl", hash = "sha256:a03a4f3a19a189919c7055098790285cc5c5b0b3976f8d227aea39dbf9f8bfdb", size = 249170, upload-time = "2025-12-28T15:40:44.279Z" }, - { url = "https://files.pythonhosted.org/packages/af/18/9e29baabdec1a8644157f572541079b4658199cfd372a578f84228e860de/coverage-7.13.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:3820778ea1387c2b6a818caec01c63adc5b3750211af6447e8dcfb9b6f08dbba", size = 250081, upload-time = "2025-12-28T15:40:45.748Z" }, - { url = "https://files.pythonhosted.org/packages/00/f8/c3021625a71c3b2f516464d322e41636aea381018319050a8114105872ee/coverage-7.13.1-cp311-cp311-win32.whl", hash = "sha256:ff10896fa55167371960c5908150b434b71c876dfab97b69478f22c8b445ea19", size = 221281, upload-time = "2025-12-28T15:40:47.232Z" }, - { url = "https://files.pythonhosted.org/packages/27/56/c216625f453df6e0559ed666d246fcbaaa93f3aa99eaa5080cea1229aa3d/coverage-7.13.1-cp311-cp311-win_amd64.whl", hash = "sha256:a998cc0aeeea4c6d5622a3754da5a493055d2d95186bad877b0a34ea6e6dbe0a", size = 222215, upload-time = "2025-12-28T15:40:49.19Z" }, - { url = "https://files.pythonhosted.org/packages/5c/9a/be342e76f6e531cae6406dc46af0d350586f24d9b67fdfa6daee02df71af/coverage-7.13.1-cp311-cp311-win_arm64.whl", hash = "sha256:fea07c1a39a22614acb762e3fbbb4011f65eedafcb2948feeef641ac78b4ee5c", size = 220886, upload-time = "2025-12-28T15:40:51.067Z" }, - { url = "https://files.pythonhosted.org/packages/ce/8a/87af46cccdfa78f53db747b09f5f9a21d5fc38d796834adac09b30a8ce74/coverage-7.13.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:6f34591000f06e62085b1865c9bc5f7858df748834662a51edadfd2c3bfe0dd3", size = 218927, upload-time = "2025-12-28T15:40:52.814Z" }, - { url = "https://files.pythonhosted.org/packages/82/a8/6e22fdc67242a4a5a153f9438d05944553121c8f4ba70cb072af4c41362e/coverage-7.13.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:b67e47c5595b9224599016e333f5ec25392597a89d5744658f837d204e16c63e", size = 219288, upload-time = "2025-12-28T15:40:54.262Z" }, - { url = "https://files.pythonhosted.org/packages/d0/0a/853a76e03b0f7c4375e2ca025df45c918beb367f3e20a0a8e91967f6e96c/coverage-7.13.1-cp312-cp312-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:3e7b8bd70c48ffb28461ebe092c2345536fb18bbbf19d287c8913699735f505c", size = 250786, upload-time = "2025-12-28T15:40:56.059Z" }, - { url = "https://files.pythonhosted.org/packages/ea/b4/694159c15c52b9f7ec7adf49d50e5f8ee71d3e9ef38adb4445d13dd56c20/coverage-7.13.1-cp312-cp312-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:c223d078112e90dc0e5c4e35b98b9584164bea9fbbd221c0b21c5241f6d51b62", size = 253543, upload-time = "2025-12-28T15:40:57.585Z" }, - { url = "https://files.pythonhosted.org/packages/96/b2/7f1f0437a5c855f87e17cf5d0dc35920b6440ff2b58b1ba9788c059c26c8/coverage-7.13.1-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:794f7c05af0763b1bbd1b9e6eff0e52ad068be3b12cd96c87de037b01390c968", size = 254635, upload-time = "2025-12-28T15:40:59.443Z" }, - { url = "https://files.pythonhosted.org/packages/e9/d1/73c3fdb8d7d3bddd9473c9c6a2e0682f09fc3dfbcb9c3f36412a7368bcab/coverage-7.13.1-cp312-cp312-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:0642eae483cc8c2902e4af7298bf886d605e80f26382124cddc3967c2a3df09e", size = 251202, upload-time = "2025-12-28T15:41:01.328Z" }, - { url = "https://files.pythonhosted.org/packages/66/3c/f0edf75dcc152f145d5598329e864bbbe04ab78660fe3e8e395f9fff010f/coverage-7.13.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:9f5e772ed5fef25b3de9f2008fe67b92d46831bd2bc5bdc5dd6bfd06b83b316f", size = 252566, upload-time = "2025-12-28T15:41:03.319Z" }, - { url = "https://files.pythonhosted.org/packages/17/b3/e64206d3c5f7dcbceafd14941345a754d3dbc78a823a6ed526e23b9cdaab/coverage-7.13.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:45980ea19277dc0a579e432aef6a504fe098ef3a9032ead15e446eb0f1191aee", size = 250711, upload-time = "2025-12-28T15:41:06.411Z" }, - { url = "https://files.pythonhosted.org/packages/dc/ad/28a3eb970a8ef5b479ee7f0c484a19c34e277479a5b70269dc652b730733/coverage-7.13.1-cp312-cp312-musllinux_1_2_riscv64.whl", hash = "sha256:e4f18eca6028ffa62adbd185a8f1e1dd242f2e68164dba5c2b74a5204850b4cf", size = 250278, upload-time = "2025-12-28T15:41:08.285Z" }, - { url = "https://files.pythonhosted.org/packages/54/e3/c8f0f1a93133e3e1291ca76cbb63565bd4b5c5df63b141f539d747fff348/coverage-7.13.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:f8dca5590fec7a89ed6826fce625595279e586ead52e9e958d3237821fbc750c", size = 252154, upload-time = "2025-12-28T15:41:09.969Z" }, - { url = "https://files.pythonhosted.org/packages/d0/bf/9939c5d6859c380e405b19e736321f1c7d402728792f4c752ad1adcce005/coverage-7.13.1-cp312-cp312-win32.whl", hash = "sha256:ff86d4e85188bba72cfb876df3e11fa243439882c55957184af44a35bd5880b7", size = 221487, upload-time = "2025-12-28T15:41:11.468Z" }, - { url = "https://files.pythonhosted.org/packages/fa/dc/7282856a407c621c2aad74021680a01b23010bb8ebf427cf5eacda2e876f/coverage-7.13.1-cp312-cp312-win_amd64.whl", hash = "sha256:16cc1da46c04fb0fb128b4dc430b78fa2aba8a6c0c9f8eb391fd5103409a6ac6", size = 222299, upload-time = "2025-12-28T15:41:13.386Z" }, - { url = "https://files.pythonhosted.org/packages/10/79/176a11203412c350b3e9578620013af35bcdb79b651eb976f4a4b32044fa/coverage-7.13.1-cp312-cp312-win_arm64.whl", hash = "sha256:8d9bc218650022a768f3775dd7fdac1886437325d8d295d923ebcfef4892ad5c", size = 220941, upload-time = "2025-12-28T15:41:14.975Z" }, - { url = "https://files.pythonhosted.org/packages/cc/48/d9f421cb8da5afaa1a64570d9989e00fb7955e6acddc5a12979f7666ef60/coverage-7.13.1-py3-none-any.whl", hash = "sha256:2016745cb3ba554469d02819d78958b571792bb68e31302610e898f80dd3a573", size = 210722, upload-time = "2025-12-28T15:42:54.901Z" }, + { url = "https://files.pythonhosted.org/packages/6c/01/abca50583a8975bb6e1c59eff67ed8e48bb127c07dad5c28d9e96ccc09ec/coverage-7.13.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:060ebf6f2c51aff5ba38e1f43a2095e087389b1c69d559fde6049a4b0001320e", size = 218971, upload-time = "2026-01-25T12:57:36.953Z" }, + { url = "https://files.pythonhosted.org/packages/eb/0e/b6489f344d99cd1e5b4d5e1be52dfd3f8a3dc5112aa6c33948da8cabad4e/coverage-7.13.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c1ea8ca9db5e7469cd364552985e15911548ea5b69c48a17291f0cac70484b2e", size = 219473, upload-time = "2026-01-25T12:57:38.934Z" }, + { url = "https://files.pythonhosted.org/packages/17/11/db2f414915a8e4ec53f60b17956c27f21fb68fcf20f8a455ce7c2ccec638/coverage-7.13.2-cp311-cp311-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:b780090d15fd58f07cf2011943e25a5f0c1c894384b13a216b6c86c8a8a7c508", size = 249896, upload-time = "2026-01-25T12:57:40.365Z" }, + { url = "https://files.pythonhosted.org/packages/80/06/0823fe93913663c017e508e8810c998c8ebd3ec2a5a85d2c3754297bdede/coverage-7.13.2-cp311-cp311-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:88a800258d83acb803c38175b4495d293656d5fac48659c953c18e5f539a274b", size = 251810, upload-time = "2026-01-25T12:57:42.045Z" }, + { url = "https://files.pythonhosted.org/packages/61/dc/b151c3cc41b28cdf7f0166c5fa1271cbc305a8ec0124cce4b04f74791a18/coverage-7.13.2-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:6326e18e9a553e674d948536a04a80d850a5eeefe2aae2e6d7cf05d54046c01b", size = 253920, upload-time = "2026-01-25T12:57:44.026Z" }, + { url = "https://files.pythonhosted.org/packages/2d/35/e83de0556e54a4729a2b94ea816f74ce08732e81945024adee46851c2264/coverage-7.13.2-cp311-cp311-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:59562de3f797979e1ff07c587e2ac36ba60ca59d16c211eceaa579c266c5022f", size = 250025, upload-time = "2026-01-25T12:57:45.624Z" }, + { url = "https://files.pythonhosted.org/packages/39/67/af2eb9c3926ce3ea0d58a0d2516fcbdacf7a9fc9559fe63076beaf3f2596/coverage-7.13.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:27ba1ed6f66b0e2d61bfa78874dffd4f8c3a12f8e2b5410e515ab345ba7bc9c3", size = 251612, upload-time = "2026-01-25T12:57:47.713Z" }, + { url = "https://files.pythonhosted.org/packages/26/62/5be2e25f3d6c711d23b71296f8b44c978d4c8b4e5b26871abfc164297502/coverage-7.13.2-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:8be48da4d47cc68754ce643ea50b3234557cbefe47c2f120495e7bd0a2756f2b", size = 249670, upload-time = "2026-01-25T12:57:49.378Z" }, + { url = "https://files.pythonhosted.org/packages/b3/51/400d1b09a8344199f9b6a6fc1868005d766b7ea95e7882e494fa862ca69c/coverage-7.13.2-cp311-cp311-musllinux_1_2_riscv64.whl", hash = "sha256:2a47a4223d3361b91176aedd9d4e05844ca67d7188456227b6bf5e436630c9a1", size = 249395, upload-time = "2026-01-25T12:57:50.86Z" }, + { url = "https://files.pythonhosted.org/packages/e0/36/f02234bc6e5230e2f0a63fd125d0a2093c73ef20fdf681c7af62a140e4e7/coverage-7.13.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:c6f141b468740197d6bd38f2b26ade124363228cc3f9858bd9924ab059e00059", size = 250298, upload-time = "2026-01-25T12:57:52.287Z" }, + { url = "https://files.pythonhosted.org/packages/b0/06/713110d3dd3151b93611c9cbfc65c15b4156b44f927fced49ac0b20b32a4/coverage-7.13.2-cp311-cp311-win32.whl", hash = "sha256:89567798404af067604246e01a49ef907d112edf2b75ef814b1364d5ce267031", size = 221485, upload-time = "2026-01-25T12:57:53.876Z" }, + { url = "https://files.pythonhosted.org/packages/16/0c/3ae6255fa1ebcb7dec19c9a59e85ef5f34566d1265c70af5b2fc981da834/coverage-7.13.2-cp311-cp311-win_amd64.whl", hash = "sha256:21dd57941804ae2ac7e921771a5e21bbf9aabec317a041d164853ad0a96ce31e", size = 222421, upload-time = "2026-01-25T12:57:55.433Z" }, + { url = "https://files.pythonhosted.org/packages/b5/37/fabc3179af4d61d89ea47bd04333fec735cd5e8b59baad44fed9fc4170d7/coverage-7.13.2-cp311-cp311-win_arm64.whl", hash = "sha256:10758e0586c134a0bafa28f2d37dd2cdb5e4a90de25c0fc0c77dabbad46eca28", size = 221088, upload-time = "2026-01-25T12:57:57.41Z" }, + { url = "https://files.pythonhosted.org/packages/46/39/e92a35f7800222d3f7b2cbb7bbc3b65672ae8d501cb31801b2d2bd7acdf1/coverage-7.13.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:f106b2af193f965d0d3234f3f83fc35278c7fb935dfbde56ae2da3dd2c03b84d", size = 219142, upload-time = "2026-01-25T12:58:00.448Z" }, + { url = "https://files.pythonhosted.org/packages/45/7a/8bf9e9309c4c996e65c52a7c5a112707ecdd9fbaf49e10b5a705a402bbb4/coverage-7.13.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:78f45d21dc4d5d6bd29323f0320089ef7eae16e4bef712dff79d184fa7330af3", size = 219503, upload-time = "2026-01-25T12:58:02.451Z" }, + { url = "https://files.pythonhosted.org/packages/87/93/17661e06b7b37580923f3f12406ac91d78aeed293fb6da0b69cc7957582f/coverage-7.13.2-cp312-cp312-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:fae91dfecd816444c74531a9c3d6ded17a504767e97aa674d44f638107265b99", size = 251006, upload-time = "2026-01-25T12:58:04.059Z" }, + { url = "https://files.pythonhosted.org/packages/12/f0/f9e59fb8c310171497f379e25db060abef9fa605e09d63157eebec102676/coverage-7.13.2-cp312-cp312-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:264657171406c114787b441484de620e03d8f7202f113d62fcd3d9688baa3e6f", size = 253750, upload-time = "2026-01-25T12:58:05.574Z" }, + { url = "https://files.pythonhosted.org/packages/e5/b1/1935e31add2232663cf7edd8269548b122a7d100047ff93475dbaaae673e/coverage-7.13.2-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ae47d8dcd3ded0155afbb59c62bd8ab07ea0fd4902e1c40567439e6db9dcaf2f", size = 254862, upload-time = "2026-01-25T12:58:07.647Z" }, + { url = "https://files.pythonhosted.org/packages/af/59/b5e97071ec13df5f45da2b3391b6cdbec78ba20757bc92580a5b3d5fa53c/coverage-7.13.2-cp312-cp312-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:8a0b33e9fd838220b007ce8f299114d406c1e8edb21336af4c97a26ecfd185aa", size = 251420, upload-time = "2026-01-25T12:58:09.309Z" }, + { url = "https://files.pythonhosted.org/packages/3f/75/9495932f87469d013dc515fb0ce1aac5fa97766f38f6b1a1deb1ee7b7f3a/coverage-7.13.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:b3becbea7f3ce9a2d4d430f223ec15888e4deb31395840a79e916368d6004cce", size = 252786, upload-time = "2026-01-25T12:58:10.909Z" }, + { url = "https://files.pythonhosted.org/packages/6a/59/af550721f0eb62f46f7b8cb7e6f1860592189267b1c411a4e3a057caacee/coverage-7.13.2-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:f819c727a6e6eeb8711e4ce63d78c620f69630a2e9d53bc95ca5379f57b6ba94", size = 250928, upload-time = "2026-01-25T12:58:12.449Z" }, + { url = "https://files.pythonhosted.org/packages/9b/b1/21b4445709aae500be4ab43bbcfb4e53dc0811c3396dcb11bf9f23fd0226/coverage-7.13.2-cp312-cp312-musllinux_1_2_riscv64.whl", hash = "sha256:4f7b71757a3ab19f7ba286e04c181004c1d61be921795ee8ba6970fd0ec91da5", size = 250496, upload-time = "2026-01-25T12:58:14.047Z" }, + { url = "https://files.pythonhosted.org/packages/ba/b1/0f5d89dfe0392990e4f3980adbde3eb34885bc1effb2dc369e0bf385e389/coverage-7.13.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:b7fc50d2afd2e6b4f6f2f403b70103d280a8e0cb35320cbbe6debcda02a1030b", size = 252373, upload-time = "2026-01-25T12:58:15.976Z" }, + { url = "https://files.pythonhosted.org/packages/01/c9/0cf1a6a57a9968cc049a6b896693faa523c638a5314b1fc374eb2b2ac904/coverage-7.13.2-cp312-cp312-win32.whl", hash = "sha256:292250282cf9bcf206b543d7608bda17ca6fc151f4cbae949fc7e115112fbd41", size = 221696, upload-time = "2026-01-25T12:58:17.517Z" }, + { url = "https://files.pythonhosted.org/packages/4d/05/d7540bf983f09d32803911afed135524570f8c47bb394bf6206c1dc3a786/coverage-7.13.2-cp312-cp312-win_amd64.whl", hash = "sha256:eeea10169fac01549a7921d27a3e517194ae254b542102267bef7a93ed38c40e", size = 222504, upload-time = "2026-01-25T12:58:19.115Z" }, + { url = "https://files.pythonhosted.org/packages/15/8b/1a9f037a736ced0a12aacf6330cdaad5008081142a7070bc58b0f7930cbc/coverage-7.13.2-cp312-cp312-win_arm64.whl", hash = "sha256:2a5b567f0b635b592c917f96b9a9cb3dbd4c320d03f4bf94e9084e494f2e8894", size = 221120, upload-time = "2026-01-25T12:58:21.334Z" }, + { url = "https://files.pythonhosted.org/packages/d2/db/d291e30fdf7ea617a335531e72294e0c723356d7fdde8fba00610a76bda9/coverage-7.13.2-py3-none-any.whl", hash = "sha256:40ce1ea1e25125556d8e76bd0b61500839a07944cc287ac21d5626f3e620cad5", size = 210943, upload-time = "2026-01-25T13:00:02.388Z" }, ] [[package]] @@ -915,11 +915,11 @@ wheels = [ [[package]] name = "markdown" -version = "3.10" +version = "3.10.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/7d/ab/7dd27d9d863b3376fcf23a5a13cb5d024aed1db46f963f1b5735ae43b3be/markdown-3.10.tar.gz", hash = "sha256:37062d4f2aa4b2b6b32aefb80faa300f82cc790cb949a35b8caede34f2b68c0e", size = 364931, upload-time = "2025-11-03T19:51:15.007Z" } +sdist = { url = "https://files.pythonhosted.org/packages/b7/b1/af95bcae8549f1f3fd70faacb29075826a0d689a27f232e8cee315efa053/markdown-3.10.1.tar.gz", hash = "sha256:1c19c10bd5c14ac948c53d0d762a04e2fa35a6d58a6b7b1e6bfcbe6fefc0001a", size = 365402, upload-time = "2026-01-21T18:09:28.206Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/70/81/54e3ce63502cd085a0c556652a4e1b919c45a446bd1e5300e10c44c8c521/markdown-3.10-py3-none-any.whl", hash = "sha256:b5b99d6951e2e4948d939255596523444c0e677c669700b1d17aa4a8a464cb7c", size = 107678, upload-time = "2025-11-03T19:51:13.887Z" }, + { url = "https://files.pythonhosted.org/packages/59/1b/6ef961f543593969d25b2afe57a3564200280528caa9bd1082eecdd7b3bc/markdown-3.10.1-py3-none-any.whl", hash = "sha256:867d788939fe33e4b736426f5b9f651ad0c0ae0ecf89df0ca5d1176c70812fe3", size = 107684, upload-time = "2026-01-21T18:09:27.203Z" }, ] [[package]] @@ -1158,47 +1158,47 @@ wheels = [ [[package]] name = "multidict" -version = "6.7.0" +version = "6.7.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/80/1e/5492c365f222f907de1039b91f922b93fa4f764c713ee858d235495d8f50/multidict-6.7.0.tar.gz", hash = "sha256:c6e99d9a65ca282e578dfea819cfa9c0a62b2499d8677392e09feaf305e9e6f5", size = 101834, upload-time = "2025-10-06T14:52:30.657Z" } +sdist = { url = "https://files.pythonhosted.org/packages/1a/c2/c2d94cbe6ac1753f3fc980da97b3d930efe1da3af3c9f5125354436c073d/multidict-6.7.1.tar.gz", hash = "sha256:ec6652a1bee61c53a3e5776b6049172c53b6aaba34f18c9ad04f82712bac623d", size = 102010, upload-time = "2026-01-26T02:46:45.979Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/34/9e/5c727587644d67b2ed479041e4b1c58e30afc011e3d45d25bbe35781217c/multidict-6.7.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4d409aa42a94c0b3fa617708ef5276dfe81012ba6753a0370fcc9d0195d0a1fc", size = 76604, upload-time = "2025-10-06T14:48:54.277Z" }, - { url = "https://files.pythonhosted.org/packages/17/e4/67b5c27bd17c085a5ea8f1ec05b8a3e5cba0ca734bfcad5560fb129e70ca/multidict-6.7.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:14c9e076eede3b54c636f8ce1c9c252b5f057c62131211f0ceeec273810c9721", size = 44715, upload-time = "2025-10-06T14:48:55.445Z" }, - { url = "https://files.pythonhosted.org/packages/4d/e1/866a5d77be6ea435711bef2a4291eed11032679b6b28b56b4776ab06ba3e/multidict-6.7.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:4c09703000a9d0fa3c3404b27041e574cc7f4df4c6563873246d0e11812a94b6", size = 44332, upload-time = "2025-10-06T14:48:56.706Z" }, - { url = "https://files.pythonhosted.org/packages/31/61/0c2d50241ada71ff61a79518db85ada85fdabfcf395d5968dae1cbda04e5/multidict-6.7.0-cp311-cp311-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:a265acbb7bb33a3a2d626afbe756371dce0279e7b17f4f4eda406459c2b5ff1c", size = 245212, upload-time = "2025-10-06T14:48:58.042Z" }, - { url = "https://files.pythonhosted.org/packages/ac/e0/919666a4e4b57fff1b57f279be1c9316e6cdc5de8a8b525d76f6598fefc7/multidict-6.7.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:51cb455de290ae462593e5b1cb1118c5c22ea7f0d3620d9940bf695cea5a4bd7", size = 246671, upload-time = "2025-10-06T14:49:00.004Z" }, - { url = "https://files.pythonhosted.org/packages/a1/cc/d027d9c5a520f3321b65adea289b965e7bcbd2c34402663f482648c716ce/multidict-6.7.0-cp311-cp311-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:db99677b4457c7a5c5a949353e125ba72d62b35f74e26da141530fbb012218a7", size = 225491, upload-time = "2025-10-06T14:49:01.393Z" }, - { url = "https://files.pythonhosted.org/packages/75/c4/bbd633980ce6155a28ff04e6a6492dd3335858394d7bb752d8b108708558/multidict-6.7.0-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:f470f68adc395e0183b92a2f4689264d1ea4b40504a24d9882c27375e6662bb9", size = 257322, upload-time = "2025-10-06T14:49:02.745Z" }, - { url = "https://files.pythonhosted.org/packages/4c/6d/d622322d344f1f053eae47e033b0b3f965af01212de21b10bcf91be991fb/multidict-6.7.0-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:0db4956f82723cc1c270de9c6e799b4c341d327762ec78ef82bb962f79cc07d8", size = 254694, upload-time = "2025-10-06T14:49:04.15Z" }, - { url = "https://files.pythonhosted.org/packages/a8/9f/78f8761c2705d4c6d7516faed63c0ebdac569f6db1bef95e0d5218fdc146/multidict-6.7.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:3e56d780c238f9e1ae66a22d2adf8d16f485381878250db8d496623cd38b22bd", size = 246715, upload-time = "2025-10-06T14:49:05.967Z" }, - { url = "https://files.pythonhosted.org/packages/78/59/950818e04f91b9c2b95aab3d923d9eabd01689d0dcd889563988e9ea0fd8/multidict-6.7.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:9d14baca2ee12c1a64740d4531356ba50b82543017f3ad6de0deb943c5979abb", size = 243189, upload-time = "2025-10-06T14:49:07.37Z" }, - { url = "https://files.pythonhosted.org/packages/7a/3d/77c79e1934cad2ee74991840f8a0110966d9599b3af95964c0cd79bb905b/multidict-6.7.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:295a92a76188917c7f99cda95858c822f9e4aae5824246bba9b6b44004ddd0a6", size = 237845, upload-time = "2025-10-06T14:49:08.759Z" }, - { url = "https://files.pythonhosted.org/packages/63/1b/834ce32a0a97a3b70f86437f685f880136677ac00d8bce0027e9fd9c2db7/multidict-6.7.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:39f1719f57adbb767ef592a50ae5ebb794220d1188f9ca93de471336401c34d2", size = 246374, upload-time = "2025-10-06T14:49:10.574Z" }, - { url = "https://files.pythonhosted.org/packages/23/ef/43d1c3ba205b5dec93dc97f3fba179dfa47910fc73aaaea4f7ceb41cec2a/multidict-6.7.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:0a13fb8e748dfc94749f622de065dd5c1def7e0d2216dba72b1d8069a389c6ff", size = 253345, upload-time = "2025-10-06T14:49:12.331Z" }, - { url = "https://files.pythonhosted.org/packages/6b/03/eaf95bcc2d19ead522001f6a650ef32811aa9e3624ff0ad37c445c7a588c/multidict-6.7.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:e3aa16de190d29a0ea1b48253c57d99a68492c8dd8948638073ab9e74dc9410b", size = 246940, upload-time = "2025-10-06T14:49:13.821Z" }, - { url = "https://files.pythonhosted.org/packages/e8/df/ec8a5fd66ea6cd6f525b1fcbb23511b033c3e9bc42b81384834ffa484a62/multidict-6.7.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:a048ce45dcdaaf1defb76b2e684f997fb5abf74437b6cb7b22ddad934a964e34", size = 242229, upload-time = "2025-10-06T14:49:15.603Z" }, - { url = "https://files.pythonhosted.org/packages/8a/a2/59b405d59fd39ec86d1142630e9049243015a5f5291ba49cadf3c090c541/multidict-6.7.0-cp311-cp311-win32.whl", hash = "sha256:a90af66facec4cebe4181b9e62a68be65e45ac9b52b67de9eec118701856e7ff", size = 41308, upload-time = "2025-10-06T14:49:16.871Z" }, - { url = "https://files.pythonhosted.org/packages/32/0f/13228f26f8b882c34da36efa776c3b7348455ec383bab4a66390e42963ae/multidict-6.7.0-cp311-cp311-win_amd64.whl", hash = "sha256:95b5ffa4349df2887518bb839409bcf22caa72d82beec453216802f475b23c81", size = 46037, upload-time = "2025-10-06T14:49:18.457Z" }, - { url = "https://files.pythonhosted.org/packages/84/1f/68588e31b000535a3207fd3c909ebeec4fb36b52c442107499c18a896a2a/multidict-6.7.0-cp311-cp311-win_arm64.whl", hash = "sha256:329aa225b085b6f004a4955271a7ba9f1087e39dcb7e65f6284a988264a63912", size = 43023, upload-time = "2025-10-06T14:49:19.648Z" }, - { url = "https://files.pythonhosted.org/packages/c2/9e/9f61ac18d9c8b475889f32ccfa91c9f59363480613fc807b6e3023d6f60b/multidict-6.7.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8a3862568a36d26e650a19bb5cbbba14b71789032aebc0423f8cc5f150730184", size = 76877, upload-time = "2025-10-06T14:49:20.884Z" }, - { url = "https://files.pythonhosted.org/packages/38/6f/614f09a04e6184f8824268fce4bc925e9849edfa654ddd59f0b64508c595/multidict-6.7.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:960c60b5849b9b4f9dcc9bea6e3626143c252c74113df2c1540aebce70209b45", size = 45467, upload-time = "2025-10-06T14:49:22.054Z" }, - { url = "https://files.pythonhosted.org/packages/b3/93/c4f67a436dd026f2e780c433277fff72be79152894d9fc36f44569cab1a6/multidict-6.7.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2049be98fb57a31b4ccf870bf377af2504d4ae35646a19037ec271e4c07998aa", size = 43834, upload-time = "2025-10-06T14:49:23.566Z" }, - { url = "https://files.pythonhosted.org/packages/7f/f5/013798161ca665e4a422afbc5e2d9e4070142a9ff8905e482139cd09e4d0/multidict-6.7.0-cp312-cp312-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:0934f3843a1860dd465d38895c17fce1f1cb37295149ab05cd1b9a03afacb2a7", size = 250545, upload-time = "2025-10-06T14:49:24.882Z" }, - { url = "https://files.pythonhosted.org/packages/71/2f/91dbac13e0ba94669ea5119ba267c9a832f0cb65419aca75549fcf09a3dc/multidict-6.7.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:b3e34f3a1b8131ba06f1a73adab24f30934d148afcd5f5de9a73565a4404384e", size = 258305, upload-time = "2025-10-06T14:49:26.778Z" }, - { url = "https://files.pythonhosted.org/packages/ef/b0/754038b26f6e04488b48ac621f779c341338d78503fb45403755af2df477/multidict-6.7.0-cp312-cp312-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:efbb54e98446892590dc2458c19c10344ee9a883a79b5cec4bc34d6656e8d546", size = 242363, upload-time = "2025-10-06T14:49:28.562Z" }, - { url = "https://files.pythonhosted.org/packages/87/15/9da40b9336a7c9fa606c4cf2ed80a649dffeb42b905d4f63a1d7eb17d746/multidict-6.7.0-cp312-cp312-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:a35c5fc61d4f51eb045061e7967cfe3123d622cd500e8868e7c0c592a09fedc4", size = 268375, upload-time = "2025-10-06T14:49:29.96Z" }, - { url = "https://files.pythonhosted.org/packages/82/72/c53fcade0cc94dfaad583105fd92b3a783af2091eddcb41a6d5a52474000/multidict-6.7.0-cp312-cp312-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:29fe6740ebccba4175af1b9b87bf553e9c15cd5868ee967e010efcf94e4fd0f1", size = 269346, upload-time = "2025-10-06T14:49:31.404Z" }, - { url = "https://files.pythonhosted.org/packages/0d/e2/9baffdae21a76f77ef8447f1a05a96ec4bc0a24dae08767abc0a2fe680b8/multidict-6.7.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:123e2a72e20537add2f33a79e605f6191fba2afda4cbb876e35c1a7074298a7d", size = 256107, upload-time = "2025-10-06T14:49:32.974Z" }, - { url = "https://files.pythonhosted.org/packages/3c/06/3f06f611087dc60d65ef775f1fb5aca7c6d61c6db4990e7cda0cef9b1651/multidict-6.7.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:b284e319754366c1aee2267a2036248b24eeb17ecd5dc16022095e747f2f4304", size = 253592, upload-time = "2025-10-06T14:49:34.52Z" }, - { url = "https://files.pythonhosted.org/packages/20/24/54e804ec7945b6023b340c412ce9c3f81e91b3bf5fa5ce65558740141bee/multidict-6.7.0-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:803d685de7be4303b5a657b76e2f6d1240e7e0a8aa2968ad5811fa2285553a12", size = 251024, upload-time = "2025-10-06T14:49:35.956Z" }, - { url = "https://files.pythonhosted.org/packages/14/48/011cba467ea0b17ceb938315d219391d3e421dfd35928e5dbdc3f4ae76ef/multidict-6.7.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:c04a328260dfd5db8c39538f999f02779012268f54614902d0afc775d44e0a62", size = 251484, upload-time = "2025-10-06T14:49:37.631Z" }, - { url = "https://files.pythonhosted.org/packages/0d/2f/919258b43bb35b99fa127435cfb2d91798eb3a943396631ef43e3720dcf4/multidict-6.7.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:8a19cdb57cd3df4cd865849d93ee14920fb97224300c88501f16ecfa2604b4e0", size = 263579, upload-time = "2025-10-06T14:49:39.502Z" }, - { url = "https://files.pythonhosted.org/packages/31/22/a0e884d86b5242b5a74cf08e876bdf299e413016b66e55511f7a804a366e/multidict-6.7.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:9b2fd74c52accced7e75de26023b7dccee62511a600e62311b918ec5c168fc2a", size = 259654, upload-time = "2025-10-06T14:49:41.32Z" }, - { url = "https://files.pythonhosted.org/packages/b2/e5/17e10e1b5c5f5a40f2fcbb45953c9b215f8a4098003915e46a93f5fcaa8f/multidict-6.7.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:3e8bfdd0e487acf992407a140d2589fe598238eaeffa3da8448d63a63cd363f8", size = 251511, upload-time = "2025-10-06T14:49:46.021Z" }, - { url = "https://files.pythonhosted.org/packages/e3/9a/201bb1e17e7af53139597069c375e7b0dcbd47594604f65c2d5359508566/multidict-6.7.0-cp312-cp312-win32.whl", hash = "sha256:dd32a49400a2c3d52088e120ee00c1e3576cbff7e10b98467962c74fdb762ed4", size = 41895, upload-time = "2025-10-06T14:49:48.718Z" }, - { url = "https://files.pythonhosted.org/packages/46/e2/348cd32faad84eaf1d20cce80e2bb0ef8d312c55bca1f7fa9865e7770aaf/multidict-6.7.0-cp312-cp312-win_amd64.whl", hash = "sha256:92abb658ef2d7ef22ac9f8bb88e8b6c3e571671534e029359b6d9e845923eb1b", size = 46073, upload-time = "2025-10-06T14:49:50.28Z" }, - { url = "https://files.pythonhosted.org/packages/25/ec/aad2613c1910dce907480e0c3aa306905830f25df2e54ccc9dea450cb5aa/multidict-6.7.0-cp312-cp312-win_arm64.whl", hash = "sha256:490dab541a6a642ce1a9d61a4781656b346a55c13038f0b1244653828e3a83ec", size = 43226, upload-time = "2025-10-06T14:49:52.304Z" }, - { url = "https://files.pythonhosted.org/packages/b7/da/7d22601b625e241d4f23ef1ebff8acfc60da633c9e7e7922e24d10f592b3/multidict-6.7.0-py3-none-any.whl", hash = "sha256:394fc5c42a333c9ffc3e421a4c85e08580d990e08b99f6bf35b4132114c5dcb3", size = 12317, upload-time = "2025-10-06T14:52:29.272Z" }, + { url = "https://files.pythonhosted.org/packages/ce/f1/a90635c4f88fb913fbf4ce660b83b7445b7a02615bda034b2f8eb38fd597/multidict-6.7.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7ff981b266af91d7b4b3793ca3382e53229088d193a85dfad6f5f4c27fc73e5d", size = 76626, upload-time = "2026-01-26T02:43:26.485Z" }, + { url = "https://files.pythonhosted.org/packages/a6/9b/267e64eaf6fc637a15b35f5de31a566634a2740f97d8d094a69d34f524a4/multidict-6.7.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:844c5bca0b5444adb44a623fb0a1310c2f4cd41f402126bb269cd44c9b3f3e1e", size = 44706, upload-time = "2026-01-26T02:43:27.607Z" }, + { url = "https://files.pythonhosted.org/packages/dd/a4/d45caf2b97b035c57267791ecfaafbd59c68212004b3842830954bb4b02e/multidict-6.7.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f2a0a924d4c2e9afcd7ec64f9de35fcd96915149b2216e1cb2c10a56df483855", size = 44356, upload-time = "2026-01-26T02:43:28.661Z" }, + { url = "https://files.pythonhosted.org/packages/fd/d2/0a36c8473f0cbaeadd5db6c8b72d15bbceeec275807772bfcd059bef487d/multidict-6.7.1-cp311-cp311-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:8be1802715a8e892c784c0197c2ace276ea52702a0ede98b6310c8f255a5afb3", size = 244355, upload-time = "2026-01-26T02:43:31.165Z" }, + { url = "https://files.pythonhosted.org/packages/5d/16/8c65be997fd7dd311b7d39c7b6e71a0cb449bad093761481eccbbe4b42a2/multidict-6.7.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:2e2d2ed645ea29f31c4c7ea1552fcfd7cb7ba656e1eafd4134a6620c9f5fdd9e", size = 246433, upload-time = "2026-01-26T02:43:32.581Z" }, + { url = "https://files.pythonhosted.org/packages/01/fb/4dbd7e848d2799c6a026ec88ad39cf2b8416aa167fcc903baa55ecaa045c/multidict-6.7.1-cp311-cp311-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:95922cee9a778659e91db6497596435777bd25ed116701a4c034f8e46544955a", size = 225376, upload-time = "2026-01-26T02:43:34.417Z" }, + { url = "https://files.pythonhosted.org/packages/b6/8a/4a3a6341eac3830f6053062f8fbc9a9e54407c80755b3f05bc427295c2d0/multidict-6.7.1-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:6b83cabdc375ffaaa15edd97eb7c0c672ad788e2687004990074d7d6c9b140c8", size = 257365, upload-time = "2026-01-26T02:43:35.741Z" }, + { url = "https://files.pythonhosted.org/packages/f7/a2/dd575a69c1aa206e12d27d0770cdf9b92434b48a9ef0cd0d1afdecaa93c4/multidict-6.7.1-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:38fb49540705369bab8484db0689d86c0a33a0a9f2c1b197f506b71b4b6c19b0", size = 254747, upload-time = "2026-01-26T02:43:36.976Z" }, + { url = "https://files.pythonhosted.org/packages/5a/56/21b27c560c13822ed93133f08aa6372c53a8e067f11fbed37b4adcdac922/multidict-6.7.1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:439cbebd499f92e9aa6793016a8acaa161dfa749ae86d20960189f5398a19144", size = 246293, upload-time = "2026-01-26T02:43:38.258Z" }, + { url = "https://files.pythonhosted.org/packages/5a/a4/23466059dc3854763423d0ad6c0f3683a379d97673b1b89ec33826e46728/multidict-6.7.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:6d3bc717b6fe763b8be3f2bee2701d3c8eb1b2a8ae9f60910f1b2860c82b6c49", size = 242962, upload-time = "2026-01-26T02:43:40.034Z" }, + { url = "https://files.pythonhosted.org/packages/1f/67/51dd754a3524d685958001e8fa20a0f5f90a6a856e0a9dcabff69be3dbb7/multidict-6.7.1-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:619e5a1ac57986dbfec9f0b301d865dddf763696435e2962f6d9cf2fdff2bb71", size = 237360, upload-time = "2026-01-26T02:43:41.752Z" }, + { url = "https://files.pythonhosted.org/packages/64/3f/036dfc8c174934d4b55d86ff4f978e558b0e585cef70cfc1ad01adc6bf18/multidict-6.7.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:0b38ebffd9be37c1170d33bc0f36f4f262e0a09bc1aac1c34c7aa51a7293f0b3", size = 245940, upload-time = "2026-01-26T02:43:43.042Z" }, + { url = "https://files.pythonhosted.org/packages/3d/20/6214d3c105928ebc353a1c644a6ef1408bc5794fcb4f170bb524a3c16311/multidict-6.7.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:10ae39c9cfe6adedcdb764f5e8411d4a92b055e35573a2eaa88d3323289ef93c", size = 253502, upload-time = "2026-01-26T02:43:44.371Z" }, + { url = "https://files.pythonhosted.org/packages/b1/e2/c653bc4ae1be70a0f836b82172d643fcf1dade042ba2676ab08ec08bff0f/multidict-6.7.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:25167cc263257660290fba06b9318d2026e3c910be240a146e1f66dd114af2b0", size = 247065, upload-time = "2026-01-26T02:43:45.745Z" }, + { url = "https://files.pythonhosted.org/packages/c8/11/a854b4154cd3bd8b1fd375e8a8ca9d73be37610c361543d56f764109509b/multidict-6.7.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:128441d052254f42989ef98b7b6a6ecb1e6f708aa962c7984235316db59f50fa", size = 241870, upload-time = "2026-01-26T02:43:47.054Z" }, + { url = "https://files.pythonhosted.org/packages/13/bf/9676c0392309b5fdae322333d22a829715b570edb9baa8016a517b55b558/multidict-6.7.1-cp311-cp311-win32.whl", hash = "sha256:d62b7f64ffde3b99d06b707a280db04fb3855b55f5a06df387236051d0668f4a", size = 41302, upload-time = "2026-01-26T02:43:48.753Z" }, + { url = "https://files.pythonhosted.org/packages/c9/68/f16a3a8ba6f7b6dc92a1f19669c0810bd2c43fc5a02da13b1cbf8e253845/multidict-6.7.1-cp311-cp311-win_amd64.whl", hash = "sha256:bdbf9f3b332abd0cdb306e7c2113818ab1e922dc84b8f8fd06ec89ed2a19ab8b", size = 45981, upload-time = "2026-01-26T02:43:49.921Z" }, + { url = "https://files.pythonhosted.org/packages/ac/ad/9dd5305253fa00cd3c7555dbef69d5bf4133debc53b87ab8d6a44d411665/multidict-6.7.1-cp311-cp311-win_arm64.whl", hash = "sha256:b8c990b037d2fff2f4e33d3f21b9b531c5745b33a49a7d6dbe7a177266af44f6", size = 43159, upload-time = "2026-01-26T02:43:51.635Z" }, + { url = "https://files.pythonhosted.org/packages/8d/9c/f20e0e2cf80e4b2e4b1c365bf5fe104ee633c751a724246262db8f1a0b13/multidict-6.7.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a90f75c956e32891a4eda3639ce6dd86e87105271f43d43442a3aedf3cddf172", size = 76893, upload-time = "2026-01-26T02:43:52.754Z" }, + { url = "https://files.pythonhosted.org/packages/fe/cf/18ef143a81610136d3da8193da9d80bfe1cb548a1e2d1c775f26b23d024a/multidict-6.7.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:3fccb473e87eaa1382689053e4a4618e7ba7b9b9b8d6adf2027ee474597128cd", size = 45456, upload-time = "2026-01-26T02:43:53.893Z" }, + { url = "https://files.pythonhosted.org/packages/a9/65/1caac9d4cd32e8433908683446eebc953e82d22b03d10d41a5f0fefe991b/multidict-6.7.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:b0fa96985700739c4c7853a43c0b3e169360d6855780021bfc6d0f1ce7c123e7", size = 43872, upload-time = "2026-01-26T02:43:55.041Z" }, + { url = "https://files.pythonhosted.org/packages/cf/3b/d6bd75dc4f3ff7c73766e04e705b00ed6dbbaccf670d9e05a12b006f5a21/multidict-6.7.1-cp312-cp312-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:cb2a55f408c3043e42b40cc8eecd575afa27b7e0b956dfb190de0f8499a57a53", size = 251018, upload-time = "2026-01-26T02:43:56.198Z" }, + { url = "https://files.pythonhosted.org/packages/fd/80/c959c5933adedb9ac15152e4067c702a808ea183a8b64cf8f31af8ad3155/multidict-6.7.1-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:eb0ce7b2a32d09892b3dd6cc44877a0d02a33241fafca5f25c8b6b62374f8b75", size = 258883, upload-time = "2026-01-26T02:43:57.499Z" }, + { url = "https://files.pythonhosted.org/packages/86/85/7ed40adafea3d4f1c8b916e3b5cc3a8e07dfcdcb9cd72800f4ed3ca1b387/multidict-6.7.1-cp312-cp312-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:c3a32d23520ee37bf327d1e1a656fec76a2edd5c038bf43eddfa0572ec49c60b", size = 242413, upload-time = "2026-01-26T02:43:58.755Z" }, + { url = "https://files.pythonhosted.org/packages/d2/57/b8565ff533e48595503c785f8361ff9a4fde4d67de25c207cd0ba3befd03/multidict-6.7.1-cp312-cp312-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:9c90fed18bffc0189ba814749fdcc102b536e83a9f738a9003e569acd540a733", size = 268404, upload-time = "2026-01-26T02:44:00.216Z" }, + { url = "https://files.pythonhosted.org/packages/e0/50/9810c5c29350f7258180dfdcb2e52783a0632862eb334c4896ac717cebcb/multidict-6.7.1-cp312-cp312-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:da62917e6076f512daccfbbde27f46fed1c98fee202f0559adec8ee0de67f71a", size = 269456, upload-time = "2026-01-26T02:44:02.202Z" }, + { url = "https://files.pythonhosted.org/packages/f3/8d/5e5be3ced1d12966fefb5c4ea3b2a5b480afcea36406559442c6e31d4a48/multidict-6.7.1-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:bfde23ef6ed9db7eaee6c37dcec08524cb43903c60b285b172b6c094711b3961", size = 256322, upload-time = "2026-01-26T02:44:03.56Z" }, + { url = "https://files.pythonhosted.org/packages/31/6e/d8a26d81ac166a5592782d208dd90dfdc0a7a218adaa52b45a672b46c122/multidict-6.7.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:3758692429e4e32f1ba0df23219cd0b4fc0a52f476726fff9337d1a57676a582", size = 253955, upload-time = "2026-01-26T02:44:04.845Z" }, + { url = "https://files.pythonhosted.org/packages/59/4c/7c672c8aad41534ba619bcd4ade7a0dc87ed6b8b5c06149b85d3dd03f0cd/multidict-6.7.1-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:398c1478926eca669f2fd6a5856b6de9c0acf23a2cb59a14c0ba5844fa38077e", size = 251254, upload-time = "2026-01-26T02:44:06.133Z" }, + { url = "https://files.pythonhosted.org/packages/7b/bd/84c24de512cbafbdbc39439f74e967f19570ce7924e3007174a29c348916/multidict-6.7.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:c102791b1c4f3ab36ce4101154549105a53dc828f016356b3e3bcae2e3a039d3", size = 252059, upload-time = "2026-01-26T02:44:07.518Z" }, + { url = "https://files.pythonhosted.org/packages/fa/ba/f5449385510825b73d01c2d4087bf6d2fccc20a2d42ac34df93191d3dd03/multidict-6.7.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:a088b62bd733e2ad12c50dad01b7d0166c30287c166e137433d3b410add807a6", size = 263588, upload-time = "2026-01-26T02:44:09.382Z" }, + { url = "https://files.pythonhosted.org/packages/d7/11/afc7c677f68f75c84a69fe37184f0f82fce13ce4b92f49f3db280b7e92b3/multidict-6.7.1-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:3d51ff4785d58d3f6c91bdbffcb5e1f7ddfda557727043aa20d20ec4f65e324a", size = 259642, upload-time = "2026-01-26T02:44:10.73Z" }, + { url = "https://files.pythonhosted.org/packages/2b/17/ebb9644da78c4ab36403739e0e6e0e30ebb135b9caf3440825001a0bddcb/multidict-6.7.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:fc5907494fccf3e7d3f94f95c91d6336b092b5fc83811720fae5e2765890dfba", size = 251377, upload-time = "2026-01-26T02:44:12.042Z" }, + { url = "https://files.pythonhosted.org/packages/ca/a4/840f5b97339e27846c46307f2530a2805d9d537d8b8bd416af031cad7fa0/multidict-6.7.1-cp312-cp312-win32.whl", hash = "sha256:28ca5ce2fd9716631133d0e9a9b9a745ad7f60bac2bccafb56aa380fc0b6c511", size = 41887, upload-time = "2026-01-26T02:44:14.245Z" }, + { url = "https://files.pythonhosted.org/packages/80/31/0b2517913687895f5904325c2069d6a3b78f66cc641a86a2baf75a05dcbb/multidict-6.7.1-cp312-cp312-win_amd64.whl", hash = "sha256:fcee94dfbd638784645b066074b338bc9cc155d4b4bffa4adce1615c5a426c19", size = 46053, upload-time = "2026-01-26T02:44:15.371Z" }, + { url = "https://files.pythonhosted.org/packages/0c/5b/aba28e4ee4006ae4c7df8d327d31025d760ffa992ea23812a601d226e682/multidict-6.7.1-cp312-cp312-win_arm64.whl", hash = "sha256:ba0a9fb644d0c1a2194cf7ffb043bd852cea63a57f66fbd33959f7dae18517bf", size = 43307, upload-time = "2026-01-26T02:44:16.852Z" }, + { url = "https://files.pythonhosted.org/packages/81/08/7036c080d7117f28a4af526d794aab6a84463126db031b007717c1a6676e/multidict-6.7.1-py3-none-any.whl", hash = "sha256:55d97cc6dae627efa6a6e548885712d4864b81110ac76fa4e534c03819fa4a56", size = 12319, upload-time = "2026-01-26T02:46:44.004Z" }, ] [[package]] @@ -1461,11 +1461,11 @@ provides-extras = ["docs", "testing", "dev", "tools"] [[package]] name = "packaging" -version = "25.0" +version = "26.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/a1/d4/1fc4078c65507b51b96ca8f8c3ba19e6a61c8253c72794544580a7b6c24d/packaging-25.0.tar.gz", hash = "sha256:d443872c98d677bf60f6a1f2f8c1cb748e8fe762d2bf9d3148b5599295b0fc4f", size = 165727, upload-time = "2025-04-19T11:48:59.673Z" } +sdist = { url = "https://files.pythonhosted.org/packages/65/ee/299d360cdc32edc7d2cf530f3accf79c4fca01e96ffc950d8a52213bd8e4/packaging-26.0.tar.gz", hash = "sha256:00243ae351a257117b6a241061796684b084ed1c516a08c48a3f7e147a9d80b4", size = 143416, upload-time = "2026-01-21T20:50:39.064Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/20/12/38679034af332785aac8774540895e234f4d07f7545804097de4b666afd8/packaging-25.0-py3-none-any.whl", hash = "sha256:29572ef2b1f17581046b3a2227d5c611fb25ec70ca1ba8554b24b0e69331a484", size = 66469, upload-time = "2025-04-19T11:48:57.875Z" }, + { url = "https://files.pythonhosted.org/packages/b7/b9/c538f279a4e237a006a2c98387d081e9eb060d203d8ed34467cc0f0b9b53/packaging-26.0-py3-none-any.whl", hash = "sha256:b36f1fef9334a5588b4166f8bcd26a14e521f2b55e6b9de3aaa80d3ff7a37529", size = 74366, upload-time = "2026-01-21T20:50:37.788Z" }, ] [[package]] @@ -1735,11 +1735,11 @@ wheels = [ [[package]] name = "pycparser" -version = "2.23" +version = "3.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/fe/cf/d2d3b9f5699fb1e4615c8e32ff220203e43b248e1dfcc6736ad9057731ca/pycparser-2.23.tar.gz", hash = "sha256:78816d4f24add8f10a06d6f05b4d424ad9e96cfebf68a4ddc99c65c0720d00c2", size = 173734, upload-time = "2025-09-09T13:23:47.91Z" } +sdist = { url = "https://files.pythonhosted.org/packages/1b/7d/92392ff7815c21062bea51aa7b87d45576f649f16458d78b7cf94b9ab2e6/pycparser-3.0.tar.gz", hash = "sha256:600f49d217304a5902ac3c37e1281c9fe94e4d0489de643a9504c5cdfdfc6b29", size = 103492, upload-time = "2026-01-21T14:26:51.89Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a0/e3/59cd50310fc9b59512193629e1984c1f95e5c8ae6e5d8c69532ccc65a7fe/pycparser-2.23-py3-none-any.whl", hash = "sha256:e5c6e8d3fbad53479cab09ac03729e0a9faf2bee3db8208a550daf5af81a5934", size = 118140, upload-time = "2025-09-09T13:23:46.651Z" }, + { url = "https://files.pythonhosted.org/packages/0c/c3/44f3fbbfa403ea2a7c779186dc20772604442dde72947e7d01069cbe98e3/pycparser-3.0-py3-none-any.whl", hash = "sha256:b727414169a36b7d524c1c3e31839a521725078d7b2ff038656844266160a992", size = 48172, upload-time = "2026-01-21T14:26:50.693Z" }, ] [[package]] @@ -4300,11 +4300,11 @@ wheels = [ [[package]] name = "pyparsing" -version = "3.3.1" +version = "3.3.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/33/c1/1d9de9aeaa1b89b0186e5fe23294ff6517fce1bc69149185577cd31016b2/pyparsing-3.3.1.tar.gz", hash = "sha256:47fad0f17ac1e2cad3de3b458570fbc9b03560aa029ed5e16ee5554da9a2251c", size = 1550512, upload-time = "2025-12-23T03:14:04.391Z" } +sdist = { url = "https://files.pythonhosted.org/packages/f3/91/9c6ee907786a473bf81c5f53cf703ba0957b23ab84c264080fb5a450416f/pyparsing-3.3.2.tar.gz", hash = "sha256:c777f4d763f140633dcb6d8a3eda953bf7a214dc4eff598413c070bcdc117cbc", size = 6851574, upload-time = "2026-01-21T03:57:59.36Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/8b/40/2614036cdd416452f5bf98ec037f38a1afb17f327cb8e6b652d4729e0af8/pyparsing-3.3.1-py3-none-any.whl", hash = "sha256:023b5e7e5520ad96642e2c6db4cb683d3970bd640cdf7115049a6e9c3682df82", size = 121793, upload-time = "2025-12-23T03:14:02.103Z" }, + { url = "https://files.pythonhosted.org/packages/10/bd/c038d7cc38edc1aa5bf91ab8068b63d4308c66c4c8bb3cbba7dfbc049f9c/pyparsing-3.3.2-py3-none-any.whl", hash = "sha256:850ba148bd908d7e2411587e247a1e4f0327839c40e2e5e6d05a007ecc69911d", size = 122781, upload-time = "2026-01-21T03:57:55.912Z" }, ] [[package]] @@ -4702,28 +4702,28 @@ wheels = [ [[package]] name = "ruff" -version = "0.14.13" +version = "0.14.14" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/50/0a/1914efb7903174b381ee2ffeebb4253e729de57f114e63595114c8ca451f/ruff-0.14.13.tar.gz", hash = "sha256:83cd6c0763190784b99650a20fec7633c59f6ebe41c5cc9d45ee42749563ad47", size = 6059504, upload-time = "2026-01-15T20:15:16.918Z" } +sdist = { url = "https://files.pythonhosted.org/packages/2e/06/f71e3a86b2df0dfa2d2f72195941cd09b44f87711cb7fa5193732cb9a5fc/ruff-0.14.14.tar.gz", hash = "sha256:2d0f819c9a90205f3a867dbbd0be083bee9912e170fd7d9704cc8ae45824896b", size = 4515732, upload-time = "2026-01-22T22:30:17.527Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/c3/ae/0deefbc65ca74b0ab1fd3917f94dc3b398233346a74b8bbb0a916a1a6bf6/ruff-0.14.13-py3-none-linux_armv6l.whl", hash = "sha256:76f62c62cd37c276cb03a275b198c7c15bd1d60c989f944db08a8c1c2dbec18b", size = 13062418, upload-time = "2026-01-15T20:14:50.779Z" }, - { url = "https://files.pythonhosted.org/packages/47/df/5916604faa530a97a3c154c62a81cb6b735c0cb05d1e26d5ad0f0c8ac48a/ruff-0.14.13-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:914a8023ece0528d5cc33f5a684f5f38199bbb566a04815c2c211d8f40b5d0ed", size = 13442344, upload-time = "2026-01-15T20:15:07.94Z" }, - { url = "https://files.pythonhosted.org/packages/4c/f3/e0e694dd69163c3a1671e102aa574a50357536f18a33375050334d5cd517/ruff-0.14.13-py3-none-macosx_11_0_arm64.whl", hash = "sha256:d24899478c35ebfa730597a4a775d430ad0d5631b8647a3ab368c29b7e7bd063", size = 12354720, upload-time = "2026-01-15T20:15:09.854Z" }, - { url = "https://files.pythonhosted.org/packages/c3/e8/67f5fcbbaee25e8fc3b56cc33e9892eca7ffe09f773c8e5907757a7e3bdb/ruff-0.14.13-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9aaf3870f14d925bbaf18b8a2347ee0ae7d95a2e490e4d4aea6813ed15ebc80e", size = 12774493, upload-time = "2026-01-15T20:15:20.908Z" }, - { url = "https://files.pythonhosted.org/packages/6b/ce/d2e9cb510870b52a9565d885c0d7668cc050e30fa2c8ac3fb1fda15c083d/ruff-0.14.13-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:ac5b7f63dd3b27cc811850f5ffd8fff845b00ad70e60b043aabf8d6ecc304e09", size = 12815174, upload-time = "2026-01-15T20:15:05.74Z" }, - { url = "https://files.pythonhosted.org/packages/88/00/c38e5da58beebcf4fa32d0ddd993b63dfacefd02ab7922614231330845bf/ruff-0.14.13-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:78d2b1097750d90ba82ce4ba676e85230a0ed694178ca5e61aa9b459970b3eb9", size = 13680909, upload-time = "2026-01-15T20:15:14.537Z" }, - { url = "https://files.pythonhosted.org/packages/61/61/cd37c9dd5bd0a3099ba79b2a5899ad417d8f3b04038810b0501a80814fd7/ruff-0.14.13-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:7d0bf87705acbbcb8d4c24b2d77fbb73d40210a95c3903b443cd9e30824a5032", size = 15144215, upload-time = "2026-01-15T20:15:22.886Z" }, - { url = "https://files.pythonhosted.org/packages/56/8a/85502d7edbf98c2df7b8876f316c0157359165e16cdf98507c65c8d07d3d/ruff-0.14.13-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a3eb5da8e2c9e9f13431032fdcbe7681de9ceda5835efee3269417c13f1fed5c", size = 14706067, upload-time = "2026-01-15T20:14:48.271Z" }, - { url = "https://files.pythonhosted.org/packages/7e/2f/de0df127feb2ee8c1e54354dc1179b4a23798f0866019528c938ba439aca/ruff-0.14.13-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:642442b42957093811cd8d2140dfadd19c7417030a7a68cf8d51fcdd5f217427", size = 14133916, upload-time = "2026-01-15T20:14:57.357Z" }, - { url = "https://files.pythonhosted.org/packages/0d/77/9b99686bb9fe07a757c82f6f95e555c7a47801a9305576a9c67e0a31d280/ruff-0.14.13-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4acdf009f32b46f6e8864af19cbf6841eaaed8638e65c8dac845aea0d703c841", size = 13859207, upload-time = "2026-01-15T20:14:55.111Z" }, - { url = "https://files.pythonhosted.org/packages/7d/46/2bdcb34a87a179a4d23022d818c1c236cb40e477faf0d7c9afb6813e5876/ruff-0.14.13-py3-none-manylinux_2_31_riscv64.whl", hash = "sha256:591a7f68860ea4e003917d19b5c4f5ac39ff558f162dc753a2c5de897fd5502c", size = 14043686, upload-time = "2026-01-15T20:14:52.841Z" }, - { url = "https://files.pythonhosted.org/packages/1a/a9/5c6a4f56a0512c691cf143371bcf60505ed0f0860f24a85da8bd123b2bf1/ruff-0.14.13-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:774c77e841cc6e046fc3e91623ce0903d1cd07e3a36b1a9fe79b81dab3de506b", size = 12663837, upload-time = "2026-01-15T20:15:18.921Z" }, - { url = "https://files.pythonhosted.org/packages/fe/bb/b920016ece7651fa7fcd335d9d199306665486694d4361547ccb19394c44/ruff-0.14.13-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:61f4e40077a1248436772bb6512db5fc4457fe4c49e7a94ea7c5088655dd21ae", size = 12805867, upload-time = "2026-01-15T20:14:59.272Z" }, - { url = "https://files.pythonhosted.org/packages/7d/b3/0bd909851e5696cd21e32a8fc25727e5f58f1934b3596975503e6e85415c/ruff-0.14.13-py3-none-musllinux_1_2_i686.whl", hash = "sha256:6d02f1428357fae9e98ac7aa94b7e966fd24151088510d32cf6f902d6c09235e", size = 13208528, upload-time = "2026-01-15T20:15:03.732Z" }, - { url = "https://files.pythonhosted.org/packages/3b/3b/e2d94cb613f6bbd5155a75cbe072813756363eba46a3f2177a1fcd0cd670/ruff-0.14.13-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:e399341472ce15237be0c0ae5fbceca4b04cd9bebab1a2b2c979e015455d8f0c", size = 13929242, upload-time = "2026-01-15T20:15:11.918Z" }, - { url = "https://files.pythonhosted.org/packages/6a/c5/abd840d4132fd51a12f594934af5eba1d5d27298a6f5b5d6c3be45301caf/ruff-0.14.13-py3-none-win32.whl", hash = "sha256:ef720f529aec113968b45dfdb838ac8934e519711da53a0456038a0efecbd680", size = 12919024, upload-time = "2026-01-15T20:14:43.647Z" }, - { url = "https://files.pythonhosted.org/packages/c2/55/6384b0b8ce731b6e2ade2b5449bf07c0e4c31e8a2e68ea65b3bafadcecc5/ruff-0.14.13-py3-none-win_amd64.whl", hash = "sha256:6070bd026e409734b9257e03e3ef18c6e1a216f0435c6751d7a8ec69cb59abef", size = 14097887, upload-time = "2026-01-15T20:15:01.48Z" }, - { url = "https://files.pythonhosted.org/packages/4d/e1/7348090988095e4e39560cfc2f7555b1b2a7357deba19167b600fdf5215d/ruff-0.14.13-py3-none-win_arm64.whl", hash = "sha256:7ab819e14f1ad9fe39f246cfcc435880ef7a9390d81a2b6ac7e01039083dd247", size = 13080224, upload-time = "2026-01-15T20:14:45.853Z" }, + { url = "https://files.pythonhosted.org/packages/d2/89/20a12e97bc6b9f9f68343952da08a8099c57237aef953a56b82711d55edd/ruff-0.14.14-py3-none-linux_armv6l.whl", hash = "sha256:7cfe36b56e8489dee8fbc777c61959f60ec0f1f11817e8f2415f429552846aed", size = 10467650, upload-time = "2026-01-22T22:30:08.578Z" }, + { url = "https://files.pythonhosted.org/packages/a3/b1/c5de3fd2d5a831fcae21beda5e3589c0ba67eec8202e992388e4b17a6040/ruff-0.14.14-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:6006a0082336e7920b9573ef8a7f52eec837add1265cc74e04ea8a4368cd704c", size = 10883245, upload-time = "2026-01-22T22:30:04.155Z" }, + { url = "https://files.pythonhosted.org/packages/b8/7c/3c1db59a10e7490f8f6f8559d1db8636cbb13dccebf18686f4e3c9d7c772/ruff-0.14.14-py3-none-macosx_11_0_arm64.whl", hash = "sha256:026c1d25996818f0bf498636686199d9bd0d9d6341c9c2c3b62e2a0198b758de", size = 10231273, upload-time = "2026-01-22T22:30:34.642Z" }, + { url = "https://files.pythonhosted.org/packages/a1/6e/5e0e0d9674be0f8581d1f5e0f0a04761203affce3232c1a1189d0e3b4dad/ruff-0.14.14-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f666445819d31210b71e0a6d1c01e24447a20b85458eea25a25fe8142210ae0e", size = 10585753, upload-time = "2026-01-22T22:30:31.781Z" }, + { url = "https://files.pythonhosted.org/packages/23/09/754ab09f46ff1884d422dc26d59ba18b4e5d355be147721bb2518aa2a014/ruff-0.14.14-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:3c0f18b922c6d2ff9a5e6c3ee16259adc513ca775bcf82c67ebab7cbd9da5bc8", size = 10286052, upload-time = "2026-01-22T22:30:24.827Z" }, + { url = "https://files.pythonhosted.org/packages/c8/cc/e71f88dd2a12afb5f50733851729d6b571a7c3a35bfdb16c3035132675a0/ruff-0.14.14-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1629e67489c2dea43e8658c3dba659edbfd87361624b4040d1df04c9740ae906", size = 11043637, upload-time = "2026-01-22T22:30:13.239Z" }, + { url = "https://files.pythonhosted.org/packages/67/b2/397245026352494497dac935d7f00f1468c03a23a0c5db6ad8fc49ca3fb2/ruff-0.14.14-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:27493a2131ea0f899057d49d303e4292b2cae2bb57253c1ed1f256fbcd1da480", size = 12194761, upload-time = "2026-01-22T22:30:22.542Z" }, + { url = "https://files.pythonhosted.org/packages/5b/06/06ef271459f778323112c51b7587ce85230785cd64e91772034ddb88f200/ruff-0.14.14-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:01ff589aab3f5b539e35db38425da31a57521efd1e4ad1ae08fc34dbe30bd7df", size = 12005701, upload-time = "2026-01-22T22:30:20.499Z" }, + { url = "https://files.pythonhosted.org/packages/41/d6/99364514541cf811ccc5ac44362f88df66373e9fec1b9d1c4cc830593fe7/ruff-0.14.14-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1cc12d74eef0f29f51775f5b755913eb523546b88e2d733e1d701fe65144e89b", size = 11282455, upload-time = "2026-01-22T22:29:59.679Z" }, + { url = "https://files.pythonhosted.org/packages/ca/71/37daa46f89475f8582b7762ecd2722492df26421714a33e72ccc9a84d7a5/ruff-0.14.14-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bb8481604b7a9e75eff53772496201690ce2687067e038b3cc31aaf16aa0b974", size = 11215882, upload-time = "2026-01-22T22:29:57.032Z" }, + { url = "https://files.pythonhosted.org/packages/2c/10/a31f86169ec91c0705e618443ee74ede0bdd94da0a57b28e72db68b2dbac/ruff-0.14.14-py3-none-manylinux_2_31_riscv64.whl", hash = "sha256:14649acb1cf7b5d2d283ebd2f58d56b75836ed8c6f329664fa91cdea19e76e66", size = 11180549, upload-time = "2026-01-22T22:30:27.175Z" }, + { url = "https://files.pythonhosted.org/packages/fd/1e/c723f20536b5163adf79bdd10c5f093414293cdf567eed9bdb7b83940f3f/ruff-0.14.14-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:e8058d2145566510790eab4e2fad186002e288dec5e0d343a92fe7b0bc1b3e13", size = 10543416, upload-time = "2026-01-22T22:30:01.964Z" }, + { url = "https://files.pythonhosted.org/packages/3e/34/8a84cea7e42c2d94ba5bde1d7a4fae164d6318f13f933d92da6d7c2041ff/ruff-0.14.14-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:e651e977a79e4c758eb807f0481d673a67ffe53cfa92209781dfa3a996cf8412", size = 10285491, upload-time = "2026-01-22T22:30:29.51Z" }, + { url = "https://files.pythonhosted.org/packages/55/ef/b7c5ea0be82518906c978e365e56a77f8de7678c8bb6651ccfbdc178c29f/ruff-0.14.14-py3-none-musllinux_1_2_i686.whl", hash = "sha256:cc8b22da8d9d6fdd844a68ae937e2a0adf9b16514e9a97cc60355e2d4b219fc3", size = 10733525, upload-time = "2026-01-22T22:30:06.499Z" }, + { url = "https://files.pythonhosted.org/packages/6a/5b/aaf1dfbcc53a2811f6cc0a1759de24e4b03e02ba8762daabd9b6bd8c59e3/ruff-0.14.14-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:16bc890fb4cc9781bb05beb5ab4cd51be9e7cb376bf1dd3580512b24eb3fda2b", size = 11315626, upload-time = "2026-01-22T22:30:36.848Z" }, + { url = "https://files.pythonhosted.org/packages/2c/aa/9f89c719c467dfaf8ad799b9bae0df494513fb21d31a6059cb5870e57e74/ruff-0.14.14-py3-none-win32.whl", hash = "sha256:b530c191970b143375b6a68e6f743800b2b786bbcf03a7965b06c4bf04568167", size = 10502442, upload-time = "2026-01-22T22:30:38.93Z" }, + { url = "https://files.pythonhosted.org/packages/87/44/90fa543014c45560cae1fffc63ea059fb3575ee6e1cb654562197e5d16fb/ruff-0.14.14-py3-none-win_amd64.whl", hash = "sha256:3dde1435e6b6fe5b66506c1dff67a421d0b7f6488d466f651c07f4cab3bf20fd", size = 11630486, upload-time = "2026-01-22T22:30:10.852Z" }, + { url = "https://files.pythonhosted.org/packages/9e/6a/40fee331a52339926a92e17ae748827270b288a35ef4a15c9c8f2ec54715/ruff-0.14.14-py3-none-win_arm64.whl", hash = "sha256:56e6981a98b13a32236a72a8da421d7839221fa308b223b9283312312e5ac76c", size = 10920448, upload-time = "2026-01-22T22:30:15.417Z" }, ] [[package]] @@ -4737,15 +4737,15 @@ wheels = [ [[package]] name = "sentry-sdk" -version = "2.49.0" +version = "2.50.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "certifi" }, { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/02/94/23ac26616a883f492428d9ee9ad6eee391612125326b784dbfc30e1e7bab/sentry_sdk-2.49.0.tar.gz", hash = "sha256:c1878599cde410d481c04ef50ee3aedd4f600e4d0d253f4763041e468b332c30", size = 387228, upload-time = "2026-01-08T09:56:25.642Z" } +sdist = { url = "https://files.pythonhosted.org/packages/15/8a/3c4f53d32c21012e9870913544e56bfa9e931aede080779a0f177513f534/sentry_sdk-2.50.0.tar.gz", hash = "sha256:873437a989ee1b8b25579847bae8384515bf18cfed231b06c591b735c1781fe3", size = 401233, upload-time = "2026-01-20T12:53:16.244Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/88/43/1c586f9f413765201234541857cb82fda076f4b0f7bad4a0ec248da39cf3/sentry_sdk-2.49.0-py2.py3-none-any.whl", hash = "sha256:6ea78499133874445a20fe9c826c9e960070abeb7ae0cdf930314ab16bb97aa0", size = 415693, upload-time = "2026-01-08T09:56:21.872Z" }, + { url = "https://files.pythonhosted.org/packages/4e/5b/cbc2bb9569f03c8e15d928357e7e6179e5cfab45544a3bbac8aec4caf9be/sentry_sdk-2.50.0-py2.py3-none-any.whl", hash = "sha256:0ef0ed7168657ceb5a0be081f4102d92042a125462d1d1a29277992e344e749e", size = 424961, upload-time = "2026-01-20T12:53:14.826Z" }, ] [[package]] @@ -4781,11 +4781,11 @@ wheels = [ [[package]] name = "setuptools" -version = "80.9.0" +version = "80.10.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/18/5d/3bf57dcd21979b887f014ea83c24ae194cfcd12b9e0fda66b957c69d1fca/setuptools-80.9.0.tar.gz", hash = "sha256:f36b47402ecde768dbfafc46e8e4207b4360c654f1f3bb84475f0a28628fb19c", size = 1319958, upload-time = "2025-05-27T00:56:51.443Z" } +sdist = { url = "https://files.pythonhosted.org/packages/76/95/faf61eb8363f26aa7e1d762267a8d602a1b26d4f3a1e758e92cb3cb8b054/setuptools-80.10.2.tar.gz", hash = "sha256:8b0e9d10c784bf7d262c4e5ec5d4ec94127ce206e8738f29a437945fbc219b70", size = 1200343, upload-time = "2026-01-25T22:38:17.252Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/a3/dc/17031897dae0efacfea57dfd3a82fdd2a2aeb58e0ff71b77b87e44edc772/setuptools-80.9.0-py3-none-any.whl", hash = "sha256:062d34222ad13e0cc312a4c02d73f059e86a4acbfbdea8f8f76b28c99f306922", size = 1201486, upload-time = "2025-05-27T00:56:49.664Z" }, + { url = "https://files.pythonhosted.org/packages/94/b8/f1f62a5e3c0ad2ff1d189590bfa4c46b4f3b6e49cef6f26c6ee4e575394d/setuptools-80.10.2-py3-none-any.whl", hash = "sha256:95b30ddfb717250edb492926c92b5221f7ef3fbcc2b07579bcd4a27da21d0173", size = 1064234, upload-time = "2026-01-25T22:38:15.216Z" }, ] [[package]] @@ -4864,17 +4864,18 @@ wheels = [ [[package]] name = "sounddevice" -version = "0.5.3" +version = "0.5.5" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cffi" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/4e/4f/28e734898b870db15b6474453f19813d3c81b91c806d9e6f867bd6e4dd03/sounddevice-0.5.3.tar.gz", hash = "sha256:cbac2b60198fbab84533697e7c4904cc895ec69d5fb3973556c9eb74a4629b2c", size = 53465, upload-time = "2025-10-19T13:23:57.922Z" } +sdist = { url = "https://files.pythonhosted.org/packages/2a/f9/2592608737553638fca98e21e54bfec40bf577bb98a61b2770c912aab25e/sounddevice-0.5.5.tar.gz", hash = "sha256:22487b65198cb5bf2208755105b524f78ad173e5ab6b445bdab1c989f6698df3", size = 143191, upload-time = "2026-01-23T18:36:43.529Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/73/e7/9020e9f0f3df00432728f4c4044387468a743e3d9a4f91123d77be10010e/sounddevice-0.5.3-py3-none-any.whl", hash = "sha256:ea7738baa0a9f9fef7390f649e41c9f2c8ada776180e56c2ffd217133c92a806", size = 32670, upload-time = "2025-10-19T13:23:51.779Z" }, - { url = "https://files.pythonhosted.org/packages/2f/39/714118f8413e0e353436914f2b976665161f1be2b6483ac15a8f61484c14/sounddevice-0.5.3-py3-none-macosx_10_6_x86_64.macosx_10_6_universal2.whl", hash = "sha256:278dc4451fff70934a176df048b77d80d7ce1623a6ec9db8b34b806f3112f9c2", size = 108306, upload-time = "2025-10-19T13:23:53.277Z" }, - { url = "https://files.pythonhosted.org/packages/f5/74/52186e3e5c833d00273f7949a9383adff93692c6e02406bf359cb4d3e921/sounddevice-0.5.3-py3-none-win32.whl", hash = "sha256:845d6927bcf14e84be5292a61ab3359cf8e6b9145819ec6f3ac2619ff089a69c", size = 312882, upload-time = "2025-10-19T13:23:54.829Z" }, - { url = "https://files.pythonhosted.org/packages/66/c7/16123d054aef6d445176c9122bfbe73c11087589b2413cab22aff5a7839a/sounddevice-0.5.3-py3-none-win_amd64.whl", hash = "sha256:f55ad20082efc2bdec06928e974fbcae07bc6c405409ae1334cefe7d377eb687", size = 364025, upload-time = "2025-10-19T13:23:56.362Z" }, + { url = "https://files.pythonhosted.org/packages/1e/0a/478e441fd049002cf308520c0d62dd8333e7c6cc8d997f0dda07b9fbcc46/sounddevice-0.5.5-py3-none-any.whl", hash = "sha256:30ff99f6c107f49d25ad16a45cacd8d91c25a1bcdd3e81a206b921a3a6405b1f", size = 32807, upload-time = "2026-01-23T18:36:35.649Z" }, + { url = "https://files.pythonhosted.org/packages/56/f9/c037c35f6d0b6bc3bc7bfb314f1d6f1f9a341328ef47cd63fc4f850a7b27/sounddevice-0.5.5-py3-none-macosx_10_6_x86_64.macosx_10_6_universal2.whl", hash = "sha256:05eb9fd6c54c38d67741441c19164c0dae8ce80453af2d8c4ad2e7823d15b722", size = 108557, upload-time = "2026-01-23T18:36:37.41Z" }, + { url = "https://files.pythonhosted.org/packages/88/a1/d19dd9889cd4bce2e233c4fac007cd8daaf5b9fe6e6a5d432cf17be0b807/sounddevice-0.5.5-py3-none-win32.whl", hash = "sha256:1234cc9b4c9df97b6cbe748146ae0ec64dd7d6e44739e8e42eaa5b595313a103", size = 317765, upload-time = "2026-01-23T18:36:39.047Z" }, + { url = "https://files.pythonhosted.org/packages/c3/0e/002ed7c4c1c2ab69031f78989d3b789fee3a7fba9e586eb2b81688bf4961/sounddevice-0.5.5-py3-none-win_amd64.whl", hash = "sha256:cfc6b2c49fb7f555591c78cb8ecf48d6a637fd5b6e1db5fec6ed9365d64b3519", size = 365324, upload-time = "2026-01-23T18:36:40.496Z" }, + { url = "https://files.pythonhosted.org/packages/4e/39/a61d4b83a7746b70d23d9173be688c0c6bfc7173772344b7442c2c155497/sounddevice-0.5.5-py3-none-win_arm64.whl", hash = "sha256:3861901ddd8230d2e0e8ae62ac320cdd4c688d81df89da036dcb812f757bb3e6", size = 317115, upload-time = "2026-01-23T18:36:42.235Z" }, ] [[package]] @@ -4918,27 +4919,26 @@ wheels = [ [[package]] name = "ty" -version = "0.0.12" +version = "0.0.13" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/b5/78/ba1a4ad403c748fbba8be63b7e774a90e80b67192f6443d624c64fe4aaab/ty-0.0.12.tar.gz", hash = "sha256:cd01810e106c3b652a01b8f784dd21741de9fdc47bd595d02c122a7d5cefeee7", size = 4981303, upload-time = "2026-01-14T22:30:48.537Z" } +sdist = { url = "https://files.pythonhosted.org/packages/5a/dc/b607f00916f5a7c52860b84a66dc17bc6988e8445e96b1d6e175a3837397/ty-0.0.13.tar.gz", hash = "sha256:7a1d135a400ca076407ea30012d1f75419634160ed3b9cad96607bf2956b23b3", size = 4999183, upload-time = "2026-01-21T13:21:16.133Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7d/8f/c21314d074dda5fb13d3300fa6733fd0d8ff23ea83a721818740665b6314/ty-0.0.12-py3-none-linux_armv6l.whl", hash = "sha256:eb9da1e2c68bd754e090eab39ed65edf95168d36cbeb43ff2bd9f86b4edd56d1", size = 9614164, upload-time = "2026-01-14T22:30:44.016Z" }, - { url = "https://files.pythonhosted.org/packages/09/28/f8a4d944d13519d70c486e8f96d6fa95647ac2aa94432e97d5cfec1f42f6/ty-0.0.12-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:c181f42aa19b0ed7f1b0c2d559980b1f1d77cc09419f51c8321c7ddf67758853", size = 9542337, upload-time = "2026-01-14T22:30:05.687Z" }, - { url = "https://files.pythonhosted.org/packages/e1/9c/f576e360441de7a8201daa6dc4ebc362853bc5305e059cceeb02ebdd9a48/ty-0.0.12-py3-none-macosx_11_0_arm64.whl", hash = "sha256:1f829e1eecd39c3e1b032149db7ae6a3284f72fc36b42436e65243a9ed1173db", size = 8909582, upload-time = "2026-01-14T22:30:46.089Z" }, - { url = "https://files.pythonhosted.org/packages/d6/13/0898e494032a5d8af3060733d12929e3e7716db6c75eac63fa125730a3e7/ty-0.0.12-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f45162e7826e1789cf3374627883cdeb0d56b82473a0771923e4572928e90be3", size = 9384932, upload-time = "2026-01-14T22:30:13.769Z" }, - { url = "https://files.pythonhosted.org/packages/e4/1a/b35b6c697008a11d4cedfd34d9672db2f0a0621ec80ece109e13fca4dfef/ty-0.0.12-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:d11fec40b269bec01e751b2337d1c7ffa959a2c2090a950d7e21c2792442cccd", size = 9453140, upload-time = "2026-01-14T22:30:11.131Z" }, - { url = "https://files.pythonhosted.org/packages/dd/1e/71c9edbc79a3c88a0711324458f29c7dbf6c23452c6e760dc25725483064/ty-0.0.12-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:09d99e37e761a4d2651ad9d5a610d11235fbcbf35dc6d4bc04abf54e7cf894f1", size = 9960680, upload-time = "2026-01-14T22:30:33.621Z" }, - { url = "https://files.pythonhosted.org/packages/0e/75/39375129f62dd22f6ad5a99cd2a42fd27d8b91b235ce2db86875cdad397d/ty-0.0.12-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:d9ca0cdb17bd37397da7b16a7cd23423fc65c3f9691e453ad46c723d121225a1", size = 10904518, upload-time = "2026-01-14T22:30:08.464Z" }, - { url = "https://files.pythonhosted.org/packages/32/5e/26c6d88fafa11a9d31ca9f4d12989f57782ec61e7291d4802d685b5be118/ty-0.0.12-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fcf2757b905e7eddb7e456140066335b18eb68b634a9f72d6f54a427ab042c64", size = 10525001, upload-time = "2026-01-14T22:30:16.454Z" }, - { url = "https://files.pythonhosted.org/packages/c2/a5/2f0b91894af13187110f9ad7ee926d86e4e6efa755c9c88a820ed7f84c85/ty-0.0.12-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:00cf34c1ebe1147efeda3021a1064baa222c18cdac114b7b050bbe42deb4ca80", size = 10307103, upload-time = "2026-01-14T22:30:41.221Z" }, - { url = "https://files.pythonhosted.org/packages/4b/77/13d0410827e4bc713ebb7fdaf6b3590b37dcb1b82e0a81717b65548f2442/ty-0.0.12-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2bb3a655bd869352e9a22938d707631ac9fbca1016242b1f6d132d78f347c851", size = 10072737, upload-time = "2026-01-14T22:30:51.783Z" }, - { url = "https://files.pythonhosted.org/packages/e1/dd/fc36d8bac806c74cf04b4ca735bca14d19967ca84d88f31e121767880df1/ty-0.0.12-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:4658e282c7cb82be304052f8f64f9925f23c3c4f90eeeb32663c74c4b095d7ba", size = 9368726, upload-time = "2026-01-14T22:30:18.683Z" }, - { url = "https://files.pythonhosted.org/packages/54/70/9e8e461647550f83e2fe54bc632ccbdc17a4909644783cdbdd17f7296059/ty-0.0.12-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:c167d838eaaa06e03bb66a517f75296b643d950fbd93c1d1686a187e5a8dbd1f", size = 9454704, upload-time = "2026-01-14T22:30:22.759Z" }, - { url = "https://files.pythonhosted.org/packages/04/9b/6292cf7c14a0efeca0539cf7d78f453beff0475cb039fbea0eb5d07d343d/ty-0.0.12-py3-none-musllinux_1_2_i686.whl", hash = "sha256:2956e0c9ab7023533b461d8a0e6b2ea7b78e01a8dde0688e8234d0fce10c4c1c", size = 9649829, upload-time = "2026-01-14T22:30:31.234Z" }, - { url = "https://files.pythonhosted.org/packages/49/bd/472a5d2013371e4870886cff791c94abdf0b92d43d305dd0f8e06b6ff719/ty-0.0.12-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:5c6a3fd7479580009f21002f3828320621d8a82d53b7ba36993234e3ccad58c8", size = 10162814, upload-time = "2026-01-14T22:30:36.174Z" }, - { url = "https://files.pythonhosted.org/packages/31/e9/2ecbe56826759845a7c21d80aa28187865ea62bc9757b056f6cbc06f78ed/ty-0.0.12-py3-none-win32.whl", hash = "sha256:a91c24fd75c0f1796d8ede9083e2c0ec96f106dbda73a09fe3135e075d31f742", size = 9140115, upload-time = "2026-01-14T22:30:38.903Z" }, - { url = "https://files.pythonhosted.org/packages/5d/6d/d9531eff35a5c0ec9dbc10231fac21f9dd6504814048e81d6ce1c84dc566/ty-0.0.12-py3-none-win_amd64.whl", hash = "sha256:df151894be55c22d47068b0f3b484aff9e638761e2267e115d515fcc9c5b4a4b", size = 9884532, upload-time = "2026-01-14T22:30:25.112Z" }, - { url = "https://files.pythonhosted.org/packages/e9/f3/20b49e75967023b123a221134548ad7000f9429f13fdcdda115b4c26305f/ty-0.0.12-py3-none-win_arm64.whl", hash = "sha256:cea99d334b05629de937ce52f43278acf155d3a316ad6a35356635f886be20ea", size = 9313974, upload-time = "2026-01-14T22:30:27.44Z" }, + { url = "https://files.pythonhosted.org/packages/1a/df/3632f1918f4c0a33184f107efc5d436ab6da147fd3d3b94b3af6461efbf4/ty-0.0.13-py3-none-linux_armv6l.whl", hash = "sha256:1b2b8e02697c3a94c722957d712a0615bcc317c9b9497be116ef746615d892f2", size = 9993501, upload-time = "2026-01-21T13:21:26.628Z" }, + { url = "https://files.pythonhosted.org/packages/92/87/6a473ced5ac280c6ce5b1627c71a8a695c64481b99aabc798718376a441e/ty-0.0.13-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:f15cdb8e233e2b5adfce673bb21f4c5e8eaf3334842f7eea3c70ac6fda8c1de5", size = 9860986, upload-time = "2026-01-21T13:21:24.425Z" }, + { url = "https://files.pythonhosted.org/packages/5d/9b/d89ae375cf0a7cd9360e1164ce017f8c753759be63b6a11ed4c944abe8c6/ty-0.0.13-py3-none-macosx_11_0_arm64.whl", hash = "sha256:0819e89ac9f0d8af7a062837ce197f0461fee2fc14fd07e2c368780d3a397b73", size = 9350748, upload-time = "2026-01-21T13:21:28.502Z" }, + { url = "https://files.pythonhosted.org/packages/a8/a6/9ad58518056fab344b20c0bb2c1911936ebe195318e8acc3bc45ac1c6b6b/ty-0.0.13-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1de79f481084b7cc7a202ba0d7a75e10970d10ffa4f025b23f2e6b7324b74886", size = 9849884, upload-time = "2026-01-21T13:21:21.886Z" }, + { url = "https://files.pythonhosted.org/packages/b1/c3/8add69095fa179f523d9e9afcc15a00818af0a37f2b237a9b59bc0046c34/ty-0.0.13-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:4fb2154cff7c6e95d46bfaba283c60642616f20d73e5f96d0c89c269f3e1bcec", size = 9822975, upload-time = "2026-01-21T13:21:14.292Z" }, + { url = "https://files.pythonhosted.org/packages/a4/05/4c0927c68a0a6d43fb02f3f0b6c19c64e3461dc8ed6c404dde0efb8058f7/ty-0.0.13-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:00be58d89337c27968a20d58ca553458608c5b634170e2bec82824c2e4cf4d96", size = 10294045, upload-time = "2026-01-21T13:21:30.505Z" }, + { url = "https://files.pythonhosted.org/packages/b4/86/6dc190838aba967557fe0bfd494c595d00b5081315a98aaf60c0e632aaeb/ty-0.0.13-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:72435eade1fa58c6218abb4340f43a6c3ff856ae2dc5722a247d3a6dd32e9737", size = 10916460, upload-time = "2026-01-21T13:21:07.788Z" }, + { url = "https://files.pythonhosted.org/packages/04/40/9ead96b7c122e1109dfcd11671184c3506996bf6a649306ec427e81d9544/ty-0.0.13-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:77a548742ee8f621d718159e7027c3b555051d096a49bb580249a6c5fc86c271", size = 10597154, upload-time = "2026-01-21T13:21:18.064Z" }, + { url = "https://files.pythonhosted.org/packages/aa/7d/e832a2c081d2be845dc6972d0c7998914d168ccbc0b9c86794419ab7376e/ty-0.0.13-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:da067c57c289b7cf914669704b552b6207c2cc7f50da4118c3e12388642e6b3f", size = 10410710, upload-time = "2026-01-21T13:21:12.388Z" }, + { url = "https://files.pythonhosted.org/packages/31/e3/898be3a96237a32f05c4c29b43594dc3b46e0eedfe8243058e46153b324f/ty-0.0.13-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:d1b50a01fffa140417fca5a24b658fbe0734074a095d5b6f0552484724474343", size = 9826299, upload-time = "2026-01-21T13:21:00.845Z" }, + { url = "https://files.pythonhosted.org/packages/bb/eb/db2d852ce0ed742505ff18ee10d7d252f3acfd6fc60eca7e9c7a0288a6d8/ty-0.0.13-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:0f33c46f52e5e9378378eca0d8059f026f3c8073ace02f7f2e8d079ddfe5207e", size = 9831610, upload-time = "2026-01-21T13:21:05.842Z" }, + { url = "https://files.pythonhosted.org/packages/9e/61/149f59c8abaddcbcbb0bd13b89c7741ae1c637823c5cf92ed2c644fcadef/ty-0.0.13-py3-none-musllinux_1_2_i686.whl", hash = "sha256:168eda24d9a0b202cf3758c2962cc295878842042b7eca9ed2965259f59ce9f2", size = 9978885, upload-time = "2026-01-21T13:21:10.306Z" }, + { url = "https://files.pythonhosted.org/packages/a0/cd/026d4e4af60a80918a8d73d2c42b8262dd43ab2fa7b28d9743004cb88d57/ty-0.0.13-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:d4917678b95dc8cb399cc459fab568ba8d5f0f33b7a94bf840d9733043c43f29", size = 10506453, upload-time = "2026-01-21T13:20:56.633Z" }, + { url = "https://files.pythonhosted.org/packages/63/06/8932833a4eca2df49c997a29afb26721612de8078ae79074c8fe87e17516/ty-0.0.13-py3-none-win32.whl", hash = "sha256:c1f2ec40daa405508b053e5b8e440fbae5fdb85c69c9ab0ee078f8bc00eeec3d", size = 9433482, upload-time = "2026-01-21T13:20:58.717Z" }, + { url = "https://files.pythonhosted.org/packages/aa/fd/e8d972d1a69df25c2cecb20ea50e49ad5f27a06f55f1f5f399a563e71645/ty-0.0.13-py3-none-win_amd64.whl", hash = "sha256:8b7b1ab9f187affbceff89d51076038363b14113be29bda2ddfa17116de1d476", size = 10319156, upload-time = "2026-01-21T13:21:03.266Z" }, + { url = "https://files.pythonhosted.org/packages/2d/c2/05fdd64ac003a560d4fbd1faa7d9a31d75df8f901675e5bed1ee2ceeff87/ty-0.0.13-py3-none-win_arm64.whl", hash = "sha256:1c9630333497c77bb9bcabba42971b96ee1f36c601dd3dcac66b4134f9fa38f0", size = 9808316, upload-time = "2026-01-21T13:20:54.053Z" }, ] [[package]] From d76f756f42a4af121d64d46611ecb93936081760 Mon Sep 17 00:00:00 2001 From: felsager <76905857+felsager@users.noreply.github.com> Date: Mon, 26 Jan 2026 15:02:57 -0800 Subject: [PATCH 14/46] long_mpc: simplify longitudinal planner by removing "modes" (#37014) --- .../lib/longitudinal_mpc_lib/long_mpc.py | 125 +++++------------- .../controls/lib/longitudinal_planner.py | 32 ++--- .../controls/tests/test_following_distance.py | 7 +- 3 files changed, 47 insertions(+), 117 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index 3f9d8245bd..9408132c5b 100755 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -35,7 +35,7 @@ X_EGO_OBSTACLE_COST = 3. X_EGO_COST = 0. V_EGO_COST = 0. A_EGO_COST = 0. -J_EGO_COST = 5.0 +J_EGO_COST = 5. A_CHANGE_COST = 200. DANGER_ZONE_COST = 100. CRASH_DISTANCE = .25 @@ -43,7 +43,6 @@ LEAD_DANGER_FACTOR = 0.75 LIMIT_COST = 1e6 ACADOS_SOLVER_TYPE = 'SQP_RTI' - # Fewer timestamps don't hurt performance and lead to # much better convergence of the MPC with low iterations N = 12 @@ -57,6 +56,7 @@ COMFORT_BRAKE = 2.5 STOP_DISTANCE = 6.0 CRUISE_MIN_ACCEL = -1.2 CRUISE_MAX_ACCEL = 1.6 +MIN_X_LEAD_FACTOR = 0.5 def get_jerk_factor(personality=log.LongitudinalPersonality.standard): if personality==log.LongitudinalPersonality.relaxed: @@ -85,20 +85,12 @@ def get_stopped_equivalence_factor(v_lead): def get_safe_obstacle_distance(v_ego, t_follow): return (v_ego**2) / (2 * COMFORT_BRAKE) + t_follow * v_ego + STOP_DISTANCE -def desired_follow_distance(v_ego, v_lead, t_follow=None): - if t_follow is None: - t_follow = get_T_FOLLOW() - return get_safe_obstacle_distance(v_ego, t_follow) - get_stopped_equivalence_factor(v_lead) - - def gen_long_model(): model = AcadosModel() model.name = MODEL_NAME - # set up states & controls - x_ego = SX.sym('x_ego') - v_ego = SX.sym('v_ego') - a_ego = SX.sym('a_ego') + # states + x_ego, v_ego, a_ego = SX.sym('x_ego'), SX.sym('v_ego'), SX.sym('a_ego') model.x = vertcat(x_ego, v_ego, a_ego) # controls @@ -126,7 +118,6 @@ def gen_long_model(): model.f_expl_expr = f_expl return model - def gen_long_ocp(): ocp = AcadosOcp() ocp.model = gen_long_model() @@ -222,30 +213,31 @@ def gen_long_ocp(): class LongitudinalMpc: - def __init__(self, mode='acc', dt=DT_MDL): - self.mode = mode + def __init__(self, dt=DT_MDL): self.dt = dt self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N) self.reset() self.source = SOURCES[2] def reset(self): - # self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N) self.solver.reset() - # self.solver.options_set('print_level', 2) + + self.x_sol = np.zeros((N+1, X_DIM)) + self.u_sol = np.zeros((N, 1)) self.v_solution = np.zeros(N+1) self.a_solution = np.zeros(N+1) - self.prev_a = np.array(self.a_solution) self.j_solution = np.zeros(N) + self.prev_a = np.array(self.a_solution) self.yref = np.zeros((N+1, COST_DIM)) + for i in range(N): self.solver.cost_set(i, "yref", self.yref[i]) self.solver.cost_set(N, "yref", self.yref[N][:COST_E_DIM]) - self.x_sol = np.zeros((N+1, X_DIM)) - self.u_sol = np.zeros((N,1)) + self.params = np.zeros((N+1, PARAM_DIM)) for i in range(N+1): self.solver.set(i, 'x', np.zeros(X_DIM)) + self.last_cloudlog_t = 0 self.status = False self.crash_cnt = 0.0 @@ -276,16 +268,9 @@ class LongitudinalMpc: def set_weights(self, prev_accel_constraint=True, personality=log.LongitudinalPersonality.standard): jerk_factor = get_jerk_factor(personality) - if self.mode == 'acc': - a_change_cost = A_CHANGE_COST if prev_accel_constraint else 0 - cost_weights = [X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, jerk_factor * a_change_cost, jerk_factor * J_EGO_COST] - constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST] - elif self.mode == 'blended': - a_change_cost = 40.0 if prev_accel_constraint else 0 - cost_weights = [0., 0.1, 0.2, 5.0, a_change_cost, 1.0] - constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST] - else: - raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner cost set') + a_change_cost = A_CHANGE_COST if prev_accel_constraint else 0 + cost_weights = [X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, jerk_factor * a_change_cost, jerk_factor * J_EGO_COST] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST] self.set_cost_weights(cost_weights, constraint_cost_weights) def set_cur_state(self, v, a): @@ -320,14 +305,14 @@ class LongitudinalMpc: # MPC will not converge if immediate crash is expected # Clip lead distance to what is still possible to brake for - min_x_lead = ((v_ego + v_lead)/2) * (v_ego - v_lead) / (-ACCEL_MIN * 2) + min_x_lead = MIN_X_LEAD_FACTOR * (v_ego + v_lead) * (v_ego - v_lead) / (-ACCEL_MIN * 2) x_lead = np.clip(x_lead, min_x_lead, 1e8) v_lead = np.clip(v_lead, 0.0, 1e8) a_lead = np.clip(a_lead, -10., 5.) lead_xv = self.extrapolate_lead(x_lead, v_lead, a_lead, a_lead_tau) return lead_xv - def update(self, radarstate, v_cruise, x, v, a, j, personality=log.LongitudinalPersonality.standard): + def update(self, radarstate, v_cruise, personality=log.LongitudinalPersonality.standard): t_follow = get_T_FOLLOW(personality) v_ego = self.x0[1] self.status = radarstate.leadOne.status or radarstate.leadTwo.status @@ -341,56 +326,28 @@ class LongitudinalMpc: lead_0_obstacle = lead_xv_0[:,0] + get_stopped_equivalence_factor(lead_xv_0[:,1]) lead_1_obstacle = lead_xv_1[:,0] + get_stopped_equivalence_factor(lead_xv_1[:,1]) - self.params[:,0] = ACCEL_MIN - self.params[:,1] = ACCEL_MAX + # Fake an obstacle for cruise, this ensures smooth acceleration to set speed + # when the leads are no factor. + v_lower = v_ego + (T_IDXS * CRUISE_MIN_ACCEL * 1.05) + # TODO does this make sense when max_a is negative? + v_upper = v_ego + (T_IDXS * CRUISE_MAX_ACCEL * 1.05) + v_cruise_clipped = np.clip(v_cruise * np.ones(N+1), v_lower, v_upper) + cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped, t_follow) - # Update in ACC mode or ACC/e2e blend - if self.mode == 'acc': - self.params[:,5] = LEAD_DANGER_FACTOR + x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle]) + self.source = SOURCES[np.argmin(x_obstacles[0])] - # Fake an obstacle for cruise, this ensures smooth acceleration to set speed - # when the leads are no factor. - v_lower = v_ego + (T_IDXS * CRUISE_MIN_ACCEL * 1.05) - # TODO does this make sense when max_a is negative? - v_upper = v_ego + (T_IDXS * CRUISE_MAX_ACCEL * 1.05) - v_cruise_clipped = np.clip(v_cruise * np.ones(N+1), - v_lower, - v_upper) - cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped, t_follow) - x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle]) - self.source = SOURCES[np.argmin(x_obstacles[0])] - - # These are not used in ACC mode - x[:], v[:], a[:], j[:] = 0.0, 0.0, 0.0, 0.0 - - elif self.mode == 'blended': - self.params[:,5] = 1.0 - - x_obstacles = np.column_stack([lead_0_obstacle, - lead_1_obstacle]) - cruise_target = T_IDXS * np.clip(v_cruise, v_ego - 2.0, 1e3) + x[0] - xforward = ((v[1:] + v[:-1]) / 2) * (T_IDXS[1:] - T_IDXS[:-1]) - x = np.cumsum(np.insert(xforward, 0, x[0])) - - x_and_cruise = np.column_stack([x, cruise_target]) - x = np.min(x_and_cruise, axis=1) - - self.source = 'e2e' if x_and_cruise[1,0] < x_and_cruise[1,1] else 'cruise' - - else: - raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner update') - - self.yref[:,1] = x - self.yref[:,2] = v - self.yref[:,3] = a - self.yref[:,5] = j + self.yref[:,:] = 0.0 for i in range(N): self.solver.set(i, "yref", self.yref[i]) self.solver.set(N, "yref", self.yref[N][:COST_E_DIM]) + self.params[:,0] = ACCEL_MIN + self.params[:,1] = ACCEL_MAX self.params[:,2] = np.min(x_obstacles, axis=1) self.params[:,3] = np.copy(self.prev_a) self.params[:,4] = t_follow + self.params[:,5] = LEAD_DANGER_FACTOR self.run() if (np.any(lead_xv_0[FCW_IDXS,0] - self.x_sol[FCW_IDXS,0] < CRASH_DISTANCE) and @@ -399,18 +356,7 @@ class LongitudinalMpc: else: self.crash_cnt = 0 - # Check if it got within lead comfort range - # TODO This should be done cleaner - if self.mode == 'blended': - if any((lead_0_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], t_follow))- self.x_sol[:,0] < 0.0): - self.source = 'lead0' - if any((lead_1_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], t_follow))- self.x_sol[:,0] < 0.0) and \ - (lead_1_obstacle[0] - lead_0_obstacle[0]): - self.source = 'lead1' - def run(self): - # t0 = time.monotonic() - # reset = 0 for i in range(N+1): self.solver.set(i, 'p', self.params[i]) self.solver.constraints_set(0, "lbx", self.x0) @@ -422,13 +368,6 @@ class LongitudinalMpc: self.time_linearization = float(self.solver.get_stats('time_lin')[0]) self.time_integrator = float(self.solver.get_stats('time_sim')[0]) - # qp_iter = self.solver.get_stats('statistics')[-1][-1] # SQP_RTI specific - # print(f"long_mpc timings: tot {self.solve_time:.2e}, qp {self.time_qp_solution:.2e}, lin {self.time_linearization:.2e}, \ - # integrator {self.time_integrator:.2e}, qp_iter {qp_iter}") - # res = self.solver.get_residuals() - # print(f"long_mpc residuals: {res[0]:.2e}, {res[1]:.2e}, {res[2]:.2e}, {res[3]:.2e}") - # self.solver.print_statistics() - for i in range(N+1): self.x_sol[i] = self.solver.get(i, 'x') for i in range(N): @@ -446,12 +385,8 @@ class LongitudinalMpc: self.last_cloudlog_t = t cloudlog.warning(f"Long mpc reset, solution_status: {self.solution_status}") self.reset() - # reset = 1 - # print(f"long_mpc timings: total internal {self.solve_time:.2e}, external: {(time.monotonic() - t0):.2e} qp {self.time_qp_solution:.2e}, \ - # lin {self.time_linearization:.2e} qp_iter {qp_iter}, reset {reset}") if __name__ == "__main__": ocp = gen_long_ocp() AcadosOcpSolver.generate(ocp, json_file=JSON_FILE) - # AcadosOcpSolver.build(ocp.code_export_directory, with_cython=True) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 34fc85f8a5..ad84ecf24f 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -9,13 +9,12 @@ from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.realtime import DT_MDL from openpilot.selfdrive.modeld.constants import ModelConstants from openpilot.selfdrive.controls.lib.longcontrol import LongCtrlState -from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc +from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc, SOURCES from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, get_accel_from_plan from openpilot.selfdrive.car.cruise import V_CRUISE_MAX, V_CRUISE_UNSET from openpilot.common.swaglog import cloudlog -LON_MPC_STEP = 0.2 # first step is 0.2s A_CRUISE_MAX_VALS = [1.6, 1.2, 0.8, 0.6] A_CRUISE_MAX_BP = [0., 10.0, 25., 40.] CONTROL_N_T_IDX = ModelConstants.T_IDXS[:CONTROL_N] @@ -26,14 +25,12 @@ MIN_ALLOW_THROTTLE_SPEED = 2.5 _A_TOTAL_MAX_V = [1.7, 3.2] _A_TOTAL_MAX_BP = [20., 40.] - def get_max_accel(v_ego): return np.interp(v_ego, A_CRUISE_MAX_BP, A_CRUISE_MAX_VALS) def get_coast_accel(pitch): return np.sin(pitch) * -5.65 - 0.3 # fitted from data using xx/projects/allow_throttle/compute_coast_accel.py - def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): """ This function returns a limited long acceleration allowed, depending on the existing lateral acceleration @@ -52,8 +49,6 @@ class LongitudinalPlanner: def __init__(self, CP, init_v=0.0, init_a=0.0, dt=DT_MDL): self.CP = CP self.mpc = LongitudinalMpc(dt=dt) - # TODO remove mpc modes when TR released - self.mpc.mode = 'acc' self.fcw = False self.dt = dt self.allow_throttle = True @@ -67,7 +62,6 @@ class LongitudinalPlanner: self.v_desired_trajectory = np.zeros(CONTROL_N) self.a_desired_trajectory = np.zeros(CONTROL_N) self.j_desired_trajectory = np.zeros(CONTROL_N) - self.solverExecutionTime = 0.0 @staticmethod def parse_model(model_msg): @@ -90,8 +84,6 @@ class LongitudinalPlanner: return x, v, a, j, throttle_prob def update(self, sm): - mode = 'blended' if sm['selfdriveState'].experimentalMode else 'acc' - if len(sm['carControl'].orientationNED) == 3: accel_coast = get_coast_accel(sm['carControl'].orientationNED[1]) else: @@ -113,12 +105,9 @@ class LongitudinalPlanner: # No change cost when user is controlling the speed, or when standstill prev_accel_constraint = not (reset_state or sm['carState'].standstill) - if mode == 'acc': - accel_clip = [ACCEL_MIN, get_max_accel(v_ego)] - steer_angle_without_offset = sm['carState'].steeringAngleDeg - sm['liveParameters'].angleOffsetDeg - accel_clip = limit_accel_in_turns(v_ego, steer_angle_without_offset, accel_clip, self.CP) - else: - accel_clip = [ACCEL_MIN, ACCEL_MAX] + accel_clip = [ACCEL_MIN, get_max_accel(v_ego)] + steer_angle_without_offset = sm['carState'].steeringAngleDeg - sm['liveParameters'].angleOffsetDeg + accel_clip = limit_accel_in_turns(v_ego, steer_angle_without_offset, accel_clip, self.CP) if reset_state: self.v_desired_filter.x = v_ego @@ -127,7 +116,7 @@ class LongitudinalPlanner: # Prevent divergence, smooth in current v_ego self.v_desired_filter.x = max(0.0, self.v_desired_filter.update(v_ego)) - x, v, a, j, throttle_prob = self.parse_model(sm['modelV2']) + _, _, _, _, throttle_prob = self.parse_model(sm['modelV2']) # Don't clip at low speeds since throttle_prob doesn't account for creep self.allow_throttle = throttle_prob > ALLOW_THROTTLE_THRESHOLD or v_ego <= MIN_ALLOW_THROTTLE_SPEED @@ -141,7 +130,7 @@ class LongitudinalPlanner: self.mpc.set_weights(prev_accel_constraint, personality=sm['selfdriveState'].personality) self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired) - self.mpc.update(sm['radarState'], v_cruise, x, v, a, j, personality=sm['selfdriveState'].personality) + self.mpc.update(sm['radarState'], v_cruise, personality=sm['selfdriveState'].personality) self.v_desired_trajectory = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC, self.mpc.v_solution) self.a_desired_trajectory = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC, self.mpc.a_solution) @@ -163,12 +152,13 @@ class LongitudinalPlanner: output_a_target_e2e = sm['modelV2'].action.desiredAcceleration output_should_stop_e2e = sm['modelV2'].action.shouldStop - if mode == 'acc': + if (output_a_target_e2e < output_a_target_mpc) and sm['selfdriveState'].experimentalMode: + output_a_target = output_a_target_e2e + self.output_should_stop = output_should_stop_e2e + self.mpc.source = SOURCES[3] + else: output_a_target = output_a_target_mpc self.output_should_stop = output_should_stop_mpc - else: - output_a_target = min(output_a_target_mpc, output_a_target_e2e) - self.output_should_stop = output_should_stop_e2e or output_should_stop_mpc for idx in range(2): accel_clip[idx] = np.clip(accel_clip[idx], self.prev_accel_clip[idx] - 0.05, self.prev_accel_clip[idx] + 0.05) diff --git a/selfdrive/controls/tests/test_following_distance.py b/selfdrive/controls/tests/test_following_distance.py index 0fd543dd60..8f66d89bf8 100644 --- a/selfdrive/controls/tests/test_following_distance.py +++ b/selfdrive/controls/tests/test_following_distance.py @@ -4,10 +4,15 @@ from parameterized import parameterized_class from cereal import log -from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import desired_follow_distance, get_T_FOLLOW +from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import get_safe_obstacle_distance, get_stopped_equivalence_factor, get_T_FOLLOW from openpilot.selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver +def desired_follow_distance(v_ego, v_lead, t_follow=None): + if t_follow is None: + t_follow = get_T_FOLLOW() + return get_safe_obstacle_distance(v_ego, t_follow) - get_stopped_equivalence_factor(v_lead) + def run_following_distance_simulation(v_lead, t_end=100.0, e2e=False, personality=0): man = Maneuver( '', From 97329e46ae11b92cf7f82fed485e5e141be6dfe2 Mon Sep 17 00:00:00 2001 From: felsager <76905857+felsager@users.noreply.github.com> Date: Mon, 26 Jan 2026 16:07:13 -0800 Subject: [PATCH 15/46] longitudinal maneuvers: add report for longitudinal mpc tuning (#37030) --- .../mpc_longitudinal_tuning_report.py | 276 ++++++++++++++++++ 1 file changed, 276 insertions(+) create mode 100644 tools/longitudinal_maneuvers/mpc_longitudinal_tuning_report.py diff --git a/tools/longitudinal_maneuvers/mpc_longitudinal_tuning_report.py b/tools/longitudinal_maneuvers/mpc_longitudinal_tuning_report.py new file mode 100644 index 0000000000..583c6240e5 --- /dev/null +++ b/tools/longitudinal_maneuvers/mpc_longitudinal_tuning_report.py @@ -0,0 +1,276 @@ +import io +import sys +import markdown +import numpy as np +import matplotlib.pyplot as plt +from openpilot.selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver +from openpilot.selfdrive.controls.tests.test_following_distance import desired_follow_distance + +TIME = 0 +EGO_V = 3 +EGO_A = 5 +LEAD_DISTANCE= 2 + +axis_labels = ['Time (s)', + 'Ego position (m)', + 'Lead distance (m)', + 'Ego Velocity (m/s)', + 'Lead Velocity (m/s)', + 'Ego acceleration (m/s^2)', + ] + + +def get_html_from_results(results, labels, AXIS): + fig, ax = plt.subplots(figsize=(16, 8)) + for idx, speed in enumerate(list(results.keys())): + ax.plot(results[speed][:, TIME], results[speed][:, AXIS], label=labels[idx]) + + ax.set_xlabel('Time (s)') + ax.set_ylabel(axis_labels[AXIS]) + ax.legend(bbox_to_anchor=(1.02, 1), loc='upper left', borderaxespad=0) + ax.grid(True, linestyle='--', alpha=0.7) + ax.text(-0.075, 0.5, '.', transform=ax.transAxes, color='none') + + fig_buffer = io.StringIO() + fig.savefig(fig_buffer, format='svg', bbox_inches='tight') + plt.close(fig) + return fig_buffer.getvalue() + '
' + + +htmls = [] + +results = {} +name = 'Resuming behind lead' +labels = [] +for lead_accel in np.linspace(1.0, 4.0, 4): + man = Maneuver( + '', + duration=11, + initial_speed=0.0, + lead_relevancy=True, + initial_distance_lead=desired_follow_distance(0.0, 0.0), + speed_lead_values=[0.0, 10 * lead_accel], + cruise_values=[100, 100], + prob_lead_values=[1.0, 1.0], + breakpoints=[1., 11], + ) + valid, results[lead_accel] = man.evaluate() + labels.append(f'{lead_accel} m/s^2 lead acceleration') + +htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, EGO_V)) +htmls.append(get_html_from_results(results, labels, EGO_A)) + + +results = {} +name = 'Approaching stopped car from 140m' +labels = [] +for speed in np.arange(0,45,5): + man = Maneuver( + name, + duration=30., + initial_speed=float(speed), + lead_relevancy=True, + initial_distance_lead=140., + speed_lead_values=[0.0, 0.], + breakpoints=[0., 30.], + ) + valid, results[speed] = man.evaluate() + results[speed][:,2] = results[speed][:,2] - results[speed][:,1] + labels.append(f'{speed} m/s approach speed') + +htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, EGO_A)) +htmls.append(get_html_from_results(results, labels, LEAD_DISTANCE)) + + +results = {} +name = 'Following 5s oscillating lead' +labels = [] +speed = np.int64(10) +for oscil in np.arange(0, 10, 1): + man = Maneuver( + '', + duration=30., + initial_speed=float(speed), + lead_relevancy=True, + initial_distance_lead=desired_follow_distance(speed, speed), + speed_lead_values=[speed, speed, speed - oscil, speed + oscil, speed - oscil, speed + oscil, speed - oscil], + breakpoints=[0.,2., 5, 8, 15, 18, 25.], + ) + valid, results[oscil] = man.evaluate() + labels.append(f'{oscil} m/s oscilliation size') + +htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, EGO_V)) +htmls.append(get_html_from_results(results, labels, EGO_A)) + + + +results = {} +name = 'Speed profile when converging to steady state lead at 30m/s' +labels = [] +for distance in np.arange(20, 140, 10): + man = Maneuver( + '', + duration=50, + initial_speed=30.0, + lead_relevancy=True, + initial_distance_lead=distance, + speed_lead_values=[30.0], + breakpoints=[0.], + ) + valid, results[distance] = man.evaluate() + results[distance][:,2] = results[distance][:,2] - results[distance][:,1] + labels.append(f'{distance} m initial distance') + +htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, EGO_V)) +htmls.append(get_html_from_results(results, labels, LEAD_DISTANCE)) + + +results = {} +name = 'Speed profile when converging to steady state lead at 20m/s' +labels = [] +for distance in np.arange(20, 140, 10): + man = Maneuver( + '', + duration=50, + initial_speed=20.0, + lead_relevancy=True, + initial_distance_lead=distance, + speed_lead_values=[20.0], + breakpoints=[0.], + ) + valid, results[distance] = man.evaluate() + results[distance][:,2] = results[distance][:,2] - results[distance][:,1] + labels.append(f'{distance} m initial distance') + +htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, EGO_V)) +htmls.append(get_html_from_results(results, labels, LEAD_DISTANCE)) + + +results = {} +name = 'Following car at 30m/s that comes to a stop' +labels = [] +for stop_time in np.arange(4, 14, 1): + man = Maneuver( + '', + duration=50, + initial_speed=30.0, + lead_relevancy=True, + initial_distance_lead=60.0, + speed_lead_values=[30.0, 30.0, 0.0, 0.0], + breakpoints=[0., 20., 20 + stop_time, 30 + stop_time], + ) + valid, results[stop_time] = man.evaluate() + results[stop_time][:,2] = results[stop_time][:,2] - results[stop_time][:,1] + labels.append(f'{stop_time} seconds stop time') + +htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, EGO_A)) +htmls.append(get_html_from_results(results, labels, LEAD_DISTANCE)) + + +results = {} +name = 'Response to cut-in at half follow distance' +labels = [] +for speed in np.arange(0, 40, 5): + man = Maneuver( + '', + duration=10, + initial_speed=float(speed), + lead_relevancy=True, + initial_distance_lead=desired_follow_distance(speed, speed)/2, + speed_lead_values=[speed, speed, speed], + cruise_values=[speed, speed, speed], + prob_lead_values=[0.0, 0.0, 1.0], + breakpoints=[0., 5.0, 5.01], + ) + valid, results[speed] = man.evaluate() + labels.append(f'{speed} m/s speed') + +htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, EGO_A)) +htmls.append(get_html_from_results(results, labels, LEAD_DISTANCE)) + + +results = {} +name = 'Follow a lead that accelerates at 2m/s^2 until steady state speed' +labels = [] +for speed in np.arange(0, 40, 5): + man = Maneuver( + '', + duration=50, + initial_speed=0.0, + lead_relevancy=True, + initial_distance_lead=desired_follow_distance(0.0, 0.0), + speed_lead_values=[0.0, 0.0, speed], + prob_lead_values=[1.0, 1.0, 1.0], + breakpoints=[0., 1.0, speed/2], + ) + valid, results[speed] = man.evaluate() + labels.append(f'{speed} m/s speed') + +htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, EGO_V)) +htmls.append(get_html_from_results(results, labels, EGO_A)) + + +results = {} +name = 'From stop to cruise' +labels = [] +for speed in np.arange(0, 40, 5): + man = Maneuver( + '', + duration=50, + initial_speed=0.0, + lead_relevancy=True, + initial_distance_lead=desired_follow_distance(0.0, 0.0), + speed_lead_values=[0.0, 0.0], + cruise_values=[0.0, speed], + prob_lead_values=[0.0, 0.0], + breakpoints=[1., 1.01], + ) + valid, results[speed] = man.evaluate() + labels.append(f'{speed} m/s speed') + +htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, EGO_V)) +htmls.append(get_html_from_results(results, labels, EGO_A)) + + +results = {} +name = 'From cruise to min' +labels = [] +for speed in np.arange(10, 40, 5): + man = Maneuver( + '', + duration=50, + initial_speed=float(speed), + lead_relevancy=True, + initial_distance_lead=desired_follow_distance(0.0, 0.0), + speed_lead_values=[0.0, 0.0], + cruise_values=[speed, 10.0], + prob_lead_values=[0.0, 0.0], + breakpoints=[1., 1.01], + ) + valid, results[speed] = man.evaluate() + labels.append(f'{speed} m/s speed') + +htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, EGO_V)) +htmls.append(get_html_from_results(results, labels, EGO_A)) + +if len(sys.argv) < 2: + file_name = 'long_mpc_tune_report.html' +else: + file_name = sys.argv[1] + +with open(file_name, 'w') as f: + f.write(markdown.markdown('# MPC longitudinal tuning report')) + +with open(file_name, 'a') as f: + for html in htmls: + f.write(html) From 93015c1c178e218adcfe9688ea13f58effc6d94e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 27 Jan 2026 15:40:09 -0800 Subject: [PATCH 16/46] ui: fix button label color (#37031) label color --- selfdrive/ui/mici/widgets/button.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/mici/widgets/button.py b/selfdrive/ui/mici/widgets/button.py index 82310577b0..9678827a91 100644 --- a/selfdrive/ui/mici/widgets/button.py +++ b/selfdrive/ui/mici/widgets/button.py @@ -16,7 +16,7 @@ except ImportError: SCROLLING_SPEED_PX_S = 50 COMPLICATION_SIZE = 36 -LABEL_COLOR = rl.WHITE +LABEL_COLOR = rl.Color(255, 255, 255, int(255 * 0.9)) LABEL_HORIZONTAL_PADDING = 40 COMPLICATION_GREY = rl.Color(0xAA, 0xAA, 0xAA, 255) PRESSED_SCALE = 1.15 if DO_ZOOM else 1.07 From bf8cae5e7cbbec97483f7e358568ea2e21ca8579 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 27 Jan 2026 16:20:32 -0800 Subject: [PATCH 17/46] mici ui: new icons (#37021) * new icons * add missing * fixed tethering big icon, size of pairing comma, buttons now use 90percent white * why o why * newline * fancy * already default * fixes * add firehose * ltl * fix caps lock icon --------- Co-authored-by: nickorie --- selfdrive/assets/icons_mici/adb_short.png | 3 +++ .../buttons/toggle_dot_disabled.png | 4 +-- .../assets/icons_mici/exclamation_point.png | 4 +-- .../assets/icons_mici/experimental_mode.png | 4 +-- selfdrive/assets/icons_mici/microphone.png | 4 +-- .../icons_mici/offroad_alerts/green_wheel.png | 4 +-- .../offroad_alerts/orange_warning.png | 4 +-- .../icons_mici/offroad_alerts/red_warning.png | 4 +-- .../icons_mici/onroad/blind_spot_left.png | 4 +-- .../icons_mici/onroad/blind_spot_right.png | 4 +-- .../assets/icons_mici/onroad/bookmark.png | 4 +-- .../icons_mici/onroad/bookmark_fill.png | 3 +++ .../driver_monitoring/dm_background.png | 4 +-- .../onroad/driver_monitoring/dm_person.png | 4 +-- .../assets/icons_mici/onroad/eye_fill.png | 4 +-- .../assets/icons_mici/onroad/eye_orange.png | 4 +-- .../assets/icons_mici/onroad/glasses.png | 4 +-- .../assets/icons_mici/onroad/onroad_fade.png | 4 +-- .../icons_mici/onroad/turn_signal_left.png | 4 +-- .../icons_mici/onroad/turn_signal_right.png | 4 +-- selfdrive/assets/icons_mici/settings.png | 4 +-- .../assets/icons_mici/settings/comma_icon.png | 4 +-- .../icons_mici/settings/developer/ssh.png | 4 +-- .../icons_mici/settings/developer_icon.png | 4 +-- .../icons_mici/settings/device/cameras.png | 4 +-- .../icons_mici/settings/device/info.png | 4 +-- .../icons_mici/settings/device/language.png | 4 +-- .../icons_mici/settings/device/lkas.png | 4 +-- .../icons_mici/settings/device/pair.png | 4 +-- .../icons_mici/settings/device/power.png | 4 +-- .../icons_mici/settings/device/reboot.png | 4 +-- .../icons_mici/settings/device/uninstall.png | 4 +-- .../icons_mici/settings/device/up_to_date.png | 4 +-- .../icons_mici/settings/device/update.png | 4 +-- .../icons_mici/settings/device_icon.png | 4 +-- .../assets/icons_mici/settings/firehose.png | 3 +++ .../settings/keyboard/backspace.png | 4 +-- .../settings/keyboard/caps_lock.png | 4 +-- .../settings/keyboard/caps_lower.png | 4 +-- .../settings/keyboard/caps_upper.png | 4 +-- .../icons_mici/settings/keyboard/confirm.png | 4 +-- .../icons_mici/settings/keyboard/space.png | 4 +-- .../icons_mici/settings/manual_icon.png | 3 --- .../settings/network/cell_strength_full.png | 4 +-- .../settings/network/cell_strength_high.png | 4 +-- .../settings/network/cell_strength_low.png | 4 +-- .../settings/network/cell_strength_medium.png | 4 +-- .../settings/network/cell_strength_none.png | 4 +-- .../icons_mici/settings/network/new/lock.png | 4 +-- .../icons_mici/settings/network/new/trash.png | 4 +-- .../icons_mici/settings/network/tethering.png | 4 +-- .../settings/network/wifi_strength_full.png | 4 +-- .../settings/network/wifi_strength_low.png | 4 +-- .../settings/network/wifi_strength_medium.png | 4 +-- .../settings/network/wifi_strength_none.png | 4 +-- .../settings/network/wifi_strength_slash.png | 4 +-- .../icons_mici/settings/toggles_icon.png | 3 --- .../assets/icons_mici/setup/back_new.png | 4 +-- .../setup/driver_monitoring/dm_check.png | 4 +-- .../setup/driver_monitoring/dm_question.png | 4 +-- .../assets/icons_mici/setup/green_car.png | 3 --- .../assets/icons_mici/setup/green_dm.png | 4 +-- .../assets/icons_mici/setup/green_info.png | 4 +-- .../assets/icons_mici/setup/green_pedal.png | 3 --- .../assets/icons_mici/setup/orange_dm.png | 4 +-- .../assets/icons_mici/setup/red_warning.png | 4 +-- selfdrive/assets/icons_mici/setup/restore.png | 4 +-- .../setup/scroll_down_indicator.png | 4 +-- .../setup/small_slider/slider_arrow.png | 4 +-- selfdrive/assets/icons_mici/setup/warning.png | 4 +-- selfdrive/assets/icons_mici/ssh_short.png | 3 +++ .../assets/icons_mici/tethering_short.png | 3 +++ .../assets/icons_mici/turn_intent_left.png | 4 +-- .../assets/icons_mici/turn_intent_right.png | 4 +-- selfdrive/assets/icons_mici/wheel.png | 4 +-- .../assets/icons_mici/wheel_critical.png | 4 +-- selfdrive/ui/mici/layouts/home.py | 20 +++++++-------- selfdrive/ui/mici/layouts/onboarding.py | 4 +-- .../ui/mici/layouts/settings/developer.py | 8 +++--- selfdrive/ui/mici/layouts/settings/device.py | 12 ++++----- .../mici/layouts/settings/network/__init__.py | 9 +++---- .../mici/layouts/settings/network/wifi_ui.py | 12 ++++----- .../ui/mici/layouts/settings/settings.py | 10 ++++---- selfdrive/ui/mici/onroad/alert_renderer.py | 8 +++--- selfdrive/ui/mici/onroad/hud_renderer.py | 4 +-- selfdrive/ui/mici/widgets/button.py | 25 +++++++++++-------- selfdrive/ui/mici/widgets/dialog.py | 4 +-- selfdrive/ui/mici/widgets/pairing_dialog.py | 2 +- system/ui/widgets/mici_keyboard.py | 20 ++++++++------- 89 files changed, 220 insertions(+), 213 deletions(-) create mode 100644 selfdrive/assets/icons_mici/adb_short.png create mode 100644 selfdrive/assets/icons_mici/onroad/bookmark_fill.png create mode 100644 selfdrive/assets/icons_mici/settings/firehose.png delete mode 100644 selfdrive/assets/icons_mici/settings/manual_icon.png delete mode 100644 selfdrive/assets/icons_mici/settings/toggles_icon.png delete mode 100644 selfdrive/assets/icons_mici/setup/green_car.png delete mode 100644 selfdrive/assets/icons_mici/setup/green_pedal.png create mode 100644 selfdrive/assets/icons_mici/ssh_short.png create mode 100644 selfdrive/assets/icons_mici/tethering_short.png diff --git a/selfdrive/assets/icons_mici/adb_short.png b/selfdrive/assets/icons_mici/adb_short.png new file mode 100644 index 0000000000..c49226c858 --- /dev/null +++ b/selfdrive/assets/icons_mici/adb_short.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:263598da73c577c01cebd31ae78f45969ef8b335be1a5f55d54a696bb2982c0a +size 2062 diff --git a/selfdrive/assets/icons_mici/buttons/toggle_dot_disabled.png b/selfdrive/assets/icons_mici/buttons/toggle_dot_disabled.png index 0e21bc1b5a..1ff4db45a5 100644 --- a/selfdrive/assets/icons_mici/buttons/toggle_dot_disabled.png +++ b/selfdrive/assets/icons_mici/buttons/toggle_dot_disabled.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:613af9ed79bb26c60fbd19c094214f0881736c0e293f6d000b530cde0478a273 -size 2470 +oid sha256:89ac033d879beeb0a7fa1919838e0ec64b1a625a4aafc14f7b990c607a79b676 +size 2220 diff --git a/selfdrive/assets/icons_mici/exclamation_point.png b/selfdrive/assets/icons_mici/exclamation_point.png index 246fc015ec..ede3b638bc 100644 --- a/selfdrive/assets/icons_mici/exclamation_point.png +++ b/selfdrive/assets/icons_mici/exclamation_point.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:b77579c099c688d1a27f356197fba9c2c8efcf4d391af580b4b29f0e70587919 -size 2086 +oid sha256:254b7f753b70c964847b686f0f71af751f2f49beea6ede4aeb333fe06062a257 +size 2289 diff --git a/selfdrive/assets/icons_mici/experimental_mode.png b/selfdrive/assets/icons_mici/experimental_mode.png index e0138bfd65..75850d08f5 100644 --- a/selfdrive/assets/icons_mici/experimental_mode.png +++ b/selfdrive/assets/icons_mici/experimental_mode.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:eb42b8d6259238beb26f286dc28fb2dc8d91b00fec1f7a7655296b5769439a15 -size 15690 +oid sha256:01841b602632c66ab14a8e52b874a1623f09641dc2ef0620f4e2d00bb4a913f3 +size 16243 diff --git a/selfdrive/assets/icons_mici/microphone.png b/selfdrive/assets/icons_mici/microphone.png index 9718a6b135..9af8f2f455 100644 --- a/selfdrive/assets/icons_mici/microphone.png +++ b/selfdrive/assets/icons_mici/microphone.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:17b6fe530598cbad34bcf31d4f21f929b792aacedef51b3ffef1941c86017811 -size 7331 +oid sha256:744dbaa68ee74e300cd46439bad79449c860e1c5c027304b0f382bd5383fba77 +size 6817 diff --git a/selfdrive/assets/icons_mici/offroad_alerts/green_wheel.png b/selfdrive/assets/icons_mici/offroad_alerts/green_wheel.png index 6a8351f6ee..08181ca35f 100644 --- a/selfdrive/assets/icons_mici/offroad_alerts/green_wheel.png +++ b/selfdrive/assets/icons_mici/offroad_alerts/green_wheel.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:05f3626e790622a4ad90e982c4aacb612d0785a752339352a3187addf763e2e9 -size 13288 +oid sha256:3b11ee84d48972a2499cb29f01594d77a1a39692f6424a315a3f83262bc16087 +size 13481 diff --git a/selfdrive/assets/icons_mici/offroad_alerts/orange_warning.png b/selfdrive/assets/icons_mici/offroad_alerts/orange_warning.png index 13af475c6d..52e6836d4b 100644 --- a/selfdrive/assets/icons_mici/offroad_alerts/orange_warning.png +++ b/selfdrive/assets/icons_mici/offroad_alerts/orange_warning.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:a877882a8dccb884bd35918f9f9b427a724a59e90a638e54f6fd5d0680ad173c -size 12137 +oid sha256:d548405a65ba4d4590c55866612dc6aa0e78d9278fc864ef60fe3e463edf4a68 +size 12169 diff --git a/selfdrive/assets/icons_mici/offroad_alerts/red_warning.png b/selfdrive/assets/icons_mici/offroad_alerts/red_warning.png index 83c3595b29..df608d3518 100644 --- a/selfdrive/assets/icons_mici/offroad_alerts/red_warning.png +++ b/selfdrive/assets/icons_mici/offroad_alerts/red_warning.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:ba944b208abed9b8b9752adb8017bd29cd2e98c89fb07ee5d0a595185c7564a5 -size 11898 +oid sha256:b6fc63326d34fbe72f6daf104d101ce19e547dbfe134427c067c957a7179df74 +size 12124 diff --git a/selfdrive/assets/icons_mici/onroad/blind_spot_left.png b/selfdrive/assets/icons_mici/onroad/blind_spot_left.png index 5d3b1e5d7b..fdc189b858 100644 --- a/selfdrive/assets/icons_mici/onroad/blind_spot_left.png +++ b/selfdrive/assets/icons_mici/onroad/blind_spot_left.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:a23743d21bc8160e013625210654a55634e4ed58e60057b70e08761bac1c3680 -size 40406 +oid sha256:77b20a8c478d982412d556afb3a035b80b4aa9fe7a86aea761af4a42147d9435 +size 45297 diff --git a/selfdrive/assets/icons_mici/onroad/blind_spot_right.png b/selfdrive/assets/icons_mici/onroad/blind_spot_right.png index 67216078d9..b6cd7834ef 100644 --- a/selfdrive/assets/icons_mici/onroad/blind_spot_right.png +++ b/selfdrive/assets/icons_mici/onroad/blind_spot_right.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:acbfa3e38f0b9f422f5c1335ce20013852df2892b813db176a51918adc83ad58 -size 40979 +oid sha256:584cea202afff6dd20d67ae1a9cd6d2b8cc07598bccb91a8d1bac0142567308e +size 45489 diff --git a/selfdrive/assets/icons_mici/onroad/bookmark.png b/selfdrive/assets/icons_mici/onroad/bookmark.png index 207182276e..305561f509 100644 --- a/selfdrive/assets/icons_mici/onroad/bookmark.png +++ b/selfdrive/assets/icons_mici/onroad/bookmark.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:e0d00d743b01c49c2b739127e9916a229caf8c48346d6d168863b080ddcaa409 -size 11124 +oid sha256:fd91685bf656e828648acf035a4737acb2c4709e8514cf0aa0a10fa470a9bb60 +size 11580 diff --git a/selfdrive/assets/icons_mici/onroad/bookmark_fill.png b/selfdrive/assets/icons_mici/onroad/bookmark_fill.png new file mode 100644 index 0000000000..531d5db1cf --- /dev/null +++ b/selfdrive/assets/icons_mici/onroad/bookmark_fill.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f3f57346a1cf9a66f9fd746f87bcebb23b7a403e9d6e4fd7701b126abcdd47ea +size 18476 diff --git a/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_background.png b/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_background.png index 04ffc24356..4129b13d92 100644 --- a/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_background.png +++ b/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_background.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:b7eb870d01e5bf6c421e204026a4ea08e177731f2d6b5b17c4ad43c90c1c3e78 -size 23549 +oid sha256:cb89d9f11cf44992f92142aa5ad84e1ac700a2601aff2abab373e2a822af149e +size 11678 diff --git a/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_person.png b/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_person.png index 540b2029a0..5b917f3a4a 100644 --- a/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_person.png +++ b/selfdrive/assets/icons_mici/onroad/driver_monitoring/dm_person.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:f7b3bb76ee2359076339285ea6bced5b680e5b919a1b7dee163f36cd819c9ea1 -size 1746 +oid sha256:e2772c6a9fe9c57099d347ad49f0cb7c906593f1fdf0e6dde96d104baf0200b0 +size 1365 diff --git a/selfdrive/assets/icons_mici/onroad/eye_fill.png b/selfdrive/assets/icons_mici/onroad/eye_fill.png index 8f0e8ebfb1..78758a9809 100644 --- a/selfdrive/assets/icons_mici/onroad/eye_fill.png +++ b/selfdrive/assets/icons_mici/onroad/eye_fill.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:51af75afbaf30abeaae1c99c7ad3e25cf5d5c90a2d6c799aad353b3302384b0a -size 4829 +oid sha256:07310879d093108435c0011846ae1184966db86443bc6e7ca036a6fa6123700b +size 4983 diff --git a/selfdrive/assets/icons_mici/onroad/eye_orange.png b/selfdrive/assets/icons_mici/onroad/eye_orange.png index b61b9b063c..932c71260b 100644 --- a/selfdrive/assets/icons_mici/onroad/eye_orange.png +++ b/selfdrive/assets/icons_mici/onroad/eye_orange.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:88b2ecf3a9834d2b156bb632ec2090d7dc112e8ab61711ba645c03489d1c457f -size 29157 +oid sha256:7be447e56d649e0362ef650494b484e140a01ead31799ce43b266f5781c918d2 +size 36473 diff --git a/selfdrive/assets/icons_mici/onroad/glasses.png b/selfdrive/assets/icons_mici/onroad/glasses.png index 1ac4442f49..006972fd39 100644 --- a/selfdrive/assets/icons_mici/onroad/glasses.png +++ b/selfdrive/assets/icons_mici/onroad/glasses.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:28c95c8970648d40b35b94724936a9ab7a6f4cbca367a40f01b86f9abedc70e5 -size 1587 +oid sha256:56de402482b5987ed9a0ff3f793a1c89f857304b34fbb8a3deb5b5d4a332be1c +size 3688 diff --git a/selfdrive/assets/icons_mici/onroad/onroad_fade.png b/selfdrive/assets/icons_mici/onroad/onroad_fade.png index bc12e57e17..3f823061b9 100644 --- a/selfdrive/assets/icons_mici/onroad/onroad_fade.png +++ b/selfdrive/assets/icons_mici/onroad/onroad_fade.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:d2a2cb4db429467783d7f721ffbed7838551e4aabf32771e73759c87b4a67bca -size 28880 +oid sha256:2aa6d04ba038f15a92868de6e6c7b04f624b4fe89d03bc3e9c4cd44cb729b24e +size 38317 diff --git a/selfdrive/assets/icons_mici/onroad/turn_signal_left.png b/selfdrive/assets/icons_mici/onroad/turn_signal_left.png index 48f52ff9ce..97b5cf1443 100644 --- a/selfdrive/assets/icons_mici/onroad/turn_signal_left.png +++ b/selfdrive/assets/icons_mici/onroad/turn_signal_left.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:0e845a211cf5d03f781efdd6eec4f8106e8dd85799ea59b51834a9099b479141 -size 30348 +oid sha256:f9f7d0554c0c79ab605c1119ffdef0a4f55196e53b75a65b6ac5218911e24a02 +size 45701 diff --git a/selfdrive/assets/icons_mici/onroad/turn_signal_right.png b/selfdrive/assets/icons_mici/onroad/turn_signal_right.png index 87ca979fbe..6bcb68dac5 100644 --- a/selfdrive/assets/icons_mici/onroad/turn_signal_right.png +++ b/selfdrive/assets/icons_mici/onroad/turn_signal_right.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:009005539f14acc29a4f5510b4e9531d2ba3667133644f6e0069c12b08ba0fd9 -size 35370 +oid sha256:7fae4872ab3c24d5e4c2be6150127a844f89bbdcadfccdff2dfed180e125d577 +size 45699 diff --git a/selfdrive/assets/icons_mici/settings.png b/selfdrive/assets/icons_mici/settings.png index e668ed1fe4..4ba7df9fdf 100644 --- a/selfdrive/assets/icons_mici/settings.png +++ b/selfdrive/assets/icons_mici/settings.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:38a52171bdc6feb3ddfd2d9f9e59db3dabd09fa0aafbc9f81137c59bd03b7c26 -size 2321 +oid sha256:14b457d2dc19d8658f525cc6989c9cfcf0edaf695b18767514242acbdbe2a6dd +size 2198 diff --git a/selfdrive/assets/icons_mici/settings/comma_icon.png b/selfdrive/assets/icons_mici/settings/comma_icon.png index 72a7c8c8f9..dd38a8938f 100644 --- a/selfdrive/assets/icons_mici/settings/comma_icon.png +++ b/selfdrive/assets/icons_mici/settings/comma_icon.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:10f469a6f5d25d9e2b0b1aae51b4fbd06d2c7b8417613bb321c2a30bb7298dab -size 1392 +oid sha256:7ad4ee47ec6470f788a026f95ed86bf344f64f9cf3186c9c78927233d2694a1d +size 1388 diff --git a/selfdrive/assets/icons_mici/settings/developer/ssh.png b/selfdrive/assets/icons_mici/settings/developer/ssh.png index cd86937aea..0f17d04eca 100644 --- a/selfdrive/assets/icons_mici/settings/developer/ssh.png +++ b/selfdrive/assets/icons_mici/settings/developer/ssh.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:c655994336b7da4ca986c6f27494bcab66e77f016ec9db8df271de53ed93e517 -size 1328 +oid sha256:b26133bee089627202d5e89a4e939ad23aaceb5d8e26d7381b1aea3ef892f2ee +size 2620 diff --git a/selfdrive/assets/icons_mici/settings/developer_icon.png b/selfdrive/assets/icons_mici/settings/developer_icon.png index af16c02912..f9d553c7c3 100644 --- a/selfdrive/assets/icons_mici/settings/developer_icon.png +++ b/selfdrive/assets/icons_mici/settings/developer_icon.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:a1f058c5640bd763d2f6927432a1daff1587770ea0d06f2e351a28462e9d8335 -size 1743 +oid sha256:ebb4f7ad9fd2f9fb3c69a38fbc00cbe690809b0ff202ffd4768ae5b699acc035 +size 1759 diff --git a/selfdrive/assets/icons_mici/settings/device/cameras.png b/selfdrive/assets/icons_mici/settings/device/cameras.png index c44c511275..ae9a88c4dc 100644 --- a/selfdrive/assets/icons_mici/settings/device/cameras.png +++ b/selfdrive/assets/icons_mici/settings/device/cameras.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:77a1281979f0b50f0e109ead56a88a33b81ef5901dd1a4537eb3fa048e0d90de -size 1345 +oid sha256:5f47e636025e044977f278a35546e0fc971f48fd53c2eeafd3508e95c35f378f +size 3117 diff --git a/selfdrive/assets/icons_mici/settings/device/info.png b/selfdrive/assets/icons_mici/settings/device/info.png index cb16320693..9a29c46d0d 100644 --- a/selfdrive/assets/icons_mici/settings/device/info.png +++ b/selfdrive/assets/icons_mici/settings/device/info.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:2649d36259700d32a0edef878647e76492b1bec2fe34ac8ea806d4e7e4c57855 -size 2668 +oid sha256:66858a5d3302333485fa391f7a9bb3a9b1ab4ae881e7fb47b04c3a4507011c94 +size 2613 diff --git a/selfdrive/assets/icons_mici/settings/device/language.png b/selfdrive/assets/icons_mici/settings/device/language.png index f6d57b3134..d2ef27de36 100644 --- a/selfdrive/assets/icons_mici/settings/device/language.png +++ b/selfdrive/assets/icons_mici/settings/device/language.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:4b982ac1b78b45487490d1dbbffed1f68735f6a35def502e882f706c30683aff -size 3664 +oid sha256:f646263b26de46f79cac836ef6865b0f25ddc91e386b99311723b68bd06693c9 +size 3304 diff --git a/selfdrive/assets/icons_mici/settings/device/lkas.png b/selfdrive/assets/icons_mici/settings/device/lkas.png index 186ea78fb9..80d37d4d5c 100644 --- a/selfdrive/assets/icons_mici/settings/device/lkas.png +++ b/selfdrive/assets/icons_mici/settings/device/lkas.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:ab6aeb6cba94acf948a0ad64a485db00bf1f3de1360ae4c57212f3f083b2bd24 -size 2554 +oid sha256:a05a41e66c7a24d461a4bbcdab0979031e5900e1db270af52ca363f0bed521f5 +size 2028 diff --git a/selfdrive/assets/icons_mici/settings/device/pair.png b/selfdrive/assets/icons_mici/settings/device/pair.png index f072b2363f..807d44335d 100644 --- a/selfdrive/assets/icons_mici/settings/device/pair.png +++ b/selfdrive/assets/icons_mici/settings/device/pair.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:ed671f4ad1523f0e66498af39e6075a0c19842ae05eddd00871a6e48ed3685d7 -size 1594 +oid sha256:678483230831d0a7d3dcad5f067a7b641e5d2ae0db477665dfc6c53a675eba18 +size 1779 diff --git a/selfdrive/assets/icons_mici/settings/device/power.png b/selfdrive/assets/icons_mici/settings/device/power.png index a2de14a4e8..711f1a4ab9 100644 --- a/selfdrive/assets/icons_mici/settings/device/power.png +++ b/selfdrive/assets/icons_mici/settings/device/power.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:5b45645ad9ff27776fdb1caa27827c526cae57f8bd4e23bd1160cb0094121ff2 -size 2338 +oid sha256:a34885e79f42d19b7777dd07e7ab51df344880cb770c48e0baaddb177c2ae938 +size 2228 diff --git a/selfdrive/assets/icons_mici/settings/device/reboot.png b/selfdrive/assets/icons_mici/settings/device/reboot.png index 6c89cd9fc2..298a85c504 100644 --- a/selfdrive/assets/icons_mici/settings/device/reboot.png +++ b/selfdrive/assets/icons_mici/settings/device/reboot.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:f24039f82d7399d02a155022de65b6dc3b8edcf17059a73a9fd3a9209e3f5575 -size 2360 +oid sha256:1356fe3ddda14568e9be1dca4e16ca9048852e3a27a3f531cd58d7d368485a82 +size 2362 diff --git a/selfdrive/assets/icons_mici/settings/device/uninstall.png b/selfdrive/assets/icons_mici/settings/device/uninstall.png index f9173711eb..53f8bc0e7d 100644 --- a/selfdrive/assets/icons_mici/settings/device/uninstall.png +++ b/selfdrive/assets/icons_mici/settings/device/uninstall.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:558ea538fb258079f9eb05fe048b2806c7635b9f0452af874b00cb8d79b45f9b -size 2421 +oid sha256:50a8ce4fa8ff7f5b0f56ba0dc65b4802dc0be2dc0967b5cb3a15e3b79a4e513e +size 2424 diff --git a/selfdrive/assets/icons_mici/settings/device/up_to_date.png b/selfdrive/assets/icons_mici/settings/device/up_to_date.png index ee925458d3..e09f7d3308 100644 --- a/selfdrive/assets/icons_mici/settings/device/up_to_date.png +++ b/selfdrive/assets/icons_mici/settings/device/up_to_date.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:4510e65775c6001758ebcf4dc13e9fa561cce5159d1fd54fbb506f22d3c7bdf3 -size 3149 +oid sha256:61bc44b6e0f99640434d6abcb64880c7bf575eda5cdcf7d74cba7d73307dd39a +size 2739 diff --git a/selfdrive/assets/icons_mici/settings/device/update.png b/selfdrive/assets/icons_mici/settings/device/update.png index cc05931b03..498c066191 100644 --- a/selfdrive/assets/icons_mici/settings/device/update.png +++ b/selfdrive/assets/icons_mici/settings/device/update.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:c6137349218ea22adba44f46a096afe2efc35536b2251192ed0ea61be443a3c5 -size 2493 +oid sha256:f28cdeaba9146521335bc11ad60a8e0368eb0ed1381e88b35a12a6138ba22ed6 +size 2409 diff --git a/selfdrive/assets/icons_mici/settings/device_icon.png b/selfdrive/assets/icons_mici/settings/device_icon.png index 0caf0d07ce..6a716e4dfd 100644 --- a/selfdrive/assets/icons_mici/settings/device_icon.png +++ b/selfdrive/assets/icons_mici/settings/device_icon.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:db20bea98259b204be634ce0d9a23fbfdcfc73a324fc0aac0f9ac54e1c51556d -size 2443 +oid sha256:2273629450aa870f0964dd285721c35d3d313fb8b4684122215a65844ae744d0 +size 1888 diff --git a/selfdrive/assets/icons_mici/settings/firehose.png b/selfdrive/assets/icons_mici/settings/firehose.png new file mode 100644 index 0000000000..37451c0482 --- /dev/null +++ b/selfdrive/assets/icons_mici/settings/firehose.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:416656861380981acc114e5285b448d6e4dc42b98539d0ba16821cbc3db89208 +size 1364 diff --git a/selfdrive/assets/icons_mici/settings/keyboard/backspace.png b/selfdrive/assets/icons_mici/settings/keyboard/backspace.png index 342f8e28da..53ff00c2ae 100644 --- a/selfdrive/assets/icons_mici/settings/keyboard/backspace.png +++ b/selfdrive/assets/icons_mici/settings/keyboard/backspace.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:116bbbd1509e6644f7b65b8dacd2402b0918785bd80207504a99ab7e13ab738f -size 2049 +oid sha256:69bb4a401429c3fdf473778f751288b2aafea27eb13f09b20e83d55212f084ba +size 1963 diff --git a/selfdrive/assets/icons_mici/settings/keyboard/caps_lock.png b/selfdrive/assets/icons_mici/settings/keyboard/caps_lock.png index d63cc56fbc..2d173bfc9f 100644 --- a/selfdrive/assets/icons_mici/settings/keyboard/caps_lock.png +++ b/selfdrive/assets/icons_mici/settings/keyboard/caps_lock.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3e8c7fec57640de6bfa8d0ede977e40920a8e651b68ed14e3d6c1850e702f3e3 -size 1399 +oid sha256:563c211fd98018e24418235602e596f3a481f04fddde0a14590e563474fcffd2 +size 1423 diff --git a/selfdrive/assets/icons_mici/settings/keyboard/caps_lower.png b/selfdrive/assets/icons_mici/settings/keyboard/caps_lower.png index eb38934302..a3ce71f049 100644 --- a/selfdrive/assets/icons_mici/settings/keyboard/caps_lower.png +++ b/selfdrive/assets/icons_mici/settings/keyboard/caps_lower.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:b7dab3af28938e9c3ad7b6c3b60526bb76498b0103c7276d90c4bff3622f07d0 -size 1157 +oid sha256:6f81811ea9cdc409d5549035ca928c76e22396193e1cefb6cacab3747ee0c297 +size 1142 diff --git a/selfdrive/assets/icons_mici/settings/keyboard/caps_upper.png b/selfdrive/assets/icons_mici/settings/keyboard/caps_upper.png index 4a2cae6c8a..7c147bc07b 100644 --- a/selfdrive/assets/icons_mici/settings/keyboard/caps_upper.png +++ b/selfdrive/assets/icons_mici/settings/keyboard/caps_upper.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:0c5a88a0e8e810115b6d497d3e230d866bd96a715ddac632f48c78b40e1df702 -size 1059 +oid sha256:60875e73dd9659122c9248d8e99d5cfd301d68dabeec2cb42cebce812c9baae9 +size 1102 diff --git a/selfdrive/assets/icons_mici/settings/keyboard/confirm.png b/selfdrive/assets/icons_mici/settings/keyboard/confirm.png index 09b180e97f..98ca5c61dc 100644 --- a/selfdrive/assets/icons_mici/settings/keyboard/confirm.png +++ b/selfdrive/assets/icons_mici/settings/keyboard/confirm.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:32ce109a9fe4814bb9bed88f67d85292791f4a6d7c162e07561920221ac38b2d -size 1411 +oid sha256:43b64365a42d7bf772d567b8867a6ced4ec0175bb88b6acaa3a5345f19ca696e +size 1268 diff --git a/selfdrive/assets/icons_mici/settings/keyboard/space.png b/selfdrive/assets/icons_mici/settings/keyboard/space.png index 778d1847d7..3d61109721 100644 --- a/selfdrive/assets/icons_mici/settings/keyboard/space.png +++ b/selfdrive/assets/icons_mici/settings/keyboard/space.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:9b04d17f3b0340a94210efa5c9547e0ac340dd6b6dd9ac1f81ba5eb3f89f405d -size 619 +oid sha256:f431e428772991323ee3ce662479e1ab29c3d80a72b93cf9c9673716ba245d5f +size 654 diff --git a/selfdrive/assets/icons_mici/settings/manual_icon.png b/selfdrive/assets/icons_mici/settings/manual_icon.png deleted file mode 100644 index 100b29da45..0000000000 --- a/selfdrive/assets/icons_mici/settings/manual_icon.png +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:957330e9fbc8c03f05dbef8097178a40efc0fc52a6faf7a9917f97046d9a5e99 -size 1559 diff --git a/selfdrive/assets/icons_mici/settings/network/cell_strength_full.png b/selfdrive/assets/icons_mici/settings/network/cell_strength_full.png index 4bf0cd8726..13f70386d4 100644 --- a/selfdrive/assets/icons_mici/settings/network/cell_strength_full.png +++ b/selfdrive/assets/icons_mici/settings/network/cell_strength_full.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:6a981d5c5558859b283cb6321c84eec947f82fc2dea8dbdd19b66781e4d3f61f -size 1060 +oid sha256:fb7af523411c5ed75c6e1418dfc2a379486f6dbd7f2f1c281d3ff54e1ea7810e +size 777 diff --git a/selfdrive/assets/icons_mici/settings/network/cell_strength_high.png b/selfdrive/assets/icons_mici/settings/network/cell_strength_high.png index df6d009335..1fea6d23b8 100644 --- a/selfdrive/assets/icons_mici/settings/network/cell_strength_high.png +++ b/selfdrive/assets/icons_mici/settings/network/cell_strength_high.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:58da16ede432cf89096c11dc0f4ea098735863fb09a1d655cb06de8a112bd263 -size 1205 +oid sha256:db86e176e016458fcff00d40e37636a808977e0cc01bcc9c04b31a1001562de8 +size 936 diff --git a/selfdrive/assets/icons_mici/settings/network/cell_strength_low.png b/selfdrive/assets/icons_mici/settings/network/cell_strength_low.png index c3323a9fea..d763f86c7f 100644 --- a/selfdrive/assets/icons_mici/settings/network/cell_strength_low.png +++ b/selfdrive/assets/icons_mici/settings/network/cell_strength_low.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:031bbd50c34d8fd5e71bdc292ba3e50b28a13c56a48dc84117723f1b35b42f51 -size 1224 +oid sha256:1cd0b3a00db36ee7eacf5887d07d40e5351fb441d98643a02df4c742cd1e935d +size 945 diff --git a/selfdrive/assets/icons_mici/settings/network/cell_strength_medium.png b/selfdrive/assets/icons_mici/settings/network/cell_strength_medium.png index 64ab947c53..148ee63e99 100644 --- a/selfdrive/assets/icons_mici/settings/network/cell_strength_medium.png +++ b/selfdrive/assets/icons_mici/settings/network/cell_strength_medium.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:ccb5f2227c72dd28e40c9f19965abe007cbd7b47cdca924907dc9fad906f5c81 -size 1219 +oid sha256:25724acfe0c261070b103ef5933053d5dd8b726ece42d0e5f715f05c67be2294 +size 956 diff --git a/selfdrive/assets/icons_mici/settings/network/cell_strength_none.png b/selfdrive/assets/icons_mici/settings/network/cell_strength_none.png index 6cdef706bd..c6d82ac316 100644 --- a/selfdrive/assets/icons_mici/settings/network/cell_strength_none.png +++ b/selfdrive/assets/icons_mici/settings/network/cell_strength_none.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:92c195721fe2b4ca42176077bf4ca3484cdfc314e961f1431b2296476bcae891 -size 1178 +oid sha256:cb0aeb6260bcd0642204f842112479f4b19b350db9addae5e14c9c5131bcf956 +size 781 diff --git a/selfdrive/assets/icons_mici/settings/network/new/lock.png b/selfdrive/assets/icons_mici/settings/network/new/lock.png index 0a0b18c7a9..9fc152d3db 100644 --- a/selfdrive/assets/icons_mici/settings/network/new/lock.png +++ b/selfdrive/assets/icons_mici/settings/network/new/lock.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:40dbbb3000e1137ec11fe658fbfebae7cadfc91356953317335f9bb70fcb40d3 -size 1235 +oid sha256:782161f35b4925c7063c441b0c341331c814614cf241f21b4e70134280c630f0 +size 1182 diff --git a/selfdrive/assets/icons_mici/settings/network/new/trash.png b/selfdrive/assets/icons_mici/settings/network/new/trash.png index 99e1a2e246..81e5f13e43 100644 --- a/selfdrive/assets/icons_mici/settings/network/new/trash.png +++ b/selfdrive/assets/icons_mici/settings/network/new/trash.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:efabf98ed66fe4447c0f13c74aec681b084de780c551ce18258c79636d4123c5 -size 1524 +oid sha256:9074162bf0469fc5ab0b5711a121289a983c887161df269ac120edd8fd024499 +size 1533 diff --git a/selfdrive/assets/icons_mici/settings/network/tethering.png b/selfdrive/assets/icons_mici/settings/network/tethering.png index 9e7b90be41..4bb416b0b1 100644 --- a/selfdrive/assets/icons_mici/settings/network/tethering.png +++ b/selfdrive/assets/icons_mici/settings/network/tethering.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:2907ce46d1b6e676402f390c530955b65e76baf0b77fafc0616c50b988b3994c -size 1609 +oid sha256:b1e322ea6e57b05b3515fcd4e9100f890e6ff80607c11360b7927fa5a9765beb +size 2752 diff --git a/selfdrive/assets/icons_mici/settings/network/wifi_strength_full.png b/selfdrive/assets/icons_mici/settings/network/wifi_strength_full.png index 1a1655fddc..fe81ffa572 100644 --- a/selfdrive/assets/icons_mici/settings/network/wifi_strength_full.png +++ b/selfdrive/assets/icons_mici/settings/network/wifi_strength_full.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:f2715ea698eccb3648ab96cbddf897ea1842acbc1eb9667bc6f34aba82d0896b -size 1976 +oid sha256:73c76e5240bdff64c1d1ed0ac2bb9c3fadb2fd61fbf8dc710b812757af8bcf6c +size 2026 diff --git a/selfdrive/assets/icons_mici/settings/network/wifi_strength_low.png b/selfdrive/assets/icons_mici/settings/network/wifi_strength_low.png index 4d64d8062f..2649cc89dc 100644 --- a/selfdrive/assets/icons_mici/settings/network/wifi_strength_low.png +++ b/selfdrive/assets/icons_mici/settings/network/wifi_strength_low.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:58d839402c6f002ba8d2217888190b338fc3ac13d372df0988fac7bf95b89302 -size 2111 +oid sha256:e66cc6174a54177793c42ef3525a9aa1592e05b0abb677442c7226269d1371a5 +size 2196 diff --git a/selfdrive/assets/icons_mici/settings/network/wifi_strength_medium.png b/selfdrive/assets/icons_mici/settings/network/wifi_strength_medium.png index 2d53a20cef..8881833375 100644 --- a/selfdrive/assets/icons_mici/settings/network/wifi_strength_medium.png +++ b/selfdrive/assets/icons_mici/settings/network/wifi_strength_medium.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:a9918724409dbfa1973a097a692c2f57e45cc2bc0ce71c498ef3e02aa82559d3 -size 2128 +oid sha256:7948a9234f2bc996aefb3a9e58a37c06ebbf54e8e4596e47800f78ef7e81961f +size 2231 diff --git a/selfdrive/assets/icons_mici/settings/network/wifi_strength_none.png b/selfdrive/assets/icons_mici/settings/network/wifi_strength_none.png index 482a0e1042..848d7849a2 100644 --- a/selfdrive/assets/icons_mici/settings/network/wifi_strength_none.png +++ b/selfdrive/assets/icons_mici/settings/network/wifi_strength_none.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3fcef95eb18e2db566b907ae99b8d8f450424b3b7823fdc24cdfe066ccf64378 -size 2141 +oid sha256:a57ea402448dacc2026631174e448b6254698fe92309221576400cbf28196936 +size 2195 diff --git a/selfdrive/assets/icons_mici/settings/network/wifi_strength_slash.png b/selfdrive/assets/icons_mici/settings/network/wifi_strength_slash.png index 38ddff84b7..4457a3fcd2 100644 --- a/selfdrive/assets/icons_mici/settings/network/wifi_strength_slash.png +++ b/selfdrive/assets/icons_mici/settings/network/wifi_strength_slash.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:73e4ae4741a039f41d79827c40be6da83f8c6eb79e9103db2dfec718ca96efb7 -size 2512 +oid sha256:7e6d166bdbbcdc106e7cd4a44ba85848888f18a6ef34e86daac8e12a3f519443 +size 2318 diff --git a/selfdrive/assets/icons_mici/settings/toggles_icon.png b/selfdrive/assets/icons_mici/settings/toggles_icon.png deleted file mode 100644 index ccb343e8ed..0000000000 --- a/selfdrive/assets/icons_mici/settings/toggles_icon.png +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:0297535eb73bea71e87c363dc12385bb9163b81403797e50966b20259f725542 -size 2528 diff --git a/selfdrive/assets/icons_mici/setup/back_new.png b/selfdrive/assets/icons_mici/setup/back_new.png index c4834a5649..20e7fe3b88 100644 --- a/selfdrive/assets/icons_mici/setup/back_new.png +++ b/selfdrive/assets/icons_mici/setup/back_new.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:7198352d23952d0f2fbc128f20523ea6f2f2b7e378aa495da748a0e34f192806 -size 1641 +oid sha256:d29a9c295b33b3164c37a68ad77795595e6ac877a5b308d28112b0315ecd498f +size 1687 diff --git a/selfdrive/assets/icons_mici/setup/driver_monitoring/dm_check.png b/selfdrive/assets/icons_mici/setup/driver_monitoring/dm_check.png index 92993e3e00..dfb9799b0b 100644 --- a/selfdrive/assets/icons_mici/setup/driver_monitoring/dm_check.png +++ b/selfdrive/assets/icons_mici/setup/driver_monitoring/dm_check.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:5b7dce550c008ff7a65ed19ccf308ecf92cd0118bb544978b7dd7393c5c27ae5 -size 809 +oid sha256:2290105f9b055b3c3d482d883d148de3418cad07b653133b0f61137e1976c407 +size 1412 diff --git a/selfdrive/assets/icons_mici/setup/driver_monitoring/dm_question.png b/selfdrive/assets/icons_mici/setup/driver_monitoring/dm_question.png index 53a837afbe..fa29be1827 100644 --- a/selfdrive/assets/icons_mici/setup/driver_monitoring/dm_question.png +++ b/selfdrive/assets/icons_mici/setup/driver_monitoring/dm_question.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:e102b8b2e71a25d9f818b37d6f75ed958430cb765a07ae50713995779fb6a886 -size 1388 +oid sha256:ec9691d2572e2e084f0b3c99a1dcd0daadf5040d16c02347ffec9dd5466c061a +size 1438 diff --git a/selfdrive/assets/icons_mici/setup/green_car.png b/selfdrive/assets/icons_mici/setup/green_car.png deleted file mode 100644 index 867cadbbd6..0000000000 --- a/selfdrive/assets/icons_mici/setup/green_car.png +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:ce8a34777e0b185f457b98845aa17fe6b5192ca46101463aecd21a9e04c0f0f0 -size 13281 diff --git a/selfdrive/assets/icons_mici/setup/green_dm.png b/selfdrive/assets/icons_mici/setup/green_dm.png index d41edd4c2a..87f4ffe788 100644 --- a/selfdrive/assets/icons_mici/setup/green_dm.png +++ b/selfdrive/assets/icons_mici/setup/green_dm.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:78795eaa5e0be5fa369e172c02f5bd4b06d20f44363ccb8cbd02cb181b13e529 -size 14289 +oid sha256:8b6d7747dd6bbf47d9782fc0d847c224b933f6616218ade1f9220018aa9d6acc +size 15052 diff --git a/selfdrive/assets/icons_mici/setup/green_info.png b/selfdrive/assets/icons_mici/setup/green_info.png index 309e56e6ee..57e005abd6 100644 --- a/selfdrive/assets/icons_mici/setup/green_info.png +++ b/selfdrive/assets/icons_mici/setup/green_info.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:2b0b1777d5bed7149982af9f2abab3fab7b6c576e3d53cf2c459804c6ec9ca1e -size 3957 +oid sha256:5055bc385a1de674e6f3cbafdb611ee4b1088de2a3c357bce76f6a192226c952 +size 14154 diff --git a/selfdrive/assets/icons_mici/setup/green_pedal.png b/selfdrive/assets/icons_mici/setup/green_pedal.png deleted file mode 100644 index 2dd18f489a..0000000000 --- a/selfdrive/assets/icons_mici/setup/green_pedal.png +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:6cadcda59bc861a1e710e0a8ac67024bdcc44b5f9261abbf098ff11cefb1da51 -size 12209 diff --git a/selfdrive/assets/icons_mici/setup/orange_dm.png b/selfdrive/assets/icons_mici/setup/orange_dm.png index 74cce9d975..97df767a98 100644 --- a/selfdrive/assets/icons_mici/setup/orange_dm.png +++ b/selfdrive/assets/icons_mici/setup/orange_dm.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:38a108f96f85a154b698693b07f2e4214124b8f2545b7c4490cea0aa998d75fd -size 11855 +oid sha256:9c45ab0b949c1c71651f9f48cf6ff10196d64eb85e042b063e92b1d7ca02dcb5 +size 13155 diff --git a/selfdrive/assets/icons_mici/setup/red_warning.png b/selfdrive/assets/icons_mici/setup/red_warning.png index ed0634079b..387794cf13 100644 --- a/selfdrive/assets/icons_mici/setup/red_warning.png +++ b/selfdrive/assets/icons_mici/setup/red_warning.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:448d3e7214a77b02b32020ddb440ccd8fe72e110493a51cc10901c8242e72ca8 -size 3185 +oid sha256:e8e8bc3c15df7512a81b902e47fb069eff1370c833095d3b25f3866efb815fff +size 11123 diff --git a/selfdrive/assets/icons_mici/setup/restore.png b/selfdrive/assets/icons_mici/setup/restore.png index 6aa6c6b851..5eff924040 100644 --- a/selfdrive/assets/icons_mici/setup/restore.png +++ b/selfdrive/assets/icons_mici/setup/restore.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:9d6b99696163cac1867d46998af9e53e212b82641b33c93b51276671f400a5ac -size 2962 +oid sha256:1f5ee67cd334d259ac33f932281db36533877009b5769c92d9cff3054fd5627c +size 2942 diff --git a/selfdrive/assets/icons_mici/setup/scroll_down_indicator.png b/selfdrive/assets/icons_mici/setup/scroll_down_indicator.png index 4d74d86075..3cd26e5181 100644 --- a/selfdrive/assets/icons_mici/setup/scroll_down_indicator.png +++ b/selfdrive/assets/icons_mici/setup/scroll_down_indicator.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:52535e34e27b0341f7690a72dc16555eeb6e032bc2c2cde0786469852fdf5987 -size 1267 +oid sha256:a733c425113a7f6ff5ec3dc50ef94b5481c0f2d306e33d1485be8ee6b2798532 +size 1136 diff --git a/selfdrive/assets/icons_mici/setup/small_slider/slider_arrow.png b/selfdrive/assets/icons_mici/setup/small_slider/slider_arrow.png index bbf1d96254..acf5b17414 100644 --- a/selfdrive/assets/icons_mici/setup/small_slider/slider_arrow.png +++ b/selfdrive/assets/icons_mici/setup/small_slider/slider_arrow.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:8425c56cb413ba757c94febe0332ce472dbf1472236b03cc4e627746fb86d701 -size 1149 +oid sha256:75a6557935075a646b17d083202832daafb263d4cfa38aea2af407afc04e2ef4 +size 1312 diff --git a/selfdrive/assets/icons_mici/setup/warning.png b/selfdrive/assets/icons_mici/setup/warning.png index 806eea28b7..1b7839f47f 100644 --- a/selfdrive/assets/icons_mici/setup/warning.png +++ b/selfdrive/assets/icons_mici/setup/warning.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3bc7a85a0672183d80817f337084060465e143362037955025c11bc8ac531076 -size 3247 +oid sha256:7584d32ac0231381e38646fdac2f71b4517905ef22024f01bd9e124d3918f33a +size 9194 diff --git a/selfdrive/assets/icons_mici/ssh_short.png b/selfdrive/assets/icons_mici/ssh_short.png new file mode 100644 index 0000000000..699ddd72e8 --- /dev/null +++ b/selfdrive/assets/icons_mici/ssh_short.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ef1735e6effcb625ea618fa35a6b908b28ca483d5997e15241d48e2d3d29819e +size 1433 diff --git a/selfdrive/assets/icons_mici/tethering_short.png b/selfdrive/assets/icons_mici/tethering_short.png new file mode 100644 index 0000000000..f97fed95de --- /dev/null +++ b/selfdrive/assets/icons_mici/tethering_short.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:fce940a3cbd2e9530e8efdde90794013a272919b2f3ea482bc06535c795640e7 +size 2176 diff --git a/selfdrive/assets/icons_mici/turn_intent_left.png b/selfdrive/assets/icons_mici/turn_intent_left.png index 6c2c47e882..3934200c9d 100644 --- a/selfdrive/assets/icons_mici/turn_intent_left.png +++ b/selfdrive/assets/icons_mici/turn_intent_left.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:ead8287b7041c32456e13721c238a71933256ca3d2b7e649c8f8731585eb5de8 -size 906 +oid sha256:001cb8227eaaff5367055395d9b3ccd5822f9a47276091832d8ad28b074d77c9 +size 914 diff --git a/selfdrive/assets/icons_mici/turn_intent_right.png b/selfdrive/assets/icons_mici/turn_intent_right.png index 03a7245e76..e342778731 100644 --- a/selfdrive/assets/icons_mici/turn_intent_right.png +++ b/selfdrive/assets/icons_mici/turn_intent_right.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:6fe0532f7040aae78baa85c4cca44f5c939adb6a6f15889e2ca036f4a493f848 -size 935 +oid sha256:7b7e0194a8b9009e493cdce35cd15711596a54227c740e9d6419a3891c6c4037 +size 912 diff --git a/selfdrive/assets/icons_mici/wheel.png b/selfdrive/assets/icons_mici/wheel.png index f122349b82..a43bcb3b99 100644 --- a/selfdrive/assets/icons_mici/wheel.png +++ b/selfdrive/assets/icons_mici/wheel.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:cc3ef0c8c3038d75f99df2c565a361107bc903944d1afe91de0cbed9f6ca062a -size 2725 +oid sha256:8cf9c6361ed82551eb99e028e0a75ff56b72ca856ccf7c9a76afe6745434980a +size 2720 diff --git a/selfdrive/assets/icons_mici/wheel_critical.png b/selfdrive/assets/icons_mici/wheel_critical.png index c0e5e8619e..676b0b4d71 100644 --- a/selfdrive/assets/icons_mici/wheel_critical.png +++ b/selfdrive/assets/icons_mici/wheel_critical.png @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:12783dc05ea6dae2647ac3a3a7c8391d520c3f0cf2f458333a357ee9633eb6c4 -size 10909 +oid sha256:4c3d9082b295f9e5ddef93f8d4e9cb961ea2374c7affd26394bbccb26e7137b2 +size 11023 diff --git a/selfdrive/ui/mici/layouts/home.py b/selfdrive/ui/mici/layouts/home.py index 9152bdc7fa..f5dab7249a 100644 --- a/selfdrive/ui/mici/layouts/home.py +++ b/selfdrive/ui/mici/layouts/home.py @@ -92,22 +92,22 @@ class MiciHomeLayout(Widget): self._settings_txt = gui_app.texture("icons_mici/settings.png", 48, 48) self._experimental_txt = gui_app.texture("icons_mici/experimental_mode.png", 48, 48) - self._mic_txt = gui_app.texture("icons_mici/microphone.png", 48, 48) + self._mic_txt = gui_app.texture("icons_mici/microphone.png", 32, 46) self._net_type = NETWORK_TYPES.get(NetworkType.none) self._net_strength = 0 self._wifi_slash_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_slash.png", 50, 44) - self._wifi_none_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_none.png", 50, 44) - self._wifi_low_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_low.png", 50, 44) - self._wifi_medium_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_medium.png", 50, 44) - self._wifi_full_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_full.png", 50, 44) + self._wifi_none_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_none.png", 50, 37) + self._wifi_low_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_low.png", 50, 37) + self._wifi_medium_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_medium.png", 50, 37) + self._wifi_full_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_full.png", 50, 37) - self._cell_none_txt = gui_app.texture("icons_mici/settings/network/cell_strength_none.png", 55, 35) - self._cell_low_txt = gui_app.texture("icons_mici/settings/network/cell_strength_low.png", 55, 35) - self._cell_medium_txt = gui_app.texture("icons_mici/settings/network/cell_strength_medium.png", 55, 35) - self._cell_high_txt = gui_app.texture("icons_mici/settings/network/cell_strength_high.png", 55, 35) - self._cell_full_txt = gui_app.texture("icons_mici/settings/network/cell_strength_full.png", 55, 35) + self._cell_none_txt = gui_app.texture("icons_mici/settings/network/cell_strength_none.png", 54, 36) + self._cell_low_txt = gui_app.texture("icons_mici/settings/network/cell_strength_low.png", 54, 36) + self._cell_medium_txt = gui_app.texture("icons_mici/settings/network/cell_strength_medium.png", 54, 36) + self._cell_high_txt = gui_app.texture("icons_mici/settings/network/cell_strength_high.png", 54, 36) + self._cell_full_txt = gui_app.texture("icons_mici/settings/network/cell_strength_full.png", 54, 36) self._openpilot_label = MiciLabel("openpilot", font_size=96, color=rl.Color(255, 255, 255, int(255 * 0.9)), font_weight=FontWeight.DISPLAY) self._version_label = MiciLabel("", font_size=36, font_weight=FontWeight.ROMAN) diff --git a/selfdrive/ui/mici/layouts/onboarding.py b/selfdrive/ui/mici/layouts/onboarding.py index 16e96d6f7d..4248fef2ec 100644 --- a/selfdrive/ui/mici/layouts/onboarding.py +++ b/selfdrive/ui/mici/layouts/onboarding.py @@ -124,9 +124,9 @@ class TrainingGuideDMTutorial(Widget): def __init__(self, continue_callback): super().__init__() - self._back_button = SmallCircleIconButton(gui_app.texture("icons_mici/setup/driver_monitoring/dm_question.png", 48, 48)) + self._back_button = SmallCircleIconButton(gui_app.texture("icons_mici/setup/driver_monitoring/dm_question.png", 28, 48)) self._back_button.set_click_callback(self._show_bad_face_page) - self._good_button = SmallCircleIconButton(gui_app.texture("icons_mici/setup/driver_monitoring/dm_check.png", 48, 35)) + self._good_button = SmallCircleIconButton(gui_app.texture("icons_mici/setup/driver_monitoring/dm_check.png", 42, 42)) # Wrap the continue callback to restore settings def wrapped_continue_callback(): diff --git a/selfdrive/ui/mici/layouts/settings/developer.py b/selfdrive/ui/mici/layouts/settings/developer.py index 8fc63e8963..b6145e042e 100644 --- a/selfdrive/ui/mici/layouts/settings/developer.py +++ b/selfdrive/ui/mici/layouts/settings/developer.py @@ -3,7 +3,7 @@ from collections.abc import Callable from openpilot.common.time_helpers import system_time_valid from openpilot.system.ui.widgets.scroller import Scroller -from openpilot.selfdrive.ui.mici.widgets.button import BigButton, BigToggle, BigParamControl +from openpilot.selfdrive.ui.mici.widgets.button import BigButton, BigToggle, BigParamControl, BigCircleParamControl from openpilot.selfdrive.ui.mici.widgets.dialog import BigDialog, BigInputDialog from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.widgets import NavWidget @@ -36,15 +36,15 @@ class DeveloperLayoutMici(NavWidget): return gui_app.set_modal_overlay(dlg) - txt_ssh = gui_app.texture("icons_mici/settings/developer/ssh.png", 77, 44) + txt_ssh = gui_app.texture("icons_mici/settings/developer/ssh.png", 56, 64) github_username = ui_state.params.get("GithubUsername") or "" self._ssh_keys_btn = BigButton("SSH keys", "Not set" if not github_username else github_username, icon=txt_ssh) self._ssh_keys_btn.set_click_callback(ssh_keys_callback) # adb, ssh, ssh keys, debug mode, joystick debug mode, longitudinal maneuver mode, ip address # ******** Main Scroller ******** - self._adb_toggle = BigParamControl("enable ADB", "AdbEnabled") - self._ssh_toggle = BigParamControl("enable SSH", "SshEnabled") + self._adb_toggle = BigCircleParamControl("icons_mici/adb_short.png", "AdbEnabled", icon_size=(82, 82), icon_offset=(0, 12)) + self._ssh_toggle = BigCircleParamControl("icons_mici/ssh_short.png", "SshEnabled", icon_size=(82, 82), icon_offset=(0, 12)) self._joystick_toggle = BigToggle("joystick debug mode", initial_state=ui_state.params.get_bool("JoystickDebugMode"), toggle_callback=self._on_joystick_debug_mode) diff --git a/selfdrive/ui/mici/layouts/settings/device.py b/selfdrive/ui/mici/layouts/settings/device.py index 988c823a99..30ea90f3d1 100644 --- a/selfdrive/ui/mici/layouts/settings/device.py +++ b/selfdrive/ui/mici/layouts/settings/device.py @@ -119,7 +119,7 @@ class UpdaterState(IntEnum): class PairBigButton(BigButton): def __init__(self): - super().__init__("pair", "connect.comma.ai", "icons_mici/settings/comma_icon.png") + super().__init__("pair", "connect.comma.ai", "icons_mici/settings/comma_icon.png", icon_size=(33, 60)) def _update_state(self): if ui_state.prime_state.is_paired(): @@ -153,8 +153,8 @@ UPDATER_TIMEOUT = 10.0 # seconds to wait for updater to respond class UpdateOpenpilotBigButton(BigButton): def __init__(self): - self._txt_update_icon = gui_app.texture("icons_mici/settings/device/update.png", 64, 64) - self._txt_reboot_icon = gui_app.texture("icons_mici/settings/device/reboot.png", 64, 64) + self._txt_update_icon = gui_app.texture("icons_mici/settings/device/update.png", 64, 75) + self._txt_reboot_icon = gui_app.texture("icons_mici/settings/device/reboot.png", 64, 70) self._txt_up_to_date_icon = gui_app.texture("icons_mici/settings/device/up_to_date.png", 64, 64) super().__init__("update openpilot", "", self._txt_update_icon) @@ -291,16 +291,16 @@ class DeviceLayoutMici(NavWidget): def uninstall_openpilot_callback(): ui_state.params.put_bool("DoUninstall", True) - reset_calibration_btn = BigButton("reset calibration", "", "icons_mici/settings/device/lkas.png") + reset_calibration_btn = BigButton("reset calibration", "", "icons_mici/settings/device/lkas.png", icon_size=(114, 60)) reset_calibration_btn.set_click_callback(lambda: _engaged_confirmation_callback(reset_calibration_callback, "reset")) uninstall_openpilot_btn = BigButton("uninstall openpilot", "", "icons_mici/settings/device/uninstall.png") uninstall_openpilot_btn.set_click_callback(lambda: _engaged_confirmation_callback(uninstall_openpilot_callback, "uninstall")) - reboot_btn = BigCircleButton("icons_mici/settings/device/reboot.png", red=False) + reboot_btn = BigCircleButton("icons_mici/settings/device/reboot.png", red=False, icon_size=(64, 70)) reboot_btn.set_click_callback(lambda: _engaged_confirmation_callback(reboot_callback, "reboot")) - self._power_off_btn = BigCircleButton("icons_mici/settings/device/power.png", red=True) + self._power_off_btn = BigCircleButton("icons_mici/settings/device/power.png", red=True, icon_size=(64, 66)) self._power_off_btn.set_click_callback(lambda: _engaged_confirmation_callback(power_off_callback, "power off")) self._load_languages() diff --git a/selfdrive/ui/mici/layouts/settings/network/__init__.py b/selfdrive/ui/mici/layouts/settings/network/__init__.py index 1faf49311a..0d5e527836 100644 --- a/selfdrive/ui/mici/layouts/settings/network/__init__.py +++ b/selfdrive/ui/mici/layouts/settings/network/__init__.py @@ -4,7 +4,7 @@ from collections.abc import Callable from openpilot.system.ui.widgets.scroller import Scroller from openpilot.selfdrive.ui.mici.layouts.settings.network.wifi_ui import WifiUIMici -from openpilot.selfdrive.ui.mici.widgets.button import BigButton, BigMultiToggle, BigToggle, BigParamControl +from openpilot.selfdrive.ui.mici.widgets.button import BigButton, BigMultiToggle, BigParamControl, BigCircleToggle from openpilot.selfdrive.ui.mici.widgets.dialog import BigInputDialog from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.lib.prime_state import PrimeType @@ -33,15 +33,14 @@ class NetworkLayoutMici(NavWidget): networks_updated=self._on_network_updated, ) - _tethering_icon = "icons_mici/settings/network/tethering.png" - # ******** Tethering ******** def tethering_toggle_callback(checked: bool): self._tethering_toggle_btn.set_enabled(False) self._network_metered_btn.set_enabled(False) self._wifi_manager.set_tethering_active(checked) - self._tethering_toggle_btn = BigToggle("enable tethering", "", toggle_callback=tethering_toggle_callback) + self._tethering_toggle_btn = BigCircleToggle("icons_mici/tethering_short.png", toggle_callback=tethering_toggle_callback, + icon_size=(82, 82), icon_offset=(0, 12)) def tethering_password_callback(password: str): if password: @@ -53,7 +52,7 @@ class NetworkLayoutMici(NavWidget): confirm_callback=tethering_password_callback) gui_app.set_modal_overlay(dlg) - txt_tethering = gui_app.texture(_tethering_icon, 64, 53) + txt_tethering = gui_app.texture("icons_mici/settings/network/tethering.png", 64, 54) self._tethering_password_btn = BigButton("tethering password", "", txt_tethering) self._tethering_password_btn.set_click_callback(tethering_password_clicked) diff --git a/selfdrive/ui/mici/layouts/settings/network/wifi_ui.py b/selfdrive/ui/mici/layouts/settings/network/wifi_ui.py index 565fef5af3..23b89438dc 100644 --- a/selfdrive/ui/mici/layouts/settings/network/wifi_ui.py +++ b/selfdrive/ui/mici/layouts/settings/network/wifi_ui.py @@ -34,12 +34,12 @@ class LoadingAnimation(Widget): class WifiIcon(Widget): def __init__(self): super().__init__() - self.set_rect(rl.Rectangle(0, 0, 89, 64)) + self.set_rect(rl.Rectangle(0, 0, 86, 64)) - self._wifi_low_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_low.png", 89, 64) - self._wifi_medium_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_medium.png", 89, 64) - self._wifi_full_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_full.png", 89, 64) - self._lock_txt = gui_app.texture("icons_mici/settings/network/new/lock.png", 23, 32) + self._wifi_low_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_low.png", 86, 64) + self._wifi_medium_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_medium.png", 86, 64) + self._wifi_full_txt = gui_app.texture("icons_mici/settings/network/wifi_strength_full.png", 86, 64) + self._lock_txt = gui_app.texture("icons_mici/settings/network/new/lock.png", 22, 32) self._network: Network | None = None self._scale = 1.0 @@ -169,7 +169,7 @@ class ForgetButton(Widget): self._bg_txt = gui_app.texture("icons_mici/settings/network/new/forget_button.png", 100, 100) self._bg_pressed_txt = gui_app.texture("icons_mici/settings/network/new/forget_button_pressed.png", 100, 100) - self._trash_txt = gui_app.texture("icons_mici/settings/network/new/trash.png", 32, 36) + self._trash_txt = gui_app.texture("icons_mici/settings/network/new/trash.png", 35, 42) self.set_rect(rl.Rectangle(0, 0, 100 + self.HORIZONTAL_MARGIN * 2, 100)) def _handle_mouse_release(self, mouse_pos: MousePos): diff --git a/selfdrive/ui/mici/layouts/settings/settings.py b/selfdrive/ui/mici/layouts/settings/settings.py index a452777748..3917899032 100644 --- a/selfdrive/ui/mici/layouts/settings/settings.py +++ b/selfdrive/ui/mici/layouts/settings/settings.py @@ -36,16 +36,16 @@ class SettingsLayout(NavWidget): self._params = Params() self._current_panel = None # PanelType.DEVICE - toggles_btn = BigButton("toggles", "", "icons_mici/settings/toggles_icon.png") + toggles_btn = BigButton("toggles", "", "icons_mici/settings.png") toggles_btn.set_click_callback(lambda: self._set_current_panel(PanelType.TOGGLES)) - network_btn = BigButton("network", "", "icons_mici/settings/network/wifi_strength_full.png") + network_btn = BigButton("network", "", "icons_mici/settings/network/wifi_strength_full.png", icon_size=(76, 56)) network_btn.set_click_callback(lambda: self._set_current_panel(PanelType.NETWORK)) - device_btn = BigButton("device", "", "icons_mici/settings/device_icon.png") + device_btn = BigButton("device", "", "icons_mici/settings/device_icon.png", icon_size=(74, 60)) device_btn.set_click_callback(lambda: self._set_current_panel(PanelType.DEVICE)) - developer_btn = BigButton("developer", "", "icons_mici/settings/developer_icon.png") + developer_btn = BigButton("developer", "", "icons_mici/settings/developer_icon.png", icon_size=(64, 60)) developer_btn.set_click_callback(lambda: self._set_current_panel(PanelType.DEVELOPER)) - firehose_btn = BigButton("firehose", "", "icons_mici/settings/comma_icon.png") + firehose_btn = BigButton("firehose", "", "icons_mici/settings/firehose.png", icon_size=(52, 62)) firehose_btn.set_click_callback(lambda: self._set_current_panel(PanelType.FIREHOSE)) self._scroller = Scroller([ diff --git a/selfdrive/ui/mici/onroad/alert_renderer.py b/selfdrive/ui/mici/onroad/alert_renderer.py index 7ee83ff880..64dd04c310 100644 --- a/selfdrive/ui/mici/onroad/alert_renderer.py +++ b/selfdrive/ui/mici/onroad/alert_renderer.py @@ -111,10 +111,10 @@ class AlertRenderer(Widget): self._load_icons() def _load_icons(self): - self._txt_turn_signal_left = gui_app.texture('icons_mici/onroad/turn_signal_left.png', 100, 91) - self._txt_turn_signal_right = gui_app.texture('icons_mici/onroad/turn_signal_right.png', 100, 91) - self._txt_blind_spot_left = gui_app.texture('icons_mici/onroad/blind_spot_left.png', 108, 128) - self._txt_blind_spot_right = gui_app.texture('icons_mici/onroad/blind_spot_right.png', 108, 128) + self._txt_turn_signal_left = gui_app.texture('icons_mici/onroad/turn_signal_left.png', 104, 96) + self._txt_turn_signal_right = gui_app.texture('icons_mici/onroad/turn_signal_right.png', 104, 96) + self._txt_blind_spot_left = gui_app.texture('icons_mici/onroad/blind_spot_left.png', 134, 150) + self._txt_blind_spot_right = gui_app.texture('icons_mici/onroad/blind_spot_right.png', 134, 150) def get_alert(self, sm: messaging.SubMaster) -> Alert | None: """Generate the current alert based on selfdrive state.""" diff --git a/selfdrive/ui/mici/onroad/hud_renderer.py b/selfdrive/ui/mici/onroad/hud_renderer.py index 7f489ccf98..a6fa1a62bb 100644 --- a/selfdrive/ui/mici/onroad/hud_renderer.py +++ b/selfdrive/ui/mici/onroad/hud_renderer.py @@ -49,8 +49,8 @@ class TurnIntent(Widget): self._turn_intent_alpha_filter = FirstOrderFilter(0, 0.05, 1 / gui_app.target_fps) self._turn_intent_rotation_filter = FirstOrderFilter(0, 0.1, 1 / gui_app.target_fps) - self._txt_turn_intent_left: rl.Texture = gui_app.texture('icons_mici/turn_intent_left.png', 50, 19) - self._txt_turn_intent_right: rl.Texture = gui_app.texture('icons_mici/turn_intent_right.png', 50, 19) + self._txt_turn_intent_left: rl.Texture = gui_app.texture('icons_mici/turn_intent_left.png', 50, 20) + self._txt_turn_intent_right: rl.Texture = gui_app.texture('icons_mici/turn_intent_right.png', 50, 20) def _render(self, _): if self._turn_intent_alpha_filter.x > 1e-2: diff --git a/selfdrive/ui/mici/widgets/button.py b/selfdrive/ui/mici/widgets/button.py index 9678827a91..0b252c21aa 100644 --- a/selfdrive/ui/mici/widgets/button.py +++ b/selfdrive/ui/mici/widgets/button.py @@ -29,9 +29,10 @@ class ScrollState(Enum): class BigCircleButton(Widget): - def __init__(self, icon: str, red: bool = False): + def __init__(self, icon: str, red: bool = False, icon_size: tuple[int, int] = (64, 53), icon_offset: tuple[int, int] = (0, 0)): super().__init__() self._red = red + self._icon_offset = icon_offset # State self.set_rect(rl.Rectangle(0, 0, 180, 180)) @@ -39,7 +40,7 @@ class BigCircleButton(Widget): self._scale_filter = BounceFilter(1.0, 0.1, 1 / gui_app.target_fps) # Icons - self._txt_icon = gui_app.texture(icon, 64, 53) + self._txt_icon = gui_app.texture(icon, *icon_size) self._txt_btn_disabled_bg = gui_app.texture("icons_mici/buttons/button_circle_disabled.png", 180, 180) self._txt_btn_bg = gui_app.texture("icons_mici/buttons/button_circle.png", 180, 180) @@ -66,13 +67,13 @@ class BigCircleButton(Widget): # draw icon icon_color = rl.WHITE if self.enabled else rl.Color(255, 255, 255, int(255 * 0.35)) - rl.draw_texture(self._txt_icon, int(self._rect.x + (self._rect.width - self._txt_icon.width) / 2), - int(self._rect.y + (self._rect.height - self._txt_icon.height) / 2), icon_color) + rl.draw_texture(self._txt_icon, int(self._rect.x + (self._rect.width - self._txt_icon.width) / 2 + self._icon_offset[0]), + int(self._rect.y + (self._rect.height - self._txt_icon.height) / 2 + self._icon_offset[1]), icon_color) class BigCircleToggle(BigCircleButton): - def __init__(self, icon: str, toggle_callback: Callable | None = None): - super().__init__(icon, False) + def __init__(self, icon: str, toggle_callback: Callable | None = None, icon_size: tuple[int, int] = (64, 53), icon_offset: tuple[int, int] = (0, 0)): + super().__init__(icon, False, icon_size=icon_size, icon_offset=icon_offset) self._toggle_callback = toggle_callback # State @@ -80,7 +81,7 @@ class BigCircleToggle(BigCircleButton): # Icons self._txt_toggle_enabled = gui_app.texture("icons_mici/buttons/toggle_dot_enabled.png", 66, 66) - self._txt_toggle_disabled = gui_app.texture("icons_mici/buttons/toggle_dot_disabled.png", 70, 70) # TODO: why discrepancy? + self._txt_toggle_disabled = gui_app.texture("icons_mici/buttons/toggle_dot_disabled.png", 66, 66) def set_checked(self, checked: bool): self._checked = checked @@ -104,11 +105,12 @@ class BigCircleToggle(BigCircleButton): class BigButton(Widget): """A lightweight stand-in for the Qt BigButton, drawn & updated each frame.""" - def __init__(self, text: str, value: str = "", icon: Union[str, rl.Texture] = ""): + def __init__(self, text: str, value: str = "", icon: Union[str, rl.Texture] = "", icon_size: tuple[int, int] = (64, 64)): super().__init__() self.set_rect(rl.Rectangle(0, 0, 402, 180)) self.text = text self.value = value + self._icon_size = icon_size self.set_icon(icon) self._scale_filter = BounceFilter(1.0, 0.1, 1 / gui_app.target_fps) @@ -134,7 +136,7 @@ class BigButton(Widget): self._scroll_state = ScrollState.PRE_SCROLL def set_icon(self, icon: Union[str, rl.Texture]): - self._txt_icon = gui_app.texture(icon, 64, 64) if isinstance(icon, str) and len(icon) else icon + self._txt_icon = gui_app.texture(icon, *self._icon_size) if isinstance(icon, str) and len(icon) else icon def set_rotate_icon(self, rotate: bool): if rotate and self._rotate_icon_t is not None: @@ -361,8 +363,9 @@ class BigParamControl(BigToggle): # TODO: param control base class class BigCircleParamControl(BigCircleToggle): - def __init__(self, icon: str, param: str, toggle_callback: Callable | None = None): - super().__init__(icon, toggle_callback) + def __init__(self, icon: str, param: str, toggle_callback: Callable | None = None, icon_size: tuple[int, int] = (64, 53), + icon_offset: tuple[int, int] = (0, 0)): + super().__init__(icon, toggle_callback, icon_size=icon_size, icon_offset=icon_offset) self._param = param self.params = Params() self.set_checked(self.params.get_bool(self._param, False)) diff --git a/selfdrive/ui/mici/widgets/dialog.py b/selfdrive/ui/mici/widgets/dialog.py index abd558aa8d..67123d33a7 100644 --- a/selfdrive/ui/mici/widgets/dialog.py +++ b/selfdrive/ui/mici/widgets/dialog.py @@ -147,10 +147,10 @@ class BigInputDialog(BigDialogBase): self._backspace_held_time: float | None = None - self._backspace_img = gui_app.texture("icons_mici/settings/keyboard/backspace.png", 44, 44) + self._backspace_img = gui_app.texture("icons_mici/settings/keyboard/backspace.png", 42, 36) self._backspace_img_alpha = FirstOrderFilter(0, 0.05, 1 / gui_app.target_fps) - self._enter_img = gui_app.texture("icons_mici/settings/keyboard/confirm.png", 44, 44) + self._enter_img = gui_app.texture("icons_mici/settings/keyboard/confirm.png", 42, 36) self._enter_img_alpha = FirstOrderFilter(0, 0.05, 1 / gui_app.target_fps) # rects for top buttons diff --git a/selfdrive/ui/mici/widgets/pairing_dialog.py b/selfdrive/ui/mici/widgets/pairing_dialog.py index e064205d59..88bab2d001 100644 --- a/selfdrive/ui/mici/widgets/pairing_dialog.py +++ b/selfdrive/ui/mici/widgets/pairing_dialog.py @@ -24,7 +24,7 @@ class PairingDialog(NavWidget): self._qr_texture: rl.Texture | None = None self._last_qr_generation = float("-inf") - self._txt_pair = gui_app.texture("icons_mici/settings/device/pair.png", 84, 64) + self._txt_pair = gui_app.texture("icons_mici/settings/device/pair.png", 33, 60) self._pair_label = MiciLabel("pair with comma connect", 48, font_weight=FontWeight.BOLD, color=rl.Color(255, 255, 255, int(255 * 0.9)), line_height=40, wrap_text=True) diff --git a/system/ui/widgets/mici_keyboard.py b/system/ui/widgets/mici_keyboard.py index 7459dc5731..a81cf85307 100644 --- a/system/ui/widgets/mici_keyboard.py +++ b/system/ui/widgets/mici_keyboard.py @@ -105,13 +105,15 @@ class SmallKey(Key): class IconKey(Key): - def __init__(self, icon: str, vertical_align: str = "center", char: str = ""): + def __init__(self, icon: str, vertical_align: str = "center", char: str = "", icon_size: tuple[int, int] = (38, 38)): super().__init__(char) - self._icon = gui_app.texture(icon, 38, 38) + self._icon_size = icon_size + self._icon = gui_app.texture(icon, *icon_size) self._vertical_align = vertical_align - def set_icon(self, icon: str): - self._icon = gui_app.texture(icon, 38, 38) + def set_icon(self, icon: str, icon_size: tuple[int, int] | None = None): + size = icon_size if icon_size is not None else self._icon_size + self._icon = gui_app.texture(icon, *size) def _render(self, _): scale = np.interp(self._size_filter.x, [CHAR_FONT_SIZE, CHAR_NEAR_FONT_SIZE], [1, 1.5]) @@ -167,8 +169,8 @@ class MiciKeyboard(Widget): self._super_special_keys = [[Key(char) for char in row] for row in super_special_chars] # control keys - self._space_key = IconKey("icons_mici/settings/keyboard/space.png", char=" ", vertical_align="bottom") - self._caps_key = IconKey("icons_mici/settings/keyboard/caps_lower.png") + self._space_key = IconKey("icons_mici/settings/keyboard/space.png", char=" ", vertical_align="bottom", icon_size=(43, 14)) + self._caps_key = IconKey("icons_mici/settings/keyboard/caps_lower.png", icon_size=(38, 33)) # these two are in different places on some layouts self._123_key, self._123_key2 = SmallKey("123"), SmallKey("123") self._abc_key = SmallKey("abc") @@ -269,14 +271,14 @@ class MiciKeyboard(Widget): self._set_keys(self._upper_keys if cycle else self._lower_keys) if not cycle: self._caps_state = CapsState.LOWER - self._caps_key.set_icon("icons_mici/settings/keyboard/caps_lower.png") + self._caps_key.set_icon("icons_mici/settings/keyboard/caps_lower.png", icon_size=(38, 33)) else: if self._caps_state == CapsState.LOWER: self._caps_state = CapsState.UPPER - self._caps_key.set_icon("icons_mici/settings/keyboard/caps_upper.png") + self._caps_key.set_icon("icons_mici/settings/keyboard/caps_upper.png", icon_size=(38, 33)) elif self._caps_state == CapsState.UPPER: self._caps_state = CapsState.LOCK - self._caps_key.set_icon("icons_mici/settings/keyboard/caps_lock.png") + self._caps_key.set_icon("icons_mici/settings/keyboard/caps_lock.png", icon_size=(39, 38)) else: self._set_uppercase(False) From 2fc10e82998373a9bfe88f1de3d8179393f7567c Mon Sep 17 00:00:00 2001 From: felsager <76905857+felsager@users.noreply.github.com> Date: Tue, 27 Jan 2026 17:15:39 -0800 Subject: [PATCH 18/46] Maneuver: log drel and use it in tuning report (#37033) --- .../test/longitudinal_maneuvers/maneuver.py | 3 ++- .../mpc_longitudinal_tuning_report.py | 17 ++++++++++------- 2 files changed, 12 insertions(+), 8 deletions(-) diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py index dfd5b3e109..ba0379f2d7 100644 --- a/selfdrive/test/longitudinal_maneuvers/maneuver.py +++ b/selfdrive/test/longitudinal_maneuvers/maneuver.py @@ -60,7 +60,8 @@ class Maneuver: log['distance_lead'], log['speed'], speed_lead, - log['acceleration']])) + log['acceleration'], + log['d_rel']])) if d_rel < .4 and (self.only_radar or prob_lead > 0.5): print("Crashed!!!!") diff --git a/tools/longitudinal_maneuvers/mpc_longitudinal_tuning_report.py b/tools/longitudinal_maneuvers/mpc_longitudinal_tuning_report.py index 583c6240e5..8c1a60f5b7 100644 --- a/tools/longitudinal_maneuvers/mpc_longitudinal_tuning_report.py +++ b/tools/longitudinal_maneuvers/mpc_longitudinal_tuning_report.py @@ -7,16 +7,18 @@ from openpilot.selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver from openpilot.selfdrive.controls.tests.test_following_distance import desired_follow_distance TIME = 0 +LEAD_DISTANCE= 2 EGO_V = 3 EGO_A = 5 -LEAD_DISTANCE= 2 +D_REL = 6 axis_labels = ['Time (s)', 'Ego position (m)', - 'Lead distance (m)', + 'Lead absolute position (m)', 'Ego Velocity (m/s)', 'Lead Velocity (m/s)', 'Ego acceleration (m/s^2)', + 'Lead distance (m)' ] @@ -81,7 +83,7 @@ for speed in np.arange(0,45,5): htmls.append(markdown.markdown('# ' + name)) htmls.append(get_html_from_results(results, labels, EGO_A)) -htmls.append(get_html_from_results(results, labels, LEAD_DISTANCE)) +htmls.append(get_html_from_results(results, labels, D_REL)) results = {} @@ -102,6 +104,7 @@ for oscil in np.arange(0, 10, 1): labels.append(f'{oscil} m/s oscilliation size') htmls.append(markdown.markdown('# ' + name)) +htmls.append(get_html_from_results(results, labels, D_REL)) htmls.append(get_html_from_results(results, labels, EGO_V)) htmls.append(get_html_from_results(results, labels, EGO_A)) @@ -126,7 +129,7 @@ for distance in np.arange(20, 140, 10): htmls.append(markdown.markdown('# ' + name)) htmls.append(get_html_from_results(results, labels, EGO_V)) -htmls.append(get_html_from_results(results, labels, LEAD_DISTANCE)) +htmls.append(get_html_from_results(results, labels, D_REL)) results = {} @@ -148,7 +151,7 @@ for distance in np.arange(20, 140, 10): htmls.append(markdown.markdown('# ' + name)) htmls.append(get_html_from_results(results, labels, EGO_V)) -htmls.append(get_html_from_results(results, labels, LEAD_DISTANCE)) +htmls.append(get_html_from_results(results, labels, D_REL)) results = {} @@ -170,7 +173,7 @@ for stop_time in np.arange(4, 14, 1): htmls.append(markdown.markdown('# ' + name)) htmls.append(get_html_from_results(results, labels, EGO_A)) -htmls.append(get_html_from_results(results, labels, LEAD_DISTANCE)) +htmls.append(get_html_from_results(results, labels, D_REL)) results = {} @@ -193,7 +196,7 @@ for speed in np.arange(0, 40, 5): htmls.append(markdown.markdown('# ' + name)) htmls.append(get_html_from_results(results, labels, EGO_A)) -htmls.append(get_html_from_results(results, labels, LEAD_DISTANCE)) +htmls.append(get_html_from_results(results, labels, D_REL)) results = {} From 0b958f7c9ae682e0ab95d0dc9f45f605be0dfce0 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 27 Jan 2026 19:59:25 -0800 Subject: [PATCH 19/46] onroad: fill bookmark icon when activated (#37034) * bookmark fill * and here's what i would have done * add --- selfdrive/ui/mici/onroad/augmented_road_view.py | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/mici/onroad/augmented_road_view.py b/selfdrive/ui/mici/onroad/augmented_road_view.py index 71ca03cccf..4e00a3aafe 100644 --- a/selfdrive/ui/mici/onroad/augmented_road_view.py +++ b/selfdrive/ui/mici/onroad/augmented_road_view.py @@ -46,6 +46,8 @@ class BookmarkIcon(Widget): super().__init__() self._bookmark_callback = bookmark_callback self._icon = gui_app.texture("icons_mici/onroad/bookmark.png", 180, 180) + self._icon_fill = gui_app.texture("icons_mici/onroad/bookmark_fill.png", 180, 180) + self._active_icon = self._icon self._offset_filter = BounceFilter(0.0, 0.1, 1 / gui_app.target_fps) # State @@ -84,6 +86,7 @@ class BookmarkIcon(Widget): if self._offset_filter.x < 1e-3: self._interacting = False + self._active_icon = self._icon def _handle_mouse_event(self, mouse_event: MouseEvent): if not ui_state.started: @@ -96,6 +99,7 @@ class BookmarkIcon(Widget): self._is_swiping = True self._is_swiping_left = False self._state = BookmarkState.DRAGGING + self._active_icon = self._icon elif mouse_event.left_down and self._is_swiping: self._swipe_current_x = mouse_event.pos.x @@ -112,6 +116,7 @@ class BookmarkIcon(Widget): if swipe_distance > self.PEEK_THRESHOLD: self._state = BookmarkState.TRIGGERED self._triggered_time = rl.get_time() + self._active_icon = self._icon_fill self._bookmark_callback() else: # Otherwise, transition back to hidden @@ -125,8 +130,8 @@ class BookmarkIcon(Widget): """Render the bookmark icon.""" if self._offset_filter.x > 0: icon_x = self.rect.x + self.rect.width - round(self._offset_filter.x) - icon_y = self.rect.y + (self.rect.height - self._icon.height) / 2 # Vertically centered - rl.draw_texture(self._icon, int(icon_x), int(icon_y), rl.WHITE) + icon_y = self.rect.y + (self.rect.height - self._active_icon.height) / 2 # Vertically centered + rl.draw_texture(self._active_icon, int(icon_x), int(icon_y), rl.WHITE) class AugmentedRoadView(CameraView): From d849d6f1d7a7c380038a9e7e72df70a125fb7b03 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 27 Jan 2026 21:28:50 -0800 Subject: [PATCH 20/46] mici keyboard: bold SmallKey (#37035) bold SmallKey --- system/ui/widgets/mici_keyboard.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/system/ui/widgets/mici_keyboard.py b/system/ui/widgets/mici_keyboard.py index a81cf85307..7fc3847809 100644 --- a/system/ui/widgets/mici_keyboard.py +++ b/system/ui/widgets/mici_keyboard.py @@ -38,10 +38,10 @@ def fast_euclidean_distance(dx, dy): class Key(Widget): - def __init__(self, char: str): + def __init__(self, char: str, font_weight: FontWeight = FontWeight.SEMI_BOLD): super().__init__() self.char = char - self._font = gui_app.font(FontWeight.SEMI_BOLD) + self._font = gui_app.font(font_weight) self._x_filter = BounceFilter(0.0, 0.1 * ANIMATION_SCALE, 1 / gui_app.target_fps) self._y_filter = BounceFilter(0.0, 0.1 * ANIMATION_SCALE, 1 / gui_app.target_fps) self._size_filter = BounceFilter(CHAR_FONT_SIZE, 0.1 * ANIMATION_SCALE, 1 / gui_app.target_fps) @@ -97,7 +97,7 @@ class Key(Widget): class SmallKey(Key): def __init__(self, chars: str): - super().__init__(chars) + super().__init__(chars, FontWeight.BOLD) self._size_filter.x = NUMBER_LAYER_SWITCH_FONT_SIZE def set_font_size(self, size: float): From e89e4407c57f0616bcdc3bd3d48bd19e95274eb9 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 28 Jan 2026 19:50:53 -0800 Subject: [PATCH 21/46] Tweak stockLkas alert (#37040) * stockLkas alert is orange, small, mid prio, ldw vis alert * copy exactly from existing ldw alert with prompt sound, black alert --- selfdrive/selfdrived/events.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index 35d4bda42f..0e37a959c5 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -479,10 +479,10 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { EventName.stockLkas: { ET.PERMANENT: Alert( - "TAKE CONTROL", "Stock LKAS: Lane Departure Detected", - AlertStatus.critical, AlertSize.full, - Priority.HIGH, VisualAlert.fcw, AudibleAlert.none, 2.), + "", + AlertStatus.userPrompt, AlertSize.small, + Priority.LOW, VisualAlert.ldw, AudibleAlert.prompt, 3.), ET.NO_ENTRY: NoEntryAlert("Stock LKAS: Lane Departure Detected"), }, From bddd20c4252303362f33241ac35ee7d51acec87b Mon Sep 17 00:00:00 2001 From: T3d Date: Thu, 29 Jan 2026 19:36:51 +0100 Subject: [PATCH 22/46] Complete french translations in app_fr.po (#37023) --- selfdrive/ui/translations/app_fr.po | 94 +++++++++++++++-------------- 1 file changed, 50 insertions(+), 44 deletions(-) diff --git a/selfdrive/ui/translations/app_fr.po b/selfdrive/ui/translations/app_fr.po index f883d4d485..409761588e 100644 --- a/selfdrive/ui/translations/app_fr.po +++ b/selfdrive/ui/translations/app_fr.po @@ -5,10 +5,10 @@ # msgid "" msgstr "" -"Project-Id-Version: PACKAGE VERSION\n" +"Project-Id-Version: \n" "Report-Msgid-Bugs-To: \n" "POT-Creation-Date: 2025-10-23 00:50-0700\n" -"PO-Revision-Date: 2025-10-20 18:19-0700\n" +"PO-Revision-Date: 2026-01-24 12:37+0100\n" "Last-Translator: Automatically generated\n" "Language-Team: none\n" "Language: fr\n" @@ -16,21 +16,22 @@ msgstr "" "Content-Type: text/plain; charset=UTF-8\n" "Content-Transfer-Encoding: 8bit\n" "Plural-Forms: nplurals=2; plural=(n > 1);\n" +"X-Generator: Poedit 3.8\n" #: selfdrive/ui/layouts/settings/device.py:160 #, python-format msgid " Steering torque response calibration is complete." -msgstr "" +msgstr " L'étalonnage de la réponse du couple de direction est terminé." #: selfdrive/ui/layouts/settings/device.py:158 #, python-format msgid " Steering torque response calibration is {}% complete." -msgstr "" +msgstr " L'étalonnage de la réponse du couple de direction est terminé à {}%." #: selfdrive/ui/layouts/settings/device.py:133 #, python-format msgid " Your device is pointed {:.1f}° {} and {:.1f}° {}." -msgstr "" +msgstr " Votre appareil est orienté {:.1f}° {} et {:.1f}° {}." #: selfdrive/ui/layouts/sidebar.py:43 msgid "--" @@ -79,12 +80,13 @@ msgstr "" #: selfdrive/ui/layouts/settings/device.py:148 #, python-format msgid "

Steering lag calibration is complete." -msgstr "" +msgstr "

L'étalonnage du délai de réponse de la direction est terminé." #: selfdrive/ui/layouts/settings/device.py:146 #, python-format msgid "

Steering lag calibration is {}% complete." msgstr "" +"

L'étalonnage du délai de réponse de la direction est terminé à {}%." #: selfdrive/ui/layouts/settings/firehose.py:138 #, python-format @@ -107,7 +109,7 @@ msgstr "AJOUTER" #: system/ui/widgets/network.py:139 #, python-format msgid "APN Setting" -msgstr "" +msgstr "Paramètres APN" #: selfdrive/ui/widgets/offroad_alerts.py:109 #, python-format @@ -117,7 +119,7 @@ msgstr "Accuser réception d'actionnement excessif" #: system/ui/widgets/network.py:74 system/ui/widgets/network.py:95 #, python-format msgid "Advanced" -msgstr "" +msgstr "Avancé" #: selfdrive/ui/layouts/settings/toggles.py:98 #, python-format @@ -208,18 +210,18 @@ msgstr "CONNECTER" #: system/ui/widgets/network.py:369 #, python-format msgid "CONNECTING..." -msgstr "CONNECTER" +msgstr "CONNECTER..." #: system/ui/widgets/confirm_dialog.py:23 system/ui/widgets/option_dialog.py:35 #: system/ui/widgets/keyboard.py:81 system/ui/widgets/network.py:318 #, python-format msgid "Cancel" -msgstr "" +msgstr "Annuler" #: system/ui/widgets/network.py:134 #, python-format msgid "Cellular Metered" -msgstr "" +msgstr "Données cellulaire limitées" #: selfdrive/ui/layouts/settings/device.py:68 #, python-format @@ -230,7 +232,7 @@ msgstr "Changer la langue" #, python-format msgid "Changing this setting will restart openpilot if the car is powered on." msgstr "" -" La modification de ce réglage redémarrera openpilot si la voiture est sous " +"La modification de ce réglage redémarrera openpilot si la voiture est sous " "tension." #: selfdrive/ui/widgets/pairing_dialog.py:129 @@ -318,7 +320,7 @@ msgstr "Personnalité de conduite" #: system/ui/widgets/network.py:123 system/ui/widgets/network.py:139 #, python-format msgid "EDIT" -msgstr "" +msgstr "EDITER" #: selfdrive/ui/layouts/sidebar.py:138 msgid "ERROR" @@ -387,22 +389,22 @@ msgstr "" #: system/ui/widgets/network.py:204 #, python-format msgid "Enter APN" -msgstr "" +msgstr "Saisir l'APN" #: system/ui/widgets/network.py:241 #, python-format msgid "Enter SSID" -msgstr "" +msgstr "Entrer le SSID" #: system/ui/widgets/network.py:254 #, python-format msgid "Enter new tethering password" -msgstr "" +msgstr "Saisir le mot de passe du partage de connexion" #: system/ui/widgets/network.py:237 system/ui/widgets/network.py:314 #, python-format msgid "Enter password" -msgstr "" +msgstr "Saisir le mot de passe" #: selfdrive/ui/widgets/ssh_key.py:89 #, python-format @@ -412,7 +414,7 @@ msgstr "Entrez votre nom d'utilisateur GitHub" #: system/ui/widgets/list_view.py:123 system/ui/widgets/list_view.py:160 #, python-format msgid "Error" -msgstr "" +msgstr "Erreur" #: selfdrive/ui/layouts/settings/toggles.py:52 #, python-format @@ -431,7 +433,7 @@ msgstr "" #: system/ui/widgets/network.py:373 #, python-format msgid "FORGETTING..." -msgstr "" +msgstr "OUBLIER..." #: selfdrive/ui/widgets/setup.py:44 #, python-format @@ -493,12 +495,12 @@ msgstr "" #: system/ui/widgets/network.py:318 system/ui/widgets/network.py:451 #, python-format msgid "Forget" -msgstr "" +msgstr "Oublier" #: system/ui/widgets/network.py:319 #, python-format msgid "Forget Wi-Fi Network \"{}\"?" -msgstr "" +msgstr "Oublier le réseau Wi-Fi \"{}\" ?" #: selfdrive/ui/layouts/sidebar.py:71 selfdrive/ui/layouts/sidebar.py:125 msgid "GOOD" @@ -532,7 +534,7 @@ msgstr "INSTALLER" #: system/ui/widgets/network.py:150 #, python-format msgid "IP Address" -msgstr "" +msgstr "Adresse IP" #: selfdrive/ui/layouts/settings/software.py:53 #, python-format @@ -574,7 +576,7 @@ msgstr "" #: selfdrive/ui/layouts/settings/device.py:60 #, python-format msgid "N/A" -msgstr "" +msgstr "NC" #: selfdrive/ui/layouts/sidebar.py:142 msgid "NO" @@ -592,7 +594,7 @@ msgstr "Aucune clé SSH trouvée" #: selfdrive/ui/widgets/ssh_key.py:126 #, python-format msgid "No SSH keys found for user '{}'" -msgstr "Aucune clé SSH trouvée pour l'utilisateur '{username}'" +msgstr "Aucune clé SSH trouvée pour l'utilisateur '{}'" #: selfdrive/ui/widgets/offroad_alerts.py:320 #, python-format @@ -677,11 +679,15 @@ msgstr "Éteindre" #, python-format msgid "Prevent large data uploads when on a metered Wi-Fi connection" msgstr "" +"Eviter les transferts de données volumineux lorsque vous êtes connecté à un " +"réseau Wi-Fi limité" #: system/ui/widgets/network.py:135 #, python-format msgid "Prevent large data uploads when on a metered cellular connection" msgstr "" +"Eviter les transferts de données volumineux lors d'une connexion à un réseau " +"cellulaire limité" #: selfdrive/ui/layouts/settings/device.py:25 msgid "" @@ -802,32 +808,32 @@ msgstr "Consultez les règles, fonctionnalités et limitations d'openpilot" #: selfdrive/ui/layouts/settings/software.py:61 #, python-format msgid "SELECT" -msgstr "" +msgstr "SELECTIONNER" #: selfdrive/ui/layouts/settings/developer.py:53 #, python-format msgid "SSH Keys" -msgstr "" +msgstr "Clefs SSH" #: system/ui/widgets/network.py:310 #, python-format msgid "Scanning Wi-Fi networks..." -msgstr "" +msgstr "Analyse des réseaux Wi-Fi..." #: system/ui/widgets/option_dialog.py:36 #, python-format msgid "Select" -msgstr "" +msgstr "Sélectionner" #: selfdrive/ui/layouts/settings/software.py:183 #, python-format msgid "Select a branch" -msgstr "" +msgstr "Sélectionner une branche" #: selfdrive/ui/layouts/settings/device.py:91 #, python-format msgid "Select a language" -msgstr "" +msgstr "Sélectionner un langage" #: selfdrive/ui/layouts/settings/device.py:60 #, python-format @@ -880,12 +886,12 @@ msgstr "TEMPÉRATURE" #: selfdrive/ui/layouts/settings/software.py:61 #, python-format msgid "Target Branch" -msgstr "" +msgstr "Branche cible" #: system/ui/widgets/network.py:124 #, python-format msgid "Tethering Password" -msgstr "" +msgstr "Mot de passe du partage de connexion" #: selfdrive/ui/layouts/settings/settings.py:64 msgid "Toggles" @@ -986,12 +992,12 @@ msgstr "Wi‑Fi" #: system/ui/widgets/network.py:144 #, python-format msgid "Wi-Fi Network Metered" -msgstr "" +msgstr "Réseau Wi-Fi limité" #: system/ui/widgets/network.py:314 #, python-format msgid "Wrong password" -msgstr "" +msgstr "Mauvais mot de passe" #: selfdrive/ui/layouts/onboarding.py:145 #, python-format @@ -1020,12 +1026,12 @@ msgstr "comma prime" #: system/ui/widgets/network.py:142 #, python-format msgid "default" -msgstr "" +msgstr "défaut" #: selfdrive/ui/layouts/settings/device.py:133 #, python-format msgid "down" -msgstr "" +msgstr "bas" #: selfdrive/ui/layouts/settings/software.py:106 #, python-format @@ -1035,7 +1041,7 @@ msgstr "échec de la vérification de mise à jour" #: system/ui/widgets/network.py:237 system/ui/widgets/network.py:314 #, python-format msgid "for \"{}\"" -msgstr "" +msgstr "pour \"{}\"" #: selfdrive/ui/onroad/hud_renderer.py:177 #, python-format @@ -1045,17 +1051,17 @@ msgstr "km/h" #: system/ui/widgets/network.py:204 #, python-format msgid "leave blank for automatic configuration" -msgstr "" +msgstr "ne pas remplir pour une configuration automatique" #: selfdrive/ui/layouts/settings/device.py:134 #, python-format msgid "left" -msgstr "" +msgstr "gauche" #: system/ui/widgets/network.py:142 #, python-format msgid "metered" -msgstr "" +msgstr "limité" #: selfdrive/ui/onroad/hud_renderer.py:177 #, python-format @@ -1116,7 +1122,7 @@ msgid "" "openpilot is continuously calibrating, resetting is rarely required. " "Resetting calibration will restart openpilot if the car is powered on." msgstr "" -" La modification de ce réglage redémarrera openpilot si la voiture est sous " +"La modification de ce réglage redémarrera openpilot si la voiture est sous " "tension." #: selfdrive/ui/layouts/settings/firehose.py:20 @@ -1153,17 +1159,17 @@ msgstr "" #: selfdrive/ui/layouts/settings/device.py:134 #, python-format msgid "right" -msgstr "" +msgstr "droite" #: system/ui/widgets/network.py:142 #, python-format msgid "unmetered" -msgstr "" +msgstr "non limité" #: selfdrive/ui/layouts/settings/device.py:133 #, python-format msgid "up" -msgstr "" +msgstr "haut" #: selfdrive/ui/layouts/settings/software.py:117 #, python-format From df7f426405de7ea4885cc54cd44c8ee9c9152f8c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 30 Jan 2026 00:09:19 -0800 Subject: [PATCH 23/46] bump opendbc (#37043) * bump opendbc * update refs --- opendbc_repo | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index d424d1f247..c8e92d0463 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit d424d1f247384b68923b8093875e1a370ef8221d +Subproject commit c8e92d046324be54cfedccd2a27101060861e82b diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 7b9039180c..85b79391c3 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -77951c4ccd0916b87c8dfda9faa33cd2d5d2cc11 \ No newline at end of file +67f3daf309dc6cbb6844fcbaeb83e6596637e551 \ No newline at end of file From 569099eb70eef3c379bb61c84e4dd0504c63bd99 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 30 Jan 2026 00:09:44 -0800 Subject: [PATCH 24/46] update docs --- docs/CARS.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index b349679395..65f79cdba4 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,7 +4,7 @@ A supported vehicle is one that just works when you install a comma device. All supported cars provide a better experience than any stock system. Supported vehicles reference the US market unless otherwise specified. -# 327 Supported Cars +# 328 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Hardware Needed
 |Video|Setup Video| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:|:---:| @@ -103,6 +103,7 @@ A supported vehicle is one that just works when you install a comma device. All |Honda|N-Box 2018|All|openpilot available[1](#footnotes)|0 mph|11 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Honda|Odyssey 2018-20|Honda Sensing|openpilot|26 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Honda|Odyssey 2021-26|All|openpilot available[1](#footnotes)|0 mph|43 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| +|Honda|Odyssey (Taiwan) 2018-19|Honda Sensing|openpilot|19 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Honda|Passport 2019-25|All|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Honda|Passport 2026|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch C connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Honda|Pilot 2016-22|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 OBD-C cable (2 ft)
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| @@ -202,7 +203,7 @@ A supported vehicle is one that just works when you install a comma device. All |Lexus|IS 2017-19|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 Toyota A connector
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Lexus|IS 2022-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 Toyota A connector
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Lexus|LC 2024-25|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 Toyota A connector
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| -|Lexus|LS 2018|All except Lexus Safety System+ A|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 Toyota A connector
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| +|Lexus|LS 2018|All except Lexus Safety System+ A|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 Toyota A connector
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Lexus|NX 2018-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 Toyota A connector
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Lexus|NX 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 Toyota A connector
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| |Lexus|NX Hybrid 2018-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 OBD-C cable (2 ft)
- 1 Toyota A connector
- 1 comma four
- 1 comma power v3
- 1 harness box
- 1 mount
Buy Here
||| From 32f0a2cbbc0f39b23105c906ff0d77bc4a746c7f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 30 Jan 2026 00:30:11 -0800 Subject: [PATCH 25/46] bump opendbc (#37046) bump --- opendbc_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc_repo b/opendbc_repo index c8e92d0463..e76c2cf5bb 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit c8e92d046324be54cfedccd2a27101060861e82b +Subproject commit e76c2cf5bb0042bc5822efa78fff0362feed7b54 From db3df61c34cc8280e81f3204f58454bf3393a743 Mon Sep 17 00:00:00 2001 From: King Art Date: Sat, 31 Jan 2026 01:16:56 +0000 Subject: [PATCH 26/46] fix non-determinism in modeld build (#37042) * fix non-determinism in selfservice model build also trim down model compile dependencies to the minimum required * Apply suggestions from code review --------- Co-authored-by: Shane Smiskol --- selfdrive/modeld/SConscript | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index a184b6a23d..91f3597447 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -29,7 +29,7 @@ for pathdef, fn in {'TRANSFORM': 'transforms/transform.cl', 'LOADYUV': 'transfor cython_libs = envCython["LIBS"] + libs commonmodel_lib = lenv.Library('commonmodel', common_src) lenvCython.Program('models/commonmodel_pyx.so', 'models/commonmodel_pyx.pyx', LIBS=[commonmodel_lib, *cython_libs], FRAMEWORKS=frameworks) -tinygrad_files = ["#"+x for x in glob.glob(env.Dir("#tinygrad_repo").relpath + "/**", recursive=True, root_dir=env.Dir("#").abspath) if 'pycache' not in x] +tinygrad_files = sorted(["#"+x for x in glob.glob(env.Dir("#tinygrad_repo").relpath + "/**", recursive=True, root_dir=env.Dir("#").abspath) if 'pycache' not in x]) # Get model metadata for model_name in ['driving_vision', 'driving_policy', 'dmonitoring_model']: From c35df583a5cb287304a88701b2a9040f74788ecc Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 31 Jan 2026 15:52:50 -0800 Subject: [PATCH 27/46] tools: enable log caching by default (#36962) --- .github/workflows/repo-maintenance.yaml | 2 +- .github/workflows/tests.yaml | 2 +- selfdrive/car/tests/big_cars_test.sh | 1 - selfdrive/test/process_replay/README.md | 2 +- tools/lib/tests/test_caching.py | 13 ++++++++----- tools/lib/tests/test_logreader.py | 10 ++++++++-- tools/lib/url_file.py | 4 ++-- tools/replay/can_replay.py | 2 -- tools/tuning/measure_steering_accuracy.py | 4 ---- 9 files changed, 21 insertions(+), 19 deletions(-) diff --git a/.github/workflows/repo-maintenance.yaml b/.github/workflows/repo-maintenance.yaml index 7bb91c0ca4..b8b29e602f 100644 --- a/.github/workflows/repo-maintenance.yaml +++ b/.github/workflows/repo-maintenance.yaml @@ -8,7 +8,7 @@ on: env: BASE_IMAGE: openpilot-base BUILD: selfdrive/test/docker_build.sh base - RUN: docker run --shm-size 2G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e CI=1 -e PYTHONWARNINGS=error -e FILEREADER_CACHE=1 -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v $GITHUB_WORKSPACE/.ci_cache/scons_cache:/tmp/scons_cache -v $GITHUB_WORKSPACE/.ci_cache/comma_download_cache:/tmp/comma_download_cache -v $GITHUB_WORKSPACE/.ci_cache/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/bash -c + RUN: docker run --shm-size 2G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e CI=1 -e PYTHONWARNINGS=error -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v $GITHUB_WORKSPACE/.ci_cache/scons_cache:/tmp/scons_cache -v $GITHUB_WORKSPACE/.ci_cache/comma_download_cache:/tmp/comma_download_cache -v $GITHUB_WORKSPACE/.ci_cache/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/bash -c jobs: update_translations: diff --git a/.github/workflows/tests.yaml b/.github/workflows/tests.yaml index c5802b5cb2..c7da619454 100644 --- a/.github/workflows/tests.yaml +++ b/.github/workflows/tests.yaml @@ -25,7 +25,7 @@ env: DOCKER_LOGIN: docker login ghcr.io -u ${{ github.actor }} -p ${{ secrets.GITHUB_TOKEN }} BUILD: selfdrive/test/docker_build.sh base - RUN: docker run --shm-size 2G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e CI=1 -e PYTHONWARNINGS=error -e FILEREADER_CACHE=1 -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v $GITHUB_WORKSPACE/.ci_cache/scons_cache:/tmp/scons_cache -v $GITHUB_WORKSPACE/.ci_cache/comma_download_cache:/tmp/comma_download_cache -v $GITHUB_WORKSPACE/.ci_cache/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/bash -c + RUN: docker run --shm-size 2G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e CI=1 -e PYTHONWARNINGS=error -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v $GITHUB_WORKSPACE/.ci_cache/scons_cache:/tmp/scons_cache -v $GITHUB_WORKSPACE/.ci_cache/comma_download_cache:/tmp/comma_download_cache -v $GITHUB_WORKSPACE/.ci_cache/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/bash -c PYTEST: pytest --continue-on-collection-errors --durations=0 -n logical diff --git a/selfdrive/car/tests/big_cars_test.sh b/selfdrive/car/tests/big_cars_test.sh index 863b8bead0..bb6e82dd0e 100755 --- a/selfdrive/car/tests/big_cars_test.sh +++ b/selfdrive/car/tests/big_cars_test.sh @@ -6,7 +6,6 @@ cd $BASEDIR export MAX_EXAMPLES=300 export INTERNAL_SEG_CNT=300 -export FILEREADER_CACHE=1 export INTERNAL_SEG_LIST=selfdrive/car/tests/test_models_segs.txt cd selfdrive/car/tests && pytest test_models.py test_car_interfaces.py diff --git a/selfdrive/test/process_replay/README.md b/selfdrive/test/process_replay/README.md index dc801e4285..8e279c71cd 100644 --- a/selfdrive/test/process_replay/README.md +++ b/selfdrive/test/process_replay/README.md @@ -5,7 +5,7 @@ Process replay is a regression test designed to identify any changes in the outp If the test fails, make sure that you didn't unintentionally change anything. If there are intentional changes, the reference logs will be updated. Use `test_processes.py` to run the test locally. -Use `FILEREADER_CACHE='1' test_processes.py` to cache log files. +Log files are cached by default. Use `DISABLE_FILEREADER_CACHE='1' test_processes.py` to disable caching. Currently the following processes are tested: diff --git a/tools/lib/tests/test_caching.py b/tools/lib/tests/test_caching.py index 6e70ef90b0..cb14098e6d 100644 --- a/tools/lib/tests/test_caching.py +++ b/tools/lib/tests/test_caching.py @@ -56,13 +56,13 @@ class TestFileDownload: for k, v in retry_defaults.items(): assert getattr(URLFile.pool_manager().connection_pool_kw["retries"], k) == v - # ensure caching off by default and cache dir doesn't get created - os.environ.pop("FILEREADER_CACHE", None) + # ensure caching on by default and cache dir gets created + os.environ.pop("DISABLE_FILEREADER_CACHE", None) if os.path.exists(Paths.download_cache_root()): shutil.rmtree(Paths.download_cache_root()) URLFile(f"{host}/test.txt").get_length() URLFile(f"{host}/test.txt").read() - assert not os.path.exists(Paths.download_cache_root()) + assert os.path.exists(Paths.download_cache_root()) def compare_loads(self, url, start=0, length=None): """Compares range between cached and non cached version""" @@ -90,7 +90,7 @@ class TestFileDownload: def test_small_file(self): # Make sure we don't force cache - os.environ["FILEREADER_CACHE"] = "0" + os.environ.pop("DISABLE_FILEREADER_CACHE", None) small_file_url = "https://raw.githubusercontent.com/commaai/openpilot/master/docs/SAFETY.md" # If you want large file to be larger than a chunk # large_file_url = "https://commadataci.blob.core.windows.net/openpilotci/0375fdf7b1ce594d/2019-06-13--08-32-25/3/fcamera.hevc" @@ -119,7 +119,10 @@ class TestFileDownload: @pytest.mark.parametrize("cache_enabled", [True, False]) def test_recover_from_missing_file(self, host, cache_enabled): - os.environ["FILEREADER_CACHE"] = "1" if cache_enabled else "0" + if cache_enabled: + os.environ.pop("DISABLE_FILEREADER_CACHE", None) + else: + os.environ["DISABLE_FILEREADER_CACHE"] = "1" file_url = f"{host}/test.png" diff --git a/tools/lib/tests/test_logreader.py b/tools/lib/tests/test_logreader.py index ee75a8b1ce..0151940c44 100644 --- a/tools/lib/tests/test_logreader.py +++ b/tools/lib/tests/test_logreader.py @@ -93,7 +93,10 @@ class TestLogReader: @pytest.mark.parametrize("cache_enabled", [True, False]) def test_direct_parsing(self, mocker, cache_enabled): file_exists_mock = mocker.patch("openpilot.tools.lib.filereader.file_exists") - os.environ["FILEREADER_CACHE"] = "1" if cache_enabled else "0" + if cache_enabled: + os.environ.pop("DISABLE_FILEREADER_CACHE", None) + else: + os.environ["DISABLE_FILEREADER_CACHE"] = "1" qlog = tempfile.NamedTemporaryFile(mode='wb', delete=False) with requests.get(QLOG_FILE, stream=True) as r: @@ -181,7 +184,10 @@ class TestLogReader: @parameterized.expand([(True,), (False,)]) @pytest.mark.slow def test_run_across_segments(self, cache_enabled): - os.environ["FILEREADER_CACHE"] = "1" if cache_enabled else "0" + if cache_enabled: + os.environ.pop("DISABLE_FILEREADER_CACHE", None) + else: + os.environ["DISABLE_FILEREADER_CACHE"] = "1" lr = LogReader(f"{TEST_ROUTE}/0:4") assert len(lr.run_across_segments(4, noop)) == len(list(lr)) diff --git a/tools/lib/url_file.py b/tools/lib/url_file.py index 8e2f0a9222..de12070465 100644 --- a/tools/lib/url_file.py +++ b/tools/lib/url_file.py @@ -74,8 +74,8 @@ class URLFile: self._timeout = Timeout(connect=timeout, read=timeout) self._pos = 0 self._length: int | None = None - # True by default, false if FILEREADER_CACHE is defined, but can be overwritten by the cache input - self._force_download = not int(os.environ.get("FILEREADER_CACHE", "0")) + # Caching enabled by default, can be disabled with DISABLE_FILEREADER_CACHE=1, or overwritten by the cache input + self._force_download = int(os.environ.get("DISABLE_FILEREADER_CACHE", "0")) == 1 if cache is not None: self._force_download = not cache diff --git a/tools/replay/can_replay.py b/tools/replay/can_replay.py index 13c30a62ad..0717320077 100755 --- a/tools/replay/can_replay.py +++ b/tools/replay/can_replay.py @@ -5,8 +5,6 @@ import time import usb1 import threading -os.environ['FILEREADER_CACHE'] = '1' - from openpilot.common.realtime import config_realtime_process, Ratekeeper, DT_CTRL from openpilot.selfdrive.pandad import can_capnp_to_list from openpilot.tools.lib.logreader import LogReader diff --git a/tools/tuning/measure_steering_accuracy.py b/tools/tuning/measure_steering_accuracy.py index e4aef0ba15..ae3344c2eb 100755 --- a/tools/tuning/measure_steering_accuracy.py +++ b/tools/tuning/measure_steering_accuracy.py @@ -117,12 +117,8 @@ if __name__ == "__main__": parser.add_argument('--route', help="route name") parser.add_argument('--addr', default='127.0.0.1', help="IP address for optional ZMQ listener, default to msgq") parser.add_argument('--group', default='all', help="speed group to display, [crawl|slow|medium|fast|veryfast|germany|all], default to all") - parser.add_argument('--cache', default=False, action='store_true', help="use cached data, default to False") args = parser.parse_args() - if args.cache: - os.environ['FILEREADER_CACHE'] = '1' - tool = SteeringAccuracyTool(args) if args.route is not None: From 1dfef69a3c8b6a5e622cfa648075a67ed267bbdd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?P=C3=A1draic=20Slattery?= Date: Sun, 1 Feb 2026 03:37:00 +0100 Subject: [PATCH 28/46] chore: Update outdated GitHub Actions versions (#37020) * chore: Update outdated GitHub Actions versions * just the github ones --------- Co-authored-by: Adeeb Shihadeh --- .github/workflows/auto_pr_review.yaml | 6 ++--- .github/workflows/badges.yaml | 2 +- .github/workflows/ci_weekly_report.yaml | 2 +- .github/workflows/docs.yaml | 4 +-- .github/workflows/jenkins-pr-trigger.yaml | 6 ++--- .github/workflows/mici_raylib_ui_preview.yaml | 4 +-- .github/workflows/model_review.yaml | 4 +-- .github/workflows/prebuilt.yaml | 2 +- .github/workflows/raylib_ui_preview.yaml | 2 +- .github/workflows/release.yaml | 2 +- .github/workflows/repo-maintenance.yaml | 4 +-- .github/workflows/stale.yaml | 4 +-- .github/workflows/tests.yaml | 26 +++++++++---------- 13 files changed, 34 insertions(+), 34 deletions(-) diff --git a/.github/workflows/auto_pr_review.yaml b/.github/workflows/auto_pr_review.yaml index c6a1cb9821..725154d21f 100644 --- a/.github/workflows/auto_pr_review.yaml +++ b/.github/workflows/auto_pr_review.yaml @@ -11,12 +11,12 @@ jobs: pull-requests: write runs-on: ubuntu-latest steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: false # Label PRs - - uses: actions/labeler@v5.0.0 + - uses: actions/labeler@v6 with: dot: true configuration-path: .github/labeler.yaml @@ -36,7 +36,7 @@ jobs: # Welcome comment - name: "First timers PR" - uses: actions/first-interaction@v1 + uses: actions/first-interaction@v3 if: github.event.pull_request.head.repo.full_name != 'commaai/openpilot' with: repo-token: ${{ secrets.GITHUB_TOKEN }} diff --git a/.github/workflows/badges.yaml b/.github/workflows/badges.yaml index cd30e4f370..3f9c9c1c59 100644 --- a/.github/workflows/badges.yaml +++ b/.github/workflows/badges.yaml @@ -17,7 +17,7 @@ jobs: permissions: contents: write steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - uses: ./.github/workflows/setup-with-retry diff --git a/.github/workflows/ci_weekly_report.yaml b/.github/workflows/ci_weekly_report.yaml index 37a46b2096..c7f5ec34f0 100644 --- a/.github/workflows/ci_weekly_report.yaml +++ b/.github/workflows/ci_weekly_report.yaml @@ -41,7 +41,7 @@ jobs: if: always() && github.repository == 'commaai/openpilot' steps: - name: Get job results - uses: actions/github-script@v7 + uses: actions/github-script@v8 id: get-job-results with: script: | diff --git a/.github/workflows/docs.yaml b/.github/workflows/docs.yaml index 92c311829c..23a89de1c1 100644 --- a/.github/workflows/docs.yaml +++ b/.github/workflows/docs.yaml @@ -22,7 +22,7 @@ jobs: steps: - uses: commaai/timeout@v1 - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true @@ -34,7 +34,7 @@ jobs: mkdocs build # Push to docs.comma.ai - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 if: github.ref == 'refs/heads/master' && github.repository == 'commaai/openpilot' with: path: openpilot-docs diff --git a/.github/workflows/jenkins-pr-trigger.yaml b/.github/workflows/jenkins-pr-trigger.yaml index 14e2fdf49b..f8a53c5ae0 100644 --- a/.github/workflows/jenkins-pr-trigger.yaml +++ b/.github/workflows/jenkins-pr-trigger.yaml @@ -15,7 +15,7 @@ jobs: steps: - name: Check for trigger phrase id: check_comment - uses: actions/github-script@v7 + uses: actions/github-script@v8 with: script: | const triggerPhrase = "trigger-jenkins"; @@ -35,7 +35,7 @@ jobs: - name: Checkout repository if: steps.check_comment.outputs.result == 'true' - uses: actions/checkout@v4 + uses: actions/checkout@v6 with: ref: refs/pull/${{ github.event.issue.number }}/head @@ -49,7 +49,7 @@ jobs: - name: Delete trigger comment if: steps.check_comment.outputs.result == 'true' && always() - uses: actions/github-script@v7 + uses: actions/github-script@v8 with: script: | await github.rest.issues.deleteComment({ diff --git a/.github/workflows/mici_raylib_ui_preview.yaml b/.github/workflows/mici_raylib_ui_preview.yaml index 707825b1ac..5025d407cd 100644 --- a/.github/workflows/mici_raylib_ui_preview.yaml +++ b/.github/workflows/mici_raylib_ui_preview.yaml @@ -33,7 +33,7 @@ jobs: pull-requests: write actions: read steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true @@ -62,7 +62,7 @@ jobs: path: ${{ github.workspace }}/pr_ui - name: Getting master ui # filename: master_ui_raylib/mici_ui_replay.mp4 - uses: actions/checkout@v4 + uses: actions/checkout@v6 with: repository: commaai/ci-artifacts ssh-key: ${{ secrets.CI_ARTIFACTS_DEPLOY_KEY }} diff --git a/.github/workflows/model_review.yaml b/.github/workflows/model_review.yaml index 0e1825864c..6b8ce143db 100644 --- a/.github/workflows/model_review.yaml +++ b/.github/workflows/model_review.yaml @@ -16,9 +16,9 @@ jobs: if: github.repository == 'commaai/openpilot' steps: - name: Checkout - uses: actions/checkout@v4 + uses: actions/checkout@v6 - name: Checkout master - uses: actions/checkout@v4 + uses: actions/checkout@v6 with: ref: master path: base diff --git a/.github/workflows/prebuilt.yaml b/.github/workflows/prebuilt.yaml index d8963ec89f..921c27465b 100644 --- a/.github/workflows/prebuilt.yaml +++ b/.github/workflows/prebuilt.yaml @@ -29,7 +29,7 @@ jobs: running-workflow-name: 'build prebuilt' repo-token: ${{ secrets.GITHUB_TOKEN }} check-regexp: ^((?!.*(build master-ci).*).)*$ - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - run: git lfs pull diff --git a/.github/workflows/raylib_ui_preview.yaml b/.github/workflows/raylib_ui_preview.yaml index 18880e8a17..9044a97f53 100644 --- a/.github/workflows/raylib_ui_preview.yaml +++ b/.github/workflows/raylib_ui_preview.yaml @@ -58,7 +58,7 @@ jobs: path: ${{ github.workspace }}/pr_ui - name: Getting master ui - uses: actions/checkout@v4 + uses: actions/checkout@v6 with: repository: commaai/ci-artifacts ssh-key: ${{ secrets.CI_ARTIFACTS_DEPLOY_KEY }} diff --git a/.github/workflows/release.yaml b/.github/workflows/release.yaml index 0f4ce6cb3a..0f34dbe435 100644 --- a/.github/workflows/release.yaml +++ b/.github/workflows/release.yaml @@ -30,7 +30,7 @@ jobs: running-workflow-name: 'build master-ci' repo-token: ${{ secrets.GITHUB_TOKEN }} check-regexp: ^((?!.*(build prebuilt).*).)*$ - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true fetch-depth: 0 diff --git a/.github/workflows/repo-maintenance.yaml b/.github/workflows/repo-maintenance.yaml index b8b29e602f..810b602d71 100644 --- a/.github/workflows/repo-maintenance.yaml +++ b/.github/workflows/repo-maintenance.yaml @@ -15,7 +15,7 @@ jobs: runs-on: ubuntu-latest if: github.repository == 'commaai/openpilot' steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 - uses: ./.github/workflows/setup-with-retry - name: Update translations run: | @@ -39,7 +39,7 @@ jobs: image: ghcr.io/commaai/openpilot-base:latest if: github.repository == 'commaai/openpilot' steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - name: uv lock diff --git a/.github/workflows/stale.yaml b/.github/workflows/stale.yaml index 1ecd114dc4..cb7c0ac076 100644 --- a/.github/workflows/stale.yaml +++ b/.github/workflows/stale.yaml @@ -13,7 +13,7 @@ jobs: stale: runs-on: ubuntu-latest steps: - - uses: actions/stale@v9 + - uses: actions/stale@v10 with: exempt-all-milestones: true @@ -34,7 +34,7 @@ jobs: stale_drafts: runs-on: ubuntu-latest steps: - - uses: actions/stale@v9 + - uses: actions/stale@v10 with: exempt-all-milestones: true diff --git a/.github/workflows/tests.yaml b/.github/workflows/tests.yaml index c7da619454..4ade42b665 100644 --- a/.github/workflows/tests.yaml +++ b/.github/workflows/tests.yaml @@ -41,7 +41,7 @@ jobs: env: STRIPPED_DIR: /tmp/releasepilot steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - name: Getting LFS files @@ -77,7 +77,7 @@ jobs: && fromJSON('["namespace-profile-amd64-8x16", "namespace-experiments:docker.builds.local-cache=separate"]') || fromJSON('["ubuntu-24.04"]') }} steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - name: Setup docker push @@ -93,7 +93,7 @@ jobs: name: build macOS runs-on: ${{ ((github.repository == 'commaai/openpilot') && ((github.event_name != 'pull_request') || (github.event.pull_request.head.repo.full_name == 'commaai/openpilot'))) && 'namespace-profile-macos-8x14' || 'macos-latest' }} steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - run: echo "CACHE_COMMIT_DATE=$(git log -1 --pretty='format:%cd' --date=format:'%Y-%m-%d-%H:%M')" >> $GITHUB_ENV @@ -133,7 +133,7 @@ jobs: env: PYTHONWARNINGS: default steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - uses: ./.github/workflows/setup-with-retry @@ -150,7 +150,7 @@ jobs: && fromJSON('["namespace-profile-amd64-8x16", "namespace-experiments:docker.builds.local-cache=separate"]') || fromJSON('["ubuntu-24.04"]') }} steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - uses: ./.github/workflows/setup-with-retry @@ -175,14 +175,14 @@ jobs: && fromJSON('["namespace-profile-amd64-8x16", "namespace-experiments:docker.builds.local-cache=separate"]') || fromJSON('["ubuntu-24.04"]') }} steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - uses: ./.github/workflows/setup-with-retry id: setup-step - name: Cache test routes id: dependency-cache - uses: actions/cache@v4 + uses: actions/cache@v5 with: path: .ci_cache/comma_download_cache key: proc-replay-${{ hashFiles('selfdrive/test/process_replay/ref_commit', 'selfdrive/test/process_replay/test_processes.py') }} @@ -198,7 +198,7 @@ jobs: id: print-diff if: always() run: cat selfdrive/test/process_replay/diff.txt - - uses: actions/upload-artifact@v4 + - uses: actions/upload-artifact@v6 if: always() continue-on-error: true with: @@ -225,7 +225,7 @@ jobs: || fromJSON('["ubuntu-24.04"]') }} if: false # FIXME: Started to timeout recently steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - uses: ./.github/workflows/setup-with-retry @@ -249,7 +249,7 @@ jobs: && fromJSON('["namespace-profile-amd64-8x16", "namespace-experiments:docker.builds.local-cache=separate"]') || fromJSON('["ubuntu-24.04"]') }} steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - uses: ./.github/workflows/setup-with-retry @@ -261,7 +261,7 @@ jobs: source selfdrive/test/setup_xvfb.sh && python3 selfdrive/ui/tests/test_ui/raylib_screenshots.py" - name: Upload Raylib UI Report - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v6 with: name: raylib-report-${{ inputs.run_number || '1' }}-${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && 'master' || github.event.number }} path: selfdrive/ui/tests/test_ui/raylib_report/screenshots @@ -275,7 +275,7 @@ jobs: && fromJSON('["namespace-profile-amd64-8x16", "namespace-experiments:docker.builds.local-cache=separate"]') || fromJSON('["ubuntu-24.04"]') }} steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v6 with: submodules: true - uses: ./.github/workflows/setup-with-retry @@ -287,7 +287,7 @@ jobs: source selfdrive/test/setup_xvfb.sh && WINDOWED=1 python3 selfdrive/ui/tests/diff/replay.py" - name: Upload Raylib UI Report - uses: actions/upload-artifact@v4 + uses: actions/upload-artifact@v6 with: name: mici-raylib-report-${{ inputs.run_number || '1' }}-${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && 'master' || github.event.number }} path: selfdrive/ui/tests/diff/report From cd70e23dc3b990eecea2364c8e0b2d2ac48de7fd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 31 Jan 2026 20:15:23 -0800 Subject: [PATCH 29/46] clips: direct rendering with raylib (#36935) * good clips * replace * fix * fix font * lil more --- common/utils.py | 21 ++ system/ui/lib/application.py | 54 +++- tools/clip/run.py | 566 ++++++++++++++++++----------------- 3 files changed, 365 insertions(+), 276 deletions(-) diff --git a/common/utils.py b/common/utils.py index caa9a57958..ccc6719f5f 100644 --- a/common/utils.py +++ b/common/utils.py @@ -10,6 +10,27 @@ import zstandard as zstd LOG_COMPRESSION_LEVEL = 10 # little benefit up to level 15. level ~17 is a small step change +class Timer: + """Simple lap timer for profiling sequential operations.""" + + def __init__(self): + self._start = self._lap = time.monotonic() + self._sections = {} + + def lap(self, name): + now = time.monotonic() + self._sections[name] = now - self._lap + self._lap = now + + @property + def total(self): + return time.monotonic() - self._start + + def fmt(self, duration): + parts = ", ".join(f"{k}={v:.2f}s" + (f" ({duration/v:.0f}x)" if k == 'render' and v > 0 else "") for k, v in self._sections.items()) + total = self.total + realtime = f"{duration/total:.1f}x realtime" if total > 0 else "N/A" + return f"{duration}s in {total:.1f}s ({realtime}) | {parts}" def sudo_write(val: str, path: str) -> None: try: diff --git a/system/ui/lib/application.py b/system/ui/lib/application.py index 151f22ac12..da314a394f 100644 --- a/system/ui/lib/application.py +++ b/system/ui/lib/application.py @@ -1,6 +1,7 @@ import atexit import cffi import os +import queue import time import signal import sys @@ -40,6 +41,9 @@ PROFILE_RENDER = int(os.getenv("PROFILE_RENDER", "0")) PROFILE_STATS = int(os.getenv("PROFILE_STATS", "100")) # Number of functions to show in profile output RECORD = os.getenv("RECORD") == "1" RECORD_OUTPUT = str(Path(os.getenv("RECORD_OUTPUT", "output")).with_suffix(".mp4")) +RECORD_BITRATE = os.getenv("RECORD_BITRATE", "") # Target bitrate e.g. "2000k" +RECORD_SPEED = int(os.getenv("RECORD_SPEED", "1")) # Speed multiplier +OFFSCREEN = os.getenv("OFFSCREEN") == "1" # Disable FPS limiting for fast offline rendering GL_VERSION = """ #version 300 es @@ -213,6 +217,9 @@ class GuiApplication: self._render_texture: rl.RenderTexture | None = None self._burn_in_shader: rl.Shader | None = None self._ffmpeg_proc: subprocess.Popen | None = None + self._ffmpeg_queue: queue.Queue | None = None + self._ffmpeg_thread: threading.Thread | None = None + self._ffmpeg_stop_event: threading.Event | None = None self._textures: dict[str, rl.Texture] = {} self._target_fps: int = _DEFAULT_FPS self._last_fps_log_time: float = time.monotonic() @@ -277,25 +284,36 @@ class GuiApplication: rl.set_texture_filter(self._render_texture.texture, rl.TextureFilter.TEXTURE_FILTER_BILINEAR) if RECORD: + output_fps = fps * RECORD_SPEED ffmpeg_args = [ 'ffmpeg', '-v', 'warning', # Reduce ffmpeg log spam - '-stats', # Show encoding progress + '-nostats', # Suppress encoding progress '-f', 'rawvideo', # Input format '-pix_fmt', 'rgba', # Input pixel format '-s', f'{self._width}x{self._height}', # Input resolution '-r', str(fps), # Input frame rate '-i', 'pipe:0', # Input from stdin - '-vf', 'vflip,format=yuv420p', # Flip vertically and convert rgba to yuv420p - '-c:v', 'libx264', # Video codec - '-preset', 'ultrafast', # Encoding speed + '-vf', 'vflip,format=yuv420p', # Flip vertically and convert to yuv420p + '-r', str(output_fps), # Output frame rate (for speed multiplier) + '-c:v', 'libx264', + '-preset', 'ultrafast', + ] + if RECORD_BITRATE: + ffmpeg_args += ['-b:v', RECORD_BITRATE, '-maxrate', RECORD_BITRATE, '-bufsize', RECORD_BITRATE] + ffmpeg_args += [ '-y', # Overwrite existing file '-f', 'mp4', # Output format RECORD_OUTPUT, # Output file path ] self._ffmpeg_proc = subprocess.Popen(ffmpeg_args, stdin=subprocess.PIPE) + self._ffmpeg_queue = queue.Queue(maxsize=60) # Buffer up to 60 frames + self._ffmpeg_stop_event = threading.Event() + self._ffmpeg_thread = threading.Thread(target=self._ffmpeg_writer_thread, daemon=True) + self._ffmpeg_thread.start() - rl.set_target_fps(fps) + # OFFSCREEN disables FPS limiting for fast offline rendering (e.g. clips) + rl.set_target_fps(0 if OFFSCREEN else fps) self._target_fps = fps self._set_styles() @@ -337,6 +355,21 @@ class GuiApplication: print(f"{green}UI window ready in {elapsed_ms:.1f} ms{reset}") sys.exit(0) + def _ffmpeg_writer_thread(self): + """Background thread that writes frames to ffmpeg.""" + while True: + try: + data = self._ffmpeg_queue.get(timeout=1.0) + if data is None: # Sentinel to stop + break + self._ffmpeg_proc.stdin.write(data) + except queue.Empty: + if self._ffmpeg_stop_event.is_set(): + break + continue + except Exception: + break + def set_modal_overlay(self, overlay, callback: Callable | None = None): if self._modal_overlay.overlay is not None: if hasattr(self._modal_overlay.overlay, 'hide_event'): @@ -409,11 +442,17 @@ class GuiApplication: return texture def close_ffmpeg(self): + if self._ffmpeg_thread is not None: + # Signal thread to stop, send sentinel, then wait for it to drain + self._ffmpeg_stop_event.set() + self._ffmpeg_queue.put(None) + self._ffmpeg_thread.join(timeout=30) + if self._ffmpeg_proc is not None: self._ffmpeg_proc.stdin.flush() self._ffmpeg_proc.stdin.close() try: - self._ffmpeg_proc.wait(timeout=5) + self._ffmpeg_proc.wait(timeout=30) except subprocess.TimeoutExpired: self._ffmpeg_proc.terminate() self._ffmpeg_proc.wait() @@ -525,8 +564,7 @@ class GuiApplication: image = rl.load_image_from_texture(self._render_texture.texture) data_size = image.width * image.height * 4 data = bytes(rl.ffi.buffer(image.data, data_size)) - self._ffmpeg_proc.stdin.write(data) - self._ffmpeg_proc.stdin.flush() + self._ffmpeg_queue.put(data) # Async write via background thread rl.unload_image(image) self._monitor_fps() diff --git a/tools/clip/run.py b/tools/clip/run.py index 9045a4381b..324ee66690 100755 --- a/tools/clip/run.py +++ b/tools/clip/run.py @@ -1,310 +1,340 @@ #!/usr/bin/env python3 - -import logging import os -import platform -import shutil import sys import time -from argparse import ArgumentParser, ArgumentTypeError -from collections.abc import Sequence +import logging +import subprocess +import threading +import queue +import multiprocessing +import itertools +import numpy as np +import tqdm +from argparse import ArgumentParser from pathlib import Path -from random import randint -from subprocess import Popen -from typing import Literal +from concurrent.futures import ThreadPoolExecutor, as_completed -from cereal.messaging import SubMaster -from openpilot.common.basedir import BASEDIR -from openpilot.common.params import Params, UnknownKeyName -from openpilot.common.prefix import OpenpilotPrefix -from openpilot.common.utils import managed_proc from openpilot.tools.lib.route import Route from openpilot.tools.lib.logreader import LogReader +from openpilot.tools.lib.filereader import FileReader +from openpilot.tools.lib.framereader import FrameReader, ffprobe +from openpilot.selfdrive.test.process_replay.migration import migrate_all +from openpilot.common.prefix import OpenpilotPrefix +from openpilot.common.utils import Timer +from msgq.visionipc import VisionIpcServer, VisionStreamType -DEFAULT_OUTPUT = 'output.mp4' -DEMO_START = 90 -DEMO_END = 105 -DEMO_ROUTE = 'a2a0ccea32023010/2023-07-27--13-01-19' FRAMERATE = 20 -PIXEL_DEPTH = '24' -RESOLUTION = '2160x1080' -SECONDS_TO_WARM = 2 -PROC_WAIT_SECONDS = 30*10 +DEMO_ROUTE, DEMO_START, DEMO_END = 'a2a0ccea32023010/2023-07-27--13-01-19', 90, 105 -OPENPILOT_FONT = str(Path(BASEDIR, 'selfdrive/assets/fonts/Inter-Regular.ttf').resolve()) -REPLAY = str(Path(BASEDIR, 'tools/replay/replay').resolve()) -UI = str(Path(BASEDIR, 'selfdrive/ui/ui').resolve()) - -logger = logging.getLogger('clip.py') +logger = logging.getLogger('clip') -def check_for_failure(procs: list[Popen]): - for proc in procs: - exit_code = proc.poll() - if exit_code is not None and exit_code != 0: - cmd = str(proc.args) - if isinstance(proc.args, str): - cmd = proc.args - elif isinstance(proc.args, Sequence): - cmd = str(proc.args[0]) - msg = f'{cmd} failed, exit code {exit_code}' - logger.error(msg) - stdout, stderr = proc.communicate() - if stdout: - logger.error(stdout.decode()) - if stderr: - logger.error(stderr.decode()) - raise ChildProcessError(msg) - - -def escape_ffmpeg_text(value: str): - special_chars = {',': '\\,', ':': '\\:', '=': '\\=', '[': '\\[', ']': '\\]'} - value = value.replace('\\', '\\\\\\\\\\\\\\\\') - for char, escaped in special_chars.items(): - value = value.replace(char, escaped) - return value - - -def get_logreader(route: Route): - return LogReader(route.qlog_paths()[0] if len(route.qlog_paths()) else route.name.canonical_name) - - -def get_meta_text(lr: LogReader, route: Route): - init_data = lr.first('initData') - car_params = lr.first('carParams') - origin_parts = init_data.gitRemote.split('/') - origin = origin_parts[3] if len(origin_parts) > 3 else 'unknown' - return ', '.join([ - f"openpilot v{init_data.version}", - f"route: {route.name.canonical_name}", - f"car: {car_params.carFingerprint}", - f"origin: {origin}", - f"branch: {init_data.gitBranch}", - f"commit: {init_data.gitCommit[:7]}", - f"modified: {str(init_data.dirty).lower()}", - ]) - - -def parse_args(parser: ArgumentParser): +def parse_args(): + parser = ArgumentParser(description="Direct clip renderer") + parser.add_argument("route", nargs="?", help="Route ID (dongle/route or dongle/route/start/end)") + parser.add_argument("-s", "--start", type=int, help="Start time in seconds") + parser.add_argument("-e", "--end", type=int, help="End time in seconds") + parser.add_argument("-o", "--output", default="output.mp4", help="Output file path") + parser.add_argument("-d", "--data-dir", help="Local directory with route data") + parser.add_argument("-t", "--title", help="Title overlay text") + parser.add_argument("-f", "--file-size", type=float, default=9.0, help="Target file size in MB") + parser.add_argument("-x", "--speed", type=int, default=1, help="Speed multiplier") + parser.add_argument("--demo", action="store_true", help="Use demo route with default timing") + parser.add_argument("--big", action="store_true", default=True, help="Use big UI (2160x1080)") + parser.add_argument("--qcam", action="store_true", help="Use qcamera instead of fcamera") + parser.add_argument("--windowed", action="store_true", help="Show window") + parser.add_argument("--no-metadata", action="store_true", help="Disable metadata overlay") + parser.add_argument("--no-time-overlay", action="store_true", help="Disable time overlay") args = parser.parse_args() + if args.demo: - args.route = DEMO_ROUTE - if args.start is None or args.end is None: - args.start = DEMO_START - args.end = DEMO_END - elif args.route.count('/') == 1: - if args.start is None or args.end is None: - parser.error('must provide both start and end if timing is not in the route ID') - elif args.route.count('/') == 3: - if args.start is not None or args.end is not None: - parser.error('don\'t provide timing when including it in the route ID') + args.route, args.start, args.end = args.route or DEMO_ROUTE, args.start or DEMO_START, args.end or DEMO_END + elif not args.route: + parser.error("route is required (or use --demo)") + + if args.route and args.route.count('/') == 3: parts = args.route.split('/') - args.route = '/'.join(parts[:2]) - args.start = int(parts[2]) - args.end = int(parts[3]) + args.route, args.start, args.end = '/'.join(parts[:2]), args.start or int(parts[2]), args.end or int(parts[3]) + + if args.start is None or args.end is None: + parser.error("--start and --end are required") if args.end <= args.start: - parser.error(f'end ({args.end}) must be greater than start ({args.start})') - if args.start < SECONDS_TO_WARM: - parser.error(f'start must be greater than {SECONDS_TO_WARM}s to allow the UI time to warm up') - - try: - args.route = Route(args.route, data_dir=args.data_dir) - except Exception as e: - parser.error(f'failed to get route: {e}') - - # FIXME: length isn't exactly max segment seconds, simplify to replay exiting at end of data - length = round(args.route.max_seg_number * 60) - if args.start >= length: - parser.error(f'start ({args.start}s) cannot be after end of route ({length}s)') - if args.end > length: - parser.error(f'end ({args.end}s) cannot be after end of route ({length}s)') - + parser.error(f"end ({args.end}) must be greater than start ({args.start})") return args -def populate_car_params(lr: LogReader): - init_data = lr.first('initData') - assert init_data is not None +def setup_env(output_path: str, big: bool = False, speed: int = 1, target_mb: float = 0, duration: int = 0): + os.environ.update({"RECORD": "1", "OFFSCREEN": "1", "RECORD_OUTPUT": str(Path(output_path).with_suffix(".mp4"))}) + if speed > 1: + os.environ["RECORD_SPEED"] = str(speed) + if target_mb > 0 and duration > 0: + os.environ["RECORD_BITRATE"] = f"{int(target_mb * 8 * 1024 / (duration / speed))}k" + if big: + os.environ["BIG"] = "1" + + +def _download_segment(path: str) -> bytes: + with FileReader(path) as f: + return bytes(f.read()) + + +def _parse_and_chunk_segment(args: tuple) -> list[dict]: + raw_data, fps = args + from openpilot.tools.lib.logreader import _LogFileReader + messages = migrate_all(list(_LogFileReader("", dat=raw_data, sort_by_time=True))) + if not messages: + return [] + + dt_ns, chunks, current, next_time = 1e9 / fps, [], {}, messages[0].logMonoTime + 1e9 / fps # type: ignore[var-annotated] + for msg in messages: + if msg.logMonoTime >= next_time: + chunks.append(current) + current, next_time = {}, next_time + dt_ns * ((msg.logMonoTime - next_time) // dt_ns + 1) + current[msg.which()] = msg + return chunks + [current] if current else chunks + + +def load_logs_parallel(log_paths: list[str], fps: int = 20) -> list[dict]: + num_workers = min(16, len(log_paths), (multiprocessing.cpu_count() or 1)) + logger.info(f"Downloading {len(log_paths)} segments with {num_workers} workers...") + + with ThreadPoolExecutor(max_workers=num_workers) as pool: + futures = {pool.submit(_download_segment, path): idx for idx, path in enumerate(log_paths)} + raw_data = {futures[f]: f.result() for f in as_completed(futures)} + + logger.info("Parsing and chunking segments...") + with multiprocessing.Pool(num_workers) as pool: + return list(itertools.chain.from_iterable(pool.map(_parse_and_chunk_segment, [(raw_data[i], fps) for i in range(len(log_paths))]))) + + +def patch_submaster(message_chunks, ui_state): + # Reset started_frame so alerts render correctly (recv_frame must be >= started_frame) + ui_state.started_frame = 0 + ui_state.started_time = time.monotonic() + + def mock_update(timeout=None): + sm, t = ui_state.sm, time.monotonic() + sm.updated = dict.fromkeys(sm.services, False) + if sm.frame < len(message_chunks): + for svc, msg in message_chunks[sm.frame].items(): + if svc in sm.data: + sm.seen[svc] = sm.updated[svc] = sm.alive[svc] = sm.valid[svc] = True + sm.data[svc] = getattr(msg.as_builder(), svc) + sm.logMonoTime[svc], sm.recv_time[svc], sm.recv_frame[svc] = msg.logMonoTime, t, sm.frame + sm.frame += 1 + ui_state.sm.update = mock_update + + +def get_frame_dimensions(camera_path: str) -> tuple[int, int]: + """Get frame dimensions from a video file using ffprobe.""" + probe = ffprobe(camera_path) + stream = probe["streams"][0] + return stream["width"], stream["height"] + + +def iter_segment_frames(camera_paths, start_time, end_time, fps=20, use_qcam=False, frame_size: tuple[int, int] | None = None): + frames_per_seg = fps * 60 + start_frame, end_frame = int(start_time * fps), int(end_time * fps) + current_seg: int = -1 + seg_frames: FrameReader | np.ndarray | None = None + + for global_idx in range(start_frame, end_frame): + seg_idx, local_idx = global_idx // frames_per_seg, global_idx % frames_per_seg + + if seg_idx != current_seg: + current_seg = seg_idx + path = camera_paths[seg_idx] if seg_idx < len(camera_paths) else None + if not path: + raise RuntimeError(f"No camera file for segment {seg_idx}") + + if use_qcam: + w, h = frame_size or get_frame_dimensions(path) + with FileReader(path) as f: + result = subprocess.run(["ffmpeg", "-v", "quiet", "-i", "-", "-f", "rawvideo", "-pix_fmt", "nv12", "-"], + input=f.read(), capture_output=True) + if result.returncode != 0: + raise RuntimeError(f"ffmpeg failed: {result.stderr.decode()}") + seg_frames = np.frombuffer(result.stdout, dtype=np.uint8).reshape(-1, w * h * 3 // 2) + else: + seg_frames = FrameReader(path, pix_fmt="nv12") + + assert seg_frames is not None + frame = seg_frames[local_idx] if use_qcam else seg_frames.get(local_idx) # type: ignore[index, union-attr] + yield global_idx, frame + + +class FrameQueue: + def __init__(self, camera_paths, start_time, end_time, fps=20, prefetch_count=60, use_qcam=False): + # Probe first valid camera file for dimensions + first_path = next((p for p in camera_paths if p), None) + if not first_path: + raise RuntimeError("No valid camera paths") + self.frame_w, self.frame_h = get_frame_dimensions(first_path) + + self._queue, self._stop, self._error = queue.Queue(maxsize=prefetch_count), threading.Event(), None + self._thread = threading.Thread(target=self._worker, + args=(camera_paths, start_time, end_time, fps, use_qcam, (self.frame_w, self.frame_h)), daemon=True) + self._thread.start() + + def _worker(self, camera_paths, start_time, end_time, fps, use_qcam, frame_size): + try: + for idx, data in iter_segment_frames(camera_paths, start_time, end_time, fps, use_qcam, frame_size): + if self._stop.is_set(): + break + self._queue.put((idx, data.tobytes())) + except Exception as e: + logger.exception("Decode error") + self._error = e + finally: + self._queue.put(None) + + def get(self, timeout=60.0): + if self._error: + raise self._error + result = self._queue.get(timeout=timeout) + if result is None: + raise StopIteration("No more frames") + return result + + def stop(self): + self._stop.set() + while not self._queue.empty(): + try: + self._queue.get_nowait() + except queue.Empty: + break + self._thread.join(timeout=2.0) + + +def load_route_metadata(route): + from openpilot.common.params import Params, UnknownKeyName + lr = LogReader(route.log_paths()[0]) + init_data, car_params = lr.first('initData'), lr.first('carParams') params = Params() - entries = init_data.params.entries - for cp in entries: - key, value = cp.key, cp.value + for entry in init_data.params.entries: try: - params.put(key, params.cpp2python(key, value)) + params.put(entry.key, params.cpp2python(entry.key, entry.value)) except UnknownKeyName: - # forks of openpilot may have other Params keys configured. ignore these - logger.warning(f"unknown Params key '{key}', skipping") - logger.debug('persisted CarParams') + pass + + origin = init_data.gitRemote.split('/')[3] if len(init_data.gitRemote.split('/')) > 3 else 'unknown' + return { + 'version': init_data.version, 'route': route.name.canonical_name, + 'car': car_params.carFingerprint if car_params else 'unknown', 'origin': origin, + 'branch': init_data.gitBranch, 'commit': init_data.gitCommit[:7], 'modified': str(init_data.dirty).lower(), + } -def validate_env(parser: ArgumentParser): - if platform.system() not in ['Linux']: - parser.exit(1, f'clip.py: error: {platform.system()} is not a supported operating system\n') - for proc in ['Xvfb', 'ffmpeg']: - if shutil.which(proc) is None: - parser.exit(1, f'clip.py: error: missing {proc} command, is it installed?\n') - for proc in [REPLAY, UI]: - if shutil.which(proc) is None: - parser.exit(1, f'clip.py: error: missing {proc} command, did you build openpilot yet?\n') +def draw_text_box(rl, text, x, y, size, gui_app, font, font_scale, color=None, center=False): + box_color, text_color = rl.Color(0, 0, 0, 85), color or rl.WHITE + # measure_text_ex is NOT auto-scaled, so multiply by font_scale + # draw_text_ex IS auto-scaled, so pass size directly + text_size = rl.measure_text_ex(font, text, size * font_scale, 0) + text_width, text_height = int(text_size.x), int(text_size.y) + if center: + x = (gui_app.width - text_width) // 2 + rl.draw_rectangle(x - 8, y - 4, text_width + 16, text_height + 8, box_color) + rl.draw_text_ex(font, text, rl.Vector2(x, y), size, 0, text_color) -def validate_output_file(output_file: str): - if not output_file.endswith('.mp4'): - raise ArgumentTypeError('output must be an mp4') - return output_file +def render_overlays(rl, gui_app, font, font_scale, metadata, title, start_time, frame_idx, show_metadata, show_time): + if show_metadata and metadata and frame_idx < FRAMERATE * 5: + m = metadata + text = ", ".join([f"openpilot v{m['version']}", f"route: {m['route']}", f"car: {m['car']}", f"origin: {m['origin']}", + f"branch: {m['branch']}", f"commit: {m['commit']}", f"modified: {m['modified']}"]) + # Truncate if too wide (leave 20px margin on each side) + max_width = gui_app.width - 40 + while rl.measure_text_ex(font, text, 15 * font_scale, 0).x > max_width and len(text) > 20: + text = text[:-4] + "..." + draw_text_box(rl, text, 0, 8, 15, gui_app, font, font_scale, center=True) - -def validate_route(route: str): - if route.count('/') not in (1, 3): - raise ArgumentTypeError(f'route must include or exclude timing, example: {DEMO_ROUTE}') - return route - - -def validate_title(title: str): - if len(title) > 80: - raise ArgumentTypeError('title must be no longer than 80 chars') - return title - - -def wait_for_frames(procs: list[Popen]): - sm = SubMaster(['uiDebug']) - no_frames_drawn = True - while no_frames_drawn: - sm.update() - no_frames_drawn = sm['uiDebug'].drawTimeMillis == 0. - check_for_failure(procs) - - -def clip( - data_dir: str | None, - quality: Literal['low', 'high'], - prefix: str, - route: Route, - out: str, - start: int, - end: int, - speed: int, - target_mb: int, - title: str | None, -): - logger.info(f'clipping route {route.name.canonical_name}, start={start} end={end} quality={quality} target_filesize={target_mb}MB') - lr = get_logreader(route) - - begin_at = max(start - SECONDS_TO_WARM, 0) - duration = end - start - bit_rate_kbps = int(round(target_mb * 8 * 1024 * 1024 / duration / 1000)) - - # TODO: evaluate creating fn that inspects /tmp/.X11-unix and creates unused display to avoid possibility of collision - display = f':{randint(99, 999)}' - - box_style = 'box=1:boxcolor=black@0.33:boxborderw=7' - meta_text = get_meta_text(lr, route) - overlays = [ - # metadata overlay - f"drawtext=text='{escape_ffmpeg_text(meta_text)}':fontfile={OPENPILOT_FONT}:fontcolor=white:fontsize=15:{box_style}:x=(w-text_w)/2:y=5.5:enable='between(t,1,5)'", - # route time overlay - f"drawtext=text='%{{eif\\:floor(({start}+t)/60)\\:d\\:2}}\\:%{{eif\\:mod({start}+t\\,60)\\:d\\:2}}':fontfile={OPENPILOT_FONT}:fontcolor=white:fontsize=24:{box_style}:x=w-text_w-38:y=38" - ] if title: - overlays.append(f"drawtext=text='{escape_ffmpeg_text(title)}':fontfile={OPENPILOT_FONT}:fontcolor=white:fontsize=32:{box_style}:x=(w-text_w)/2:y=53") + draw_text_box(rl, title, 0, 60, 32, gui_app, font, font_scale, center=True) - if speed > 1: - overlays += [ - f"setpts=PTS/{speed}", - "fps=60", - ] + if show_time: + t = start_time + frame_idx / FRAMERATE + time_text = f"{int(t)//60:02d}:{int(t)%60:02d}" + time_width = int(rl.measure_text_ex(font, time_text, 24 * font_scale, 0).x) + draw_text_box(rl, time_text, gui_app.width - time_width - 45, 45, 24, gui_app, font, font_scale) - ffmpeg_cmd = [ - 'ffmpeg', '-y', - '-video_size', RESOLUTION, - '-framerate', str(FRAMERATE), - '-f', 'x11grab', - '-rtbufsize', '100M', - '-draw_mouse', '0', - '-i', display, - '-c:v', 'libx264', - '-maxrate', f'{bit_rate_kbps}k', - '-bufsize', f'{bit_rate_kbps*2}k', - '-crf', '23', - '-filter:v', ','.join(overlays), - '-preset', 'ultrafast', - '-tune', 'zerolatency', - '-pix_fmt', 'yuv420p', - '-movflags', '+faststart', - '-f', 'mp4', - '-t', str(duration), - out, - ] - replay_cmd = [REPLAY, '--ecam', '-c', '1', '-s', str(begin_at), '--prefix', prefix] - if data_dir: - replay_cmd.extend(['--data_dir', data_dir]) - if quality == 'low': - replay_cmd.append('--qcam') - replay_cmd.append(route.name.canonical_name) +def clip(route: Route, output: str, start: int, end: int, headless: bool = True, big: bool = False, + title: str | None = None, show_metadata: bool = True, show_time: bool = True, use_qcam: bool = False): + timer, duration = Timer(), end - start - ui_cmd = [UI, '-platform', 'xcb'] - xvfb_cmd = ['Xvfb', display, '-terminate', '-screen', '0', f'{RESOLUTION}x{PIXEL_DEPTH}'] + import pyray as rl + if big: + from openpilot.selfdrive.ui.layouts.main import MainLayout + else: + from openpilot.selfdrive.ui.mici.layouts.main import MiciMainLayout as MainLayout # type: ignore[assignment] + from openpilot.selfdrive.ui.ui_state import ui_state + from openpilot.system.ui.lib.application import gui_app, FontWeight, FONT_SCALE + timer.lap("import") - with OpenpilotPrefix(prefix, shared_download_cache=True): - populate_car_params(lr) - env = os.environ.copy() - env['DISPLAY'] = display + logger.info(f"Clipping {route.name.canonical_name}, {start}s-{end}s ({duration}s)") + seg_start, seg_end = start // 60, (end - 1) // 60 + 1 + all_chunks = load_logs_parallel(route.log_paths()[seg_start:seg_end], fps=FRAMERATE) + timer.lap("logs") - with managed_proc(xvfb_cmd, env) as xvfb_proc, managed_proc(ui_cmd, env) as ui_proc, managed_proc(replay_cmd, env) as replay_proc: - procs = [xvfb_proc, ui_proc, replay_proc] - logger.info('waiting for replay to begin (loading segments, may take a while)...') - wait_for_frames(procs) - logger.debug(f'letting UI warm up ({SECONDS_TO_WARM}s)...') - time.sleep(SECONDS_TO_WARM) - check_for_failure(procs) - with managed_proc(ffmpeg_cmd, env) as ffmpeg_proc: - procs.append(ffmpeg_proc) - logger.info(f'recording in progress ({duration}s)...') - ffmpeg_proc.wait(duration + PROC_WAIT_SECONDS) - check_for_failure(procs) - logger.info(f'recording complete: {Path(out).resolve()}') + frame_start = (start - seg_start * 60) * FRAMERATE + message_chunks = all_chunks[frame_start:frame_start + duration * FRAMERATE] + if not message_chunks: + logger.error("No messages to render") + sys.exit(1) + + metadata = load_route_metadata(route) if show_metadata else None + if headless: + rl.set_config_flags(rl.ConfigFlags.FLAG_WINDOW_HIDDEN) + + with OpenpilotPrefix(shared_download_cache=True): + camera_paths = route.qcamera_paths() if use_qcam else route.camera_paths() + frame_queue = FrameQueue(camera_paths, start, end, fps=FRAMERATE, use_qcam=use_qcam) + + vipc = VisionIpcServer("camerad") + vipc.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 4, frame_queue.frame_w, frame_queue.frame_h) + vipc.start_listener() + + patch_submaster(message_chunks, ui_state) + gui_app.init_window("clip", fps=FRAMERATE) + + main_layout = MainLayout() + main_layout.set_rect(rl.Rectangle(0, 0, gui_app.width, gui_app.height)) + font = gui_app.font(FontWeight.NORMAL) + timer.lap("setup") + + frame_idx = 0 + with tqdm.tqdm(total=len(message_chunks), desc="Rendering", unit="frame") as pbar: + for should_render in gui_app.render(): + if frame_idx >= len(message_chunks): + break + _, frame_bytes = frame_queue.get() + vipc.send(VisionStreamType.VISION_STREAM_ROAD, frame_bytes, frame_idx, int(frame_idx * 5e7), int(frame_idx * 5e7)) + ui_state.update() + if should_render: + main_layout.render() + render_overlays(rl, gui_app, font, FONT_SCALE, metadata, title, start, frame_idx, show_metadata, show_time) + frame_idx += 1 + pbar.update(1) + timer.lap("render") + + frame_queue.stop() + gui_app.close() + timer.lap("ffmpeg") + + logger.info(f"Clip saved to: {Path(output).resolve()}") + logger.info(f"Generated {timer.fmt(duration)}") def main(): - p = ArgumentParser(prog='clip.py', description='clip your openpilot route.', epilog='comma.ai') - validate_env(p) - route_group = p.add_mutually_exclusive_group(required=True) - route_group.add_argument('route', nargs='?', type=validate_route, help=f'The route (e.g. {DEMO_ROUTE} or {DEMO_ROUTE}/{DEMO_START}/{DEMO_END})') - route_group.add_argument('--demo', help='use the demo route', action='store_true') - p.add_argument('-d', '--data-dir', help='local directory where route data is stored') - p.add_argument('-e', '--end', help='stop clipping at seconds', type=int) - p.add_argument('-f', '--file-size', help='target file size (Discord/GitHub support max 10MB, default is 9MB)', type=float, default=9.) - p.add_argument('-o', '--output', help='output clip to (.mp4)', type=validate_output_file, default=DEFAULT_OUTPUT) - p.add_argument('-p', '--prefix', help='openpilot prefix', default=f'clip_{randint(100, 99999)}') - p.add_argument('-q', '--quality', help='quality of camera (low = qcam, high = hevc)', choices=['low', 'high'], default='high') - p.add_argument('-x', '--speed', help='record the clip at this speed multiple', type=int, default=1) - p.add_argument('-s', '--start', help='start clipping at seconds', type=int) - p.add_argument('-t', '--title', help='overlay this title on the video (e.g. "Chill driving across the Golden Gate Bridge")', type=validate_title) - args = parse_args(p) - exit_code = 1 - try: - clip( - data_dir=args.data_dir, - quality=args.quality, - prefix=args.prefix, - route=args.route, - out=args.output, - start=args.start, - end=args.end, - speed=args.speed, - target_mb=args.file_size, - title=args.title, - ) - exit_code = 0 - except KeyboardInterrupt as e: - logger.exception('interrupted by user', exc_info=e) - except Exception as e: - logger.exception('encountered error', exc_info=e) - sys.exit(exit_code) + logging.basicConfig(level=logging.INFO, format="%(asctime)s %(levelname)s\t%(message)s") + args = parse_args() + assert args.big, "Clips doesn't support mici UI yet. TODO: make it work" + + setup_env(args.output, big=args.big, speed=args.speed, target_mb=args.file_size, duration=args.end - args.start) + clip(Route(args.route, data_dir=args.data_dir), args.output, args.start, args.end, not args.windowed, + args.big, args.title, not args.no_metadata, not args.no_time_overlay, args.qcam) -if __name__ == '__main__': - logging.basicConfig(level=logging.INFO, format='%(asctime)s %(name)s %(levelname)s\t%(message)s') +if __name__ == "__main__": main() From e76e1e500c07a02a1b534f85238ee1ab0a441d41 Mon Sep 17 00:00:00 2001 From: Trey Moen <50057480+greatgitsby@users.noreply.github.com> Date: Sun, 1 Feb 2026 14:21:00 -0700 Subject: [PATCH 30/46] clips: use AugmentedRoadView instead of MainLayout (#37053) Render only the road view in clips rather than the full main layout, matching the updated UI module structure. --- tools/clip/run.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/tools/clip/run.py b/tools/clip/run.py index 324ee66690..5fb693f30a 100755 --- a/tools/clip/run.py +++ b/tools/clip/run.py @@ -265,9 +265,9 @@ def clip(route: Route, output: str, start: int, end: int, headless: bool = True, import pyray as rl if big: - from openpilot.selfdrive.ui.layouts.main import MainLayout + from openpilot.selfdrive.ui.onroad.augmented_road_view import AugmentedRoadView else: - from openpilot.selfdrive.ui.mici.layouts.main import MiciMainLayout as MainLayout # type: ignore[assignment] + from openpilot.selfdrive.ui.mici.onroad.augmented_road_view import AugmentedRoadView # type: ignore[assignment] from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.system.ui.lib.application import gui_app, FontWeight, FONT_SCALE timer.lap("import") @@ -298,8 +298,8 @@ def clip(route: Route, output: str, start: int, end: int, headless: bool = True, patch_submaster(message_chunks, ui_state) gui_app.init_window("clip", fps=FRAMERATE) - main_layout = MainLayout() - main_layout.set_rect(rl.Rectangle(0, 0, gui_app.width, gui_app.height)) + road_view = AugmentedRoadView() + road_view.set_rect(rl.Rectangle(0, 0, gui_app.width, gui_app.height)) font = gui_app.font(FontWeight.NORMAL) timer.lap("setup") @@ -312,7 +312,7 @@ def clip(route: Route, output: str, start: int, end: int, headless: bool = True, vipc.send(VisionStreamType.VISION_STREAM_ROAD, frame_bytes, frame_idx, int(frame_idx * 5e7), int(frame_idx * 5e7)) ui_state.update() if should_render: - main_layout.render() + road_view.render() render_overlays(rl, gui_app, font, FONT_SCALE, metadata, title, start, frame_idx, show_metadata, show_time) frame_idx += 1 pbar.update(1) From 0a84b004065edfa2f0efaedad329b3853409c316 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 1 Feb 2026 13:36:55 -0800 Subject: [PATCH 31/46] fix up status for in progress builds --- scripts/ci_results.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/scripts/ci_results.py b/scripts/ci_results.py index c3d53f222a..a133541c69 100755 --- a/scripts/ci_results.py +++ b/scripts/ci_results.py @@ -143,6 +143,9 @@ def format_markdown(gh_status, gh_run_id, jenkins_status, commit_sha, branch): lines.append(f"| {stage['name']} | {icon} {stage['status'].lower()} |") if stage["status"] == "FAILED": failed_jenkins_stages.append(stage["name"]) + # Show overall build status if still in progress + if jenkins_status["in_progress"]: + lines.append("| (build in progress) | :hourglass: in_progress |") else: icon = ":hourglass:" if jenkins_status["in_progress"] else ( ":white_check_mark:" if jenkins_status["result"] == "SUCCESS" else ":x:") From 7a990b99f7e2a714ee00b7f0e7955dd588f3c88e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 1 Feb 2026 15:07:22 -0800 Subject: [PATCH 32/46] rm future-fstrings package (#37056) --- pyproject.toml | 1 - uv.lock | 11 ----------- 2 files changed, 12 deletions(-) diff --git a/pyproject.toml b/pyproject.toml index 9a70f69d26..57fd0b8355 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -58,7 +58,6 @@ dependencies = [ # acados deps "casadi >=3.6.6", # 3.12 fixed in 3.6.6 - "future-fstrings", # joystickd "inputs", diff --git a/uv.lock b/uv.lock index b221995b85..e488d1d78b 100644 --- a/uv.lock +++ b/uv.lock @@ -633,15 +633,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9a/9a/e35b4a917281c0b8419d4207f4334c8e8c5dbf4f3f5f9ada73958d937dcc/frozenlist-1.8.0-py3-none-any.whl", hash = "sha256:0c18a16eab41e82c295618a77502e17b195883241c563b00f0aa5106fc4eaa0d", size = 13409, upload-time = "2025-10-06T05:38:16.721Z" }, ] -[[package]] -name = "future-fstrings" -version = "1.2.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/5d/e2/3874574cce18a2e3608abfe5b4b5b3c9765653c464f5da18df8971cf501d/future_fstrings-1.2.0.tar.gz", hash = "sha256:6cf41cbe97c398ab5a81168ce0dbb8ad95862d3caf23c21e4430627b90844089", size = 5786, upload-time = "2019-06-16T03:04:42.651Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/ab/6d/ea1d52e9038558dd37f5d30647eb9f07888c164960a5d4daa5f970c6da25/future_fstrings-1.2.0-py2.py3-none-any.whl", hash = "sha256:90e49598b553d8746c4dc7d9442e0359d038c3039d802c91c0a55505da318c63", size = 6138, upload-time = "2019-06-16T03:04:40.395Z" }, -] - [[package]] name = "ghp-import" version = "2.1.0" @@ -1302,7 +1293,6 @@ dependencies = [ { name = "cffi" }, { name = "crcmod-plus" }, { name = "cython" }, - { name = "future-fstrings" }, { name = "inputs" }, { name = "json-rpc" }, { name = "kaitaistruct" }, @@ -1396,7 +1386,6 @@ requires-dist = [ { name = "cython" }, { name = "dearpygui", marker = "(platform_machine != 'aarch64' and extra == 'tools') or (sys_platform != 'linux' and extra == 'tools')", specifier = ">=2.1.0" }, { name = "dictdiffer", marker = "extra == 'dev'" }, - { name = "future-fstrings" }, { name = "hypothesis", marker = "extra == 'testing'", specifier = "==6.47.*" }, { name = "inputs" }, { name = "jeepney", marker = "extra == 'dev'" }, From 422de598984a26225ba729546852a2e5eb000eeb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 1 Feb 2026 15:24:42 -0800 Subject: [PATCH 33/46] acados: strip future-fstrings declaration (#37057) * Revert "rm future-fstrings package (#37056)" This reverts commit 7a990b99f7e2a714ee00b7f0e7955dd588f3c88e. * Reapply "rm future-fstrings package (#37056)" This reverts commit 8b93f6646eed6863ad67b9bab558d305ecb8b7b4. * strip it * cleanup --- third_party/acados/acados_template/acados_ocp.py | 1 - third_party/acados/acados_template/acados_ocp_solver.py | 1 - .../acados/acados_template/acados_ocp_solver_pyx.pyx | 1 - third_party/acados/acados_template/acados_sim.py | 1 - third_party/acados/acados_template/acados_sim_solver.py | 1 - .../acados/acados_template/acados_sim_solver_common.pxd | 1 - .../acados/acados_template/acados_sim_solver_pyx.pyx | 1 - third_party/acados/acados_template/acados_solver_common.pxd | 1 - third_party/acados/acados_template/builders.py | 1 - third_party/acados/acados_template/gnsf/__init__.py | 0 third_party/acados/acados_template/utils.py | 1 - third_party/acados/build.sh | 6 ++++++ 12 files changed, 6 insertions(+), 10 deletions(-) delete mode 100644 third_party/acados/acados_template/gnsf/__init__.py diff --git a/third_party/acados/acados_template/acados_ocp.py b/third_party/acados/acados_template/acados_ocp.py index ec02822ceb..d6236e1f6e 100644 --- a/third_party/acados/acados_template/acados_ocp.py +++ b/third_party/acados/acados_template/acados_ocp.py @@ -1,4 +1,3 @@ -# -*- coding: future_fstrings -*- # # Copyright (c) The acados authors. # diff --git a/third_party/acados/acados_template/acados_ocp_solver.py b/third_party/acados/acados_template/acados_ocp_solver.py index ffc9cf4b0e..229bdf6039 100644 --- a/third_party/acados/acados_template/acados_ocp_solver.py +++ b/third_party/acados/acados_template/acados_ocp_solver.py @@ -1,4 +1,3 @@ -# -*- coding: future_fstrings -*- # # Copyright (c) The acados authors. # diff --git a/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx b/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx index acd7f02d0a..bc03ba086f 100644 --- a/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx +++ b/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx @@ -1,4 +1,3 @@ -# -*- coding: future_fstrings -*- # # Copyright (c) The acados authors. # diff --git a/third_party/acados/acados_template/acados_sim.py b/third_party/acados/acados_template/acados_sim.py index c0d6937a49..7faa49fb12 100644 --- a/third_party/acados/acados_template/acados_sim.py +++ b/third_party/acados/acados_template/acados_sim.py @@ -1,4 +1,3 @@ -# -*- coding: future_fstrings -*- # # Copyright (c) The acados authors. # diff --git a/third_party/acados/acados_template/acados_sim_solver.py b/third_party/acados/acados_template/acados_sim_solver.py index 612f439eaf..de5ee10709 100644 --- a/third_party/acados/acados_template/acados_sim_solver.py +++ b/third_party/acados/acados_template/acados_sim_solver.py @@ -1,4 +1,3 @@ -# -*- coding: future_fstrings -*- # # Copyright (c) The acados authors. # diff --git a/third_party/acados/acados_template/acados_sim_solver_common.pxd b/third_party/acados/acados_template/acados_sim_solver_common.pxd index cc6a58efd7..7c20a6d24d 100644 --- a/third_party/acados/acados_template/acados_sim_solver_common.pxd +++ b/third_party/acados/acados_template/acados_sim_solver_common.pxd @@ -1,4 +1,3 @@ -# -*- coding: future_fstrings -*- # # Copyright (c) The acados authors. # diff --git a/third_party/acados/acados_template/acados_sim_solver_pyx.pyx b/third_party/acados/acados_template/acados_sim_solver_pyx.pyx index be400addc7..01964fd7a0 100644 --- a/third_party/acados/acados_template/acados_sim_solver_pyx.pyx +++ b/third_party/acados/acados_template/acados_sim_solver_pyx.pyx @@ -1,4 +1,3 @@ -# -*- coding: future_fstrings -*- # # Copyright (c) The acados authors. # diff --git a/third_party/acados/acados_template/acados_solver_common.pxd b/third_party/acados/acados_template/acados_solver_common.pxd index c6d59d40a5..75d021626f 100644 --- a/third_party/acados/acados_template/acados_solver_common.pxd +++ b/third_party/acados/acados_template/acados_solver_common.pxd @@ -1,4 +1,3 @@ -# -*- coding: future_fstrings -*- # # Copyright (c) The acados authors. # diff --git a/third_party/acados/acados_template/builders.py b/third_party/acados/acados_template/builders.py index 6f21bfe8cd..8acc05b528 100644 --- a/third_party/acados/acados_template/builders.py +++ b/third_party/acados/acados_template/builders.py @@ -1,4 +1,3 @@ -# -*- coding: future_fstrings -*- # # Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, # Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, diff --git a/third_party/acados/acados_template/gnsf/__init__.py b/third_party/acados/acados_template/gnsf/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/third_party/acados/acados_template/utils.py b/third_party/acados/acados_template/utils.py index d6f6c02f84..f27617fa30 100644 --- a/third_party/acados/acados_template/utils.py +++ b/third_party/acados/acados_template/utils.py @@ -1,4 +1,3 @@ -# -*- coding: future_fstrings -*- # # Copyright (c) The acados authors. # diff --git a/third_party/acados/build.sh b/third_party/acados/build.sh index b45c167b16..2b803ef6b2 100755 --- a/third_party/acados/build.sh +++ b/third_party/acados/build.sh @@ -44,6 +44,12 @@ cp -r $DIR/acados_repo/lib $INSTALL_DIR cp -r $DIR/acados_repo/interfaces/acados_template/acados_template $DIR/ #pip3 install -e $DIR/acados/interfaces/acados_template +# skip macOS - sed is different :/ +if [[ "$OSTYPE" != "darwin"* ]]; then + # strip future_fstrings to avoid having to install the compatibility package + find $DIR/acados_template/ -type f -exec sed -i '/future.fstrings/d' {} + +fi + # build tera cd $DIR/acados_repo/interfaces/acados_template/tera_renderer/ if [[ "$OSTYPE" == "darwin"* ]]; then From 948d42b3e59e073d23e3506dd254a58a0227f4a5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 1 Feb 2026 15:42:42 -0800 Subject: [PATCH 34/46] rm pyopencl package (#37058) rm pyopencl --- .gitignore | 4 + pyproject.toml | 1 - tools/sim/lib/camerad.py | 54 +++++----- tools/sim/rgb_to_nv12.cl | 119 ----------------------- tools/sim/tests/test_metadrive_bridge.py | 1 - uv.lock | 30 ------ 6 files changed, 35 insertions(+), 174 deletions(-) delete mode 100644 tools/sim/rgb_to_nv12.cl diff --git a/.gitignore b/.gitignore index e4992a3d05..e2a30fb70a 100644 --- a/.gitignore +++ b/.gitignore @@ -95,3 +95,7 @@ Pipfile # Ignore all local history of files .history .ionide + +.claude/ +PLAN.md +TASK.md diff --git a/pyproject.toml b/pyproject.toml index 57fd0b8355..2239770ac9 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -112,7 +112,6 @@ dev = [ "opencv-python-headless", "parameterized >=0.8, <0.9", "pyautogui", - "pyopencl", "pytools>=2025.1.6; platform_machine != 'aarch64'", "pywinctl", "pyprof2calltree", diff --git a/tools/sim/lib/camerad.py b/tools/sim/lib/camerad.py index be4e1a610c..7634b8524d 100644 --- a/tools/sim/lib/camerad.py +++ b/tools/sim/lib/camerad.py @@ -1,14 +1,39 @@ import numpy as np -import os -import pyopencl as cl -import pyopencl.array as cl_array from msgq.visionipc import VisionIpcServer, VisionStreamType from cereal import messaging -from openpilot.common.basedir import BASEDIR from openpilot.tools.sim.lib.common import W, H + +def rgb_to_nv12(rgb): + """Convert RGB image to NV12 (YUV420) format using BT.601 coefficients.""" + h, w = rgb.shape[:2] + r = rgb[:, :, 0].astype(np.int32) + g = rgb[:, :, 1].astype(np.int32) + b = rgb[:, :, 2].astype(np.int32) + + # Y plane - BT.601 coefficients (matches original OpenCL kernel) + y = (((b * 13 + g * 65 + r * 33) + 64) >> 7) + 16 + y = np.clip(y, 0, 255).astype(np.uint8) + + # Subsample RGB for UV (2x2 box filter) + r_sub = (r[0::2, 0::2] + r[0::2, 1::2] + r[1::2, 0::2] + r[1::2, 1::2] + 2) >> 2 + g_sub = (g[0::2, 0::2] + g[0::2, 1::2] + g[1::2, 0::2] + g[1::2, 1::2] + 2) >> 2 + b_sub = (b[0::2, 0::2] + b[0::2, 1::2] + b[1::2, 0::2] + b[1::2, 1::2] + 2) >> 2 + + # U and V planes + u = np.clip((b_sub * 56 - g_sub * 37 - r_sub * 19 + 0x8080) >> 8, 0, 255).astype(np.uint8) + v = np.clip((r_sub * 56 - g_sub * 47 - b_sub * 9 + 0x8080) >> 8, 0, 255).astype(np.uint8) + + # Interleave UV for NV12 format + uv = np.empty((h // 2, w), dtype=np.uint8) + uv[:, 0::2] = u + uv[:, 1::2] = v + + return np.concatenate([y.ravel(), uv.ravel()]).tobytes() + + class Camerad: """Simulates the camerad daemon""" def __init__(self, dual_camera): @@ -24,18 +49,6 @@ class Camerad: self.vipc_server.start_listener() - # set up for pyopencl rgb to yuv conversion - self.ctx = cl.create_some_context() - self.queue = cl.CommandQueue(self.ctx) - cl_arg = f" -DHEIGHT={H} -DWIDTH={W} -DRGB_STRIDE={W * 3} -DUV_WIDTH={W // 2} -DUV_HEIGHT={H // 2} -DRGB_SIZE={W * H} -DCL_DEBUG " - - kernel_fn = os.path.join(BASEDIR, "tools/sim/rgb_to_nv12.cl") - with open(kernel_fn) as f: - prg = cl.Program(self.ctx, f.read()).build(cl_arg) - self.krnl = prg.rgb_to_nv12 - self.Wdiv4 = W // 4 if (W % 4 == 0) else (W + (4 - W % 4)) // 4 - self.Hdiv4 = H // 4 if (H % 4 == 0) else (H + (4 - H % 4)) // 4 - def cam_send_yuv_road(self, yuv): self._send_yuv(yuv, self.frame_road_id, 'roadCameraState', VisionStreamType.VISION_STREAM_ROAD) self.frame_road_id += 1 @@ -44,16 +57,11 @@ class Camerad: self._send_yuv(yuv, self.frame_wide_id, 'wideRoadCameraState', VisionStreamType.VISION_STREAM_WIDE_ROAD) self.frame_wide_id += 1 - # Returns: yuv bytes def rgb_to_yuv(self, rgb): + """Convert RGB to NV12 YUV format.""" assert rgb.shape == (H, W, 3), f"{rgb.shape}" assert rgb.dtype == np.uint8 - - rgb_cl = cl_array.to_device(self.queue, rgb) - yuv_cl = cl_array.empty_like(rgb_cl) - self.krnl(self.queue, (self.Wdiv4, self.Hdiv4), None, rgb_cl.data, yuv_cl.data).wait() - yuv = np.resize(yuv_cl.get(), rgb.size // 2) - return yuv.data.tobytes() + return rgb_to_nv12(rgb) def _send_yuv(self, yuv, frame_id, pub_type, yuv_type): eof = int(frame_id * 0.05 * 1e9) diff --git a/tools/sim/rgb_to_nv12.cl b/tools/sim/rgb_to_nv12.cl deleted file mode 100644 index 54816d5d7d..0000000000 --- a/tools/sim/rgb_to_nv12.cl +++ /dev/null @@ -1,119 +0,0 @@ -#define RGB_TO_Y(r, g, b) ((((mul24(b, 13) + mul24(g, 65) + mul24(r, 33)) + 64) >> 7) + 16) -#define RGB_TO_U(r, g, b) ((mul24(b, 56) - mul24(g, 37) - mul24(r, 19) + 0x8080) >> 8) -#define RGB_TO_V(r, g, b) ((mul24(r, 56) - mul24(g, 47) - mul24(b, 9) + 0x8080) >> 8) -#define AVERAGE(x, y, z, w) ((convert_ushort(x) + convert_ushort(y) + convert_ushort(z) + convert_ushort(w) + 1) >> 1) - -inline void convert_2_ys(__global uchar * out_yuv, int yi, const uchar8 rgbs1) { - uchar2 yy = (uchar2)( - RGB_TO_Y(rgbs1.s2, rgbs1.s1, rgbs1.s0), - RGB_TO_Y(rgbs1.s5, rgbs1.s4, rgbs1.s3) - ); -#ifdef CL_DEBUG - if(yi >= RGB_SIZE) - printf("Y vector2 overflow, %d > %d\n", yi, RGB_SIZE); -#endif - vstore2(yy, 0, out_yuv + yi); -} - -inline void convert_4_ys(__global uchar * out_yuv, int yi, const uchar8 rgbs1, const uchar8 rgbs3) { - const uchar4 yy = (uchar4)( - RGB_TO_Y(rgbs1.s2, rgbs1.s1, rgbs1.s0), - RGB_TO_Y(rgbs1.s5, rgbs1.s4, rgbs1.s3), - RGB_TO_Y(rgbs3.s0, rgbs1.s7, rgbs1.s6), - RGB_TO_Y(rgbs3.s3, rgbs3.s2, rgbs3.s1) - ); -#ifdef CL_DEBUG - if(yi > RGB_SIZE - 4) - printf("Y vector4 overflow, %d > %d\n", yi, RGB_SIZE - 4); -#endif - vstore4(yy, 0, out_yuv + yi); -} - -inline void convert_uv(__global uchar * out_yuv, int uvi, - const uchar8 rgbs1, const uchar8 rgbs2) { - // U & V: average of 2x2 pixels square - const short ab = AVERAGE(rgbs1.s0, rgbs1.s3, rgbs2.s0, rgbs2.s3); - const short ag = AVERAGE(rgbs1.s1, rgbs1.s4, rgbs2.s1, rgbs2.s4); - const short ar = AVERAGE(rgbs1.s2, rgbs1.s5, rgbs2.s2, rgbs2.s5); -#ifdef CL_DEBUG - if(uvi >= RGB_SIZE + RGB_SIZE / 2) - printf("UV overflow, %d >= %d\n", uvi, RGB_SIZE + RGB_SIZE / 2); -#endif - out_yuv[uvi] = RGB_TO_U(ar, ag, ab); - out_yuv[uvi+1] = RGB_TO_V(ar, ag, ab); -} - -inline void convert_2_uvs(__global uchar * out_yuv, int uvi, - const uchar8 rgbs1, const uchar8 rgbs2, const uchar8 rgbs3, const uchar8 rgbs4) { - // U & V: average of 2x2 pixels square - const short ab1 = AVERAGE(rgbs1.s0, rgbs1.s3, rgbs2.s0, rgbs2.s3); - const short ag1 = AVERAGE(rgbs1.s1, rgbs1.s4, rgbs2.s1, rgbs2.s4); - const short ar1 = AVERAGE(rgbs1.s2, rgbs1.s5, rgbs2.s2, rgbs2.s5); - const short ab2 = AVERAGE(rgbs1.s6, rgbs3.s1, rgbs2.s6, rgbs4.s1); - const short ag2 = AVERAGE(rgbs1.s7, rgbs3.s2, rgbs2.s7, rgbs4.s2); - const short ar2 = AVERAGE(rgbs3.s0, rgbs3.s3, rgbs4.s0, rgbs4.s3); - uchar4 uv = (uchar4)( - RGB_TO_U(ar1, ag1, ab1), - RGB_TO_V(ar1, ag1, ab1), - RGB_TO_U(ar2, ag2, ab2), - RGB_TO_V(ar2, ag2, ab2) - ); -#ifdef CL_DEBUG1 - if(uvi > RGB_SIZE + RGB_SIZE / 2 - 4) - printf("UV2 overflow, %d >= %d\n", uvi, RGB_SIZE + RGB_SIZE / 2 - 2); -#endif - vstore4(uv, 0, out_yuv + uvi); -} - -__kernel void rgb_to_nv12(__global uchar const * const rgb, - __global uchar * out_yuv) -{ - const int dx = get_global_id(0); - const int dy = get_global_id(1); - const int col = mul24(dx, 4); // Current column in rgb image - const int row = mul24(dy, 4); // Current row in rgb image - const int bgri_start = mad24(row, RGB_STRIDE, mul24(col, 3)); // Start offset of rgb data being converted - const int yi_start = mad24(row, WIDTH, col); // Start offset in the target yuv buffer - int uvi = mad24(row / 2, WIDTH, RGB_SIZE + col); - int num_col = min(WIDTH - col, 4); - int num_row = min(HEIGHT - row, 4); - if(num_row == 4) { - const uchar8 rgbs0_0 = vload8(0, rgb + bgri_start); - const uchar8 rgbs0_1 = vload8(0, rgb + bgri_start + 8); - const uchar8 rgbs1_0 = vload8(0, rgb + bgri_start + RGB_STRIDE); - const uchar8 rgbs1_1 = vload8(0, rgb + bgri_start + RGB_STRIDE + 8); - const uchar8 rgbs2_0 = vload8(0, rgb + bgri_start + RGB_STRIDE * 2); - const uchar8 rgbs2_1 = vload8(0, rgb + bgri_start + RGB_STRIDE * 2 + 8); - const uchar8 rgbs3_0 = vload8(0, rgb + bgri_start + RGB_STRIDE * 3); - const uchar8 rgbs3_1 = vload8(0, rgb + bgri_start + RGB_STRIDE * 3 + 8); - if(num_col == 4) { - convert_4_ys(out_yuv, yi_start, rgbs0_0, rgbs0_1); - convert_4_ys(out_yuv, yi_start + WIDTH, rgbs1_0, rgbs1_1); - convert_4_ys(out_yuv, yi_start + WIDTH * 2, rgbs2_0, rgbs2_1); - convert_4_ys(out_yuv, yi_start + WIDTH * 3, rgbs3_0, rgbs3_1); - convert_2_uvs(out_yuv, uvi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); - convert_2_uvs(out_yuv, uvi + WIDTH, rgbs2_0, rgbs3_0, rgbs2_1, rgbs3_1); - } else if(num_col == 2) { - convert_2_ys(out_yuv, yi_start, rgbs0_0); - convert_2_ys(out_yuv, yi_start + WIDTH, rgbs1_0); - convert_2_ys(out_yuv, yi_start + WIDTH * 2, rgbs2_0); - convert_2_ys(out_yuv, yi_start + WIDTH * 3, rgbs3_0); - convert_uv(out_yuv, uvi, rgbs0_0, rgbs1_0); - convert_uv(out_yuv, uvi + WIDTH, rgbs2_0, rgbs3_0); - } - } else { - const uchar8 rgbs0_0 = vload8(0, rgb + bgri_start); - const uchar8 rgbs0_1 = vload8(0, rgb + bgri_start + 8); - const uchar8 rgbs1_0 = vload8(0, rgb + bgri_start + RGB_STRIDE); - const uchar8 rgbs1_1 = vload8(0, rgb + bgri_start + RGB_STRIDE + 8); - if(num_col == 4) { - convert_4_ys(out_yuv, yi_start, rgbs0_0, rgbs0_1); - convert_4_ys(out_yuv, yi_start + WIDTH, rgbs1_0, rgbs1_1); - convert_2_uvs(out_yuv, uvi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); - } else if(num_col == 2) { - convert_2_ys(out_yuv, yi_start, rgbs0_0); - convert_2_ys(out_yuv, yi_start + WIDTH, rgbs1_0); - convert_uv(out_yuv, uvi, rgbs0_0, rgbs1_0); - } - } -} diff --git a/tools/sim/tests/test_metadrive_bridge.py b/tools/sim/tests/test_metadrive_bridge.py index 04ce5d584f..9be640d736 100644 --- a/tools/sim/tests/test_metadrive_bridge.py +++ b/tools/sim/tests/test_metadrive_bridge.py @@ -8,7 +8,6 @@ from openpilot.tools.sim.bridge.metadrive.metadrive_bridge import MetaDriveBridg from openpilot.tools.sim.tests.test_sim_bridge import TestSimBridgeBase @pytest.mark.slow -@pytest.mark.filterwarnings("ignore::pyopencl.CompilerWarning") # Unimportant warning of non-empty compile log class TestMetaDriveBridge(TestSimBridgeBase): @pytest.fixture(autouse=True) def setup_create_bridge(self, test_duration): diff --git a/uv.lock b/uv.lock index e488d1d78b..da387a3906 100644 --- a/uv.lock +++ b/uv.lock @@ -1336,7 +1336,6 @@ dev = [ { name = "opencv-python-headless" }, { name = "parameterized" }, { name = "pyautogui" }, - { name = "pyopencl" }, { name = "pyprof2calltree" }, { name = "pytools", marker = "platform_machine != 'aarch64'" }, { name = "pywinctl" }, @@ -1409,7 +1408,6 @@ requires-dist = [ { name = "pycapnp", specifier = "==2.1.0" }, { name = "pycryptodome" }, { name = "pyjwt" }, - { name = "pyopencl", marker = "extra == 'dev'" }, { name = "pyopenssl", specifier = "<24.3.0" }, { name = "pyprof2calltree", marker = "extra == 'dev'" }, { name = "pyserial" }, @@ -4247,34 +4245,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/db/67/64920c8d201a7fc27962f467c636c4e763b43845baba2e091a50a97a5d52/pyobjc_framework_webkit-12.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:af2c7197447638b92aafbe4847c063b6dd5e1ed83b44d3ce7e71e4c9b042ab5a", size = 50084, upload-time = "2025-11-14T10:07:05.868Z" }, ] -[[package]] -name = "pyopencl" -version = "2026.1.2" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "numpy" }, - { name = "platformdirs" }, - { name = "pytools" }, - { name = "typing-extensions" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/d8/81/fd8a2a695916a82e861bcf17b5b8fd9f81e12c9e5931f9ba536678d7b43a/pyopencl-2026.1.2.tar.gz", hash = "sha256:4397dd0b4cbb8b55f3e09bf87114a2465574506b363890b805b860c348b61970", size = 445132, upload-time = "2026-01-16T22:52:24.765Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/e3/88/abf34e31d572c59203774a66cd81c1e3b3d60b911241483675151149c6f1/pyopencl-2026.1.2-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:8052e8b402b3ed33ee0807d87d4734f66f67dbafbfb3f5a8b81e478e4d417372", size = 437029, upload-time = "2026-01-16T22:51:30.953Z" }, - { url = "https://files.pythonhosted.org/packages/5c/3d/2dd2d8bbf05a190681582b40fc1ee55b210d00ccebcbb416c62b9f9c81a1/pyopencl-2026.1.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d5e03681c3fe22d5185b16a727d96783e3787e0b65e7a29e4afe01ae0cb4e802", size = 429031, upload-time = "2026-01-16T22:51:32.674Z" }, - { url = "https://files.pythonhosted.org/packages/41/16/e554b3bd20be2e858cfb6683ee6549aeebbe5f769e5b95f561f79340ab20/pyopencl-2026.1.2-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1c8c209d517d1421b17d20b80589a2c39e09ea33350f0367314e1caeed3bc741", size = 689596, upload-time = "2026-01-16T22:51:33.913Z" }, - { url = "https://files.pythonhosted.org/packages/22/a8/1df41cf6c7b25b3bfda14aa0183c6a90eaf849528ba27753eaa25fb26e20/pyopencl-2026.1.2-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:e64e2e34bcfad426bd24b71fdb6b02aa5cb02475147742fe07ef93e81866fc7e", size = 736427, upload-time = "2026-01-16T22:51:36.595Z" }, - { url = "https://files.pythonhosted.org/packages/fc/3d/177b6a675691f7b6f708faef33f981e72fbc4bfed2b1dfa94dc70d0e8a25/pyopencl-2026.1.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:65b151c56b936481d6b6050c2b9bc520840e1402be78c282ba5c01921c25477d", size = 1163888, upload-time = "2026-01-16T22:51:37.973Z" }, - { url = "https://files.pythonhosted.org/packages/e9/fa/5905571d9fa48827c0427a3e664c0213dd045940d581b3b739d83df9c0f6/pyopencl-2026.1.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:cc40003446037f391ca0970694efb0627e2870fabb20ee21be75bc445a39d8f4", size = 1228235, upload-time = "2026-01-16T22:51:39.786Z" }, - { url = "https://files.pythonhosted.org/packages/1e/3d/538c675d078b91680d8d82962110d0c9fd42e1584763d515d6e2e82d8c57/pyopencl-2026.1.2-cp311-cp311-win_amd64.whl", hash = "sha256:b6a8e109ade7db60e8b1beb48df8f080941d0cd77fb2c225ad509c80cdef603e", size = 474753, upload-time = "2026-01-16T22:51:41.771Z" }, - { url = "https://files.pythonhosted.org/packages/cd/34/1497070e44d1689ddbd01d24a2265910e84ebc53457a489b9d2b6e1ac675/pyopencl-2026.1.2-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:7d88e59901bfe1f9296fd89acd9968f008dc7cfee7995f8cd09c3f1a77119aa6", size = 438145, upload-time = "2026-01-16T22:51:43.658Z" }, - { url = "https://files.pythonhosted.org/packages/5b/a3/71d6af8741b52d3bef443518c1ccfda003adcfa9cc1d0df83dac7005d08c/pyopencl-2026.1.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:3f96a3bff8a09d2fa924e7c33dafac6ea3ef7ec70e746d6d8e17ce2d959a6836", size = 428820, upload-time = "2026-01-16T22:51:45.326Z" }, - { url = "https://files.pythonhosted.org/packages/db/ea/c8dbabeceac9cad3dbb368e08e0aa208cc6c6251c5134cc25eb15da03639/pyopencl-2026.1.2-cp312-cp312-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:4d4e8e8215ec4fdee4b235b61977cdb1c4f041b487bdcf357be799f45b423d61", size = 685478, upload-time = "2026-01-16T22:51:46.545Z" }, - { url = "https://files.pythonhosted.org/packages/64/c7/5854ef7471dfee195bcef6348a107525ca4d1b73c15240e6444d490f9920/pyopencl-2026.1.2-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:d0052a8ccbd282d8ab196705e31f4c3ab344113ea5d5c3ddaeede00cdcab068b", size = 734017, upload-time = "2026-01-16T22:51:48.277Z" }, - { url = "https://files.pythonhosted.org/packages/3d/79/42d4eec282ed299b38d8136d05545113ec8771a1bd6b10bb4ba83ae1236c/pyopencl-2026.1.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:e43da12a376e9283407c2820b24cceeaa129b042ac710947cf8e07b13e294689", size = 1159871, upload-time = "2026-01-16T22:51:49.569Z" }, - { url = "https://files.pythonhosted.org/packages/a0/9a/fdc5d3bed0440d6206109e051008aa0a54ca131d64314bbd42177b8f0763/pyopencl-2026.1.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:1b14b2cf11dec9e0b75cbd14223d1b3c93950fc3e2f7a306b54fa1b17a2cae0f", size = 1225288, upload-time = "2026-01-16T22:51:51.125Z" }, - { url = "https://files.pythonhosted.org/packages/2d/e3/358c19180e0dab5c7dd1fcacc569e6a7ab02a7fddcb9c954f393ceddb2fa/pyopencl-2026.1.2-cp312-cp312-win_amd64.whl", hash = "sha256:d02d7ecabc8d34590dccffe12346689adc5a1ceb07df5acc4ea6c4db8aa28277", size = 474876, upload-time = "2026-01-16T22:51:52.912Z" }, -] - [[package]] name = "pyopenssl" version = "24.2.1" From 5da6bf9e036aa69994bb462fa972648e8ac33255 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 1 Feb 2026 15:46:40 -0800 Subject: [PATCH 35/46] rm pytools package (#37059) --- pyproject.toml | 1 - uv.lock | 36 ------------------------------------ 2 files changed, 37 deletions(-) diff --git a/pyproject.toml b/pyproject.toml index 2239770ac9..76b02d0c28 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -112,7 +112,6 @@ dev = [ "opencv-python-headless", "parameterized >=0.8, <0.9", "pyautogui", - "pytools>=2025.1.6; platform_machine != 'aarch64'", "pywinctl", "pyprof2calltree", "tabulate", diff --git a/uv.lock b/uv.lock index da387a3906..85f12bb055 100644 --- a/uv.lock +++ b/uv.lock @@ -1337,7 +1337,6 @@ dev = [ { name = "parameterized" }, { name = "pyautogui" }, { name = "pyprof2calltree" }, - { name = "pytools", marker = "platform_machine != 'aarch64'" }, { name = "pywinctl" }, { name = "tabulate" }, { name = "types-requests" }, @@ -1420,7 +1419,6 @@ requires-dist = [ { name = "pytest-subtests", marker = "extra == 'testing'" }, { name = "pytest-timeout", marker = "extra == 'testing'" }, { name = "pytest-xdist", marker = "extra == 'testing'", git = "https://github.com/sshane/pytest-xdist?rev=2b4372bd62699fb412c4fe2f95bf9f01bd2018da" }, - { name = "pytools", marker = "platform_machine != 'aarch64' and extra == 'dev'", specifier = ">=2025.1.6" }, { name = "pywinctl", marker = "extra == 'dev'" }, { name = "pyzmq" }, { name = "qrcode" }, @@ -4446,20 +4444,6 @@ version = "0.15" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/ef/c6/2c5999de3bb1533521f1101e8fe56fd9c266732f4d48011c7c69b29d12ae/python3-xlib-0.15.tar.gz", hash = "sha256:dc4245f3ae4aa5949c1d112ee4723901ade37a96721ba9645f2bfa56e5b383f8", size = 132828, upload-time = "2014-05-31T12:28:59.603Z" } -[[package]] -name = "pytools" -version = "2025.2.5" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "platformdirs" }, - { name = "siphash24" }, - { name = "typing-extensions" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/c3/7b/f885a57e61ded45b5b10ca60f0b7575c9fb9a282e7513d0e23a33ee647e1/pytools-2025.2.5.tar.gz", hash = "sha256:a7f5350644d46d98ee9c7e67b4b41693308aa0f5e9b188d8f0694b27dc94e3a2", size = 85594, upload-time = "2025-10-07T15:53:30.49Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/f6/84/c42c29ca4bff35baa286df70b0097e0b1c88fd57e8e6bdb09cb161a6f3c1/pytools-2025.2.5-py3-none-any.whl", hash = "sha256:42e93751ec425781e103bbcd769ba35ecbacd43339c2905401608f2fdc30cf19", size = 98811, upload-time = "2025-10-07T15:53:29.089Z" }, -] - [[package]] name = "pytweening" version = "1.2.0" @@ -4774,26 +4758,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ec/bf/cb6c1c505cb31e818e900b9312d514f381fbfa5c4363edfce0fcc4f8c1a4/shapely-2.1.2-cp312-cp312-win_amd64.whl", hash = "sha256:743044b4cfb34f9a67205cee9279feaf60ba7d02e69febc2afc609047cb49179", size = 1722861, upload-time = "2025-09-24T13:50:43.35Z" }, ] -[[package]] -name = "siphash24" -version = "1.8" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/67/a2/e049b6fccf7a94bd1b2f68b3059a7d6a7aea86a808cac80cb9ae71ab6254/siphash24-1.8.tar.gz", hash = "sha256:aa932f0af4a7335caef772fdaf73a433a32580405c41eb17ff24077944b0aa97", size = 19946, upload-time = "2025-09-02T20:42:04.856Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/82/23/f53f5bd8866c6ea3abe434c9f208e76ea027210d8b75cd0e0dc849661c7a/siphash24-1.8-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:d4662ac616bce4d3c9d6003a0d398e56f8be408fc53a166b79fad08d4f34268e", size = 76930, upload-time = "2025-09-02T20:41:00.869Z" }, - { url = "https://files.pythonhosted.org/packages/0b/25/aebf246904424a06e7ffb7a40cfa9ea9e590ea0fac82e182e0f5d1f1d7ef/siphash24-1.8-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:53d6bed0951a99c6d2891fa6f8acfd5ca80c3e96c60bcee99f6fa01a04773b1c", size = 74315, upload-time = "2025-09-02T20:41:02.38Z" }, - { url = "https://files.pythonhosted.org/packages/59/3f/7010407c3416ef052d46550d54afb2581fb247018fc6500af8c66669eff2/siphash24-1.8-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d114c03648630e9e07dac2fe95442404e4607adca91640d274ece1a4fa71123e", size = 99756, upload-time = "2025-09-02T20:41:03.902Z" }, - { url = "https://files.pythonhosted.org/packages/d4/9f/09c734833e69badd7e3faed806b4372bd6564ae0946bd250d5239885914f/siphash24-1.8-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:88c1a55ff82b127c5d3b96927a430d8859e6a98846a5b979833ac790682dd91b", size = 104044, upload-time = "2025-09-02T20:41:05.505Z" }, - { url = "https://files.pythonhosted.org/packages/24/30/56a26d9141a34433da221f732599e2b23d2d70a966c249a9f00feb9a2915/siphash24-1.8-cp311-cp311-win32.whl", hash = "sha256:9430255e6a1313470f52c07c4a4643c451a5b2853f6d4008e4dda05cafb6ce7c", size = 62196, upload-time = "2025-09-02T20:41:07.299Z" }, - { url = "https://files.pythonhosted.org/packages/47/b2/11b0ae63fd374652544e1b12f72ba2cc3fe6c93c1483bd8ff6935b0a8a4b/siphash24-1.8-cp311-cp311-win_amd64.whl", hash = "sha256:1e4b37e4ef0b4496169adce2a58b6c3f230b5852dfa5f7ad0b2d664596409e47", size = 77162, upload-time = "2025-09-02T20:41:08.878Z" }, - { url = "https://files.pythonhosted.org/packages/7f/82/ce3545ce8052ac7ca104b183415a27ec3335e5ed51978fdd7b433f3cfe5b/siphash24-1.8-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:df5ed437c6e6cc96196b38728e57cd30b0427df45223475a90e173f5015ef5ba", size = 78136, upload-time = "2025-09-02T20:41:10.083Z" }, - { url = "https://files.pythonhosted.org/packages/15/88/896c3b91bc9deb78c415448b1db67343917f35971a9e23a5967a9d323b8a/siphash24-1.8-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:f4ef78abdf811325c7089a35504df339c48c0007d4af428a044431d329721e56", size = 74588, upload-time = "2025-09-02T20:41:11.251Z" }, - { url = "https://files.pythonhosted.org/packages/12/fd/8dad3f5601db485ba862e1c1f91a5d77fb563650856a6708e9acb40ee53c/siphash24-1.8-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:065eff55c4fefb3a29fd26afb2c072abf7f668ffd53b91d41f92a1c485fcbe5c", size = 98655, upload-time = "2025-09-02T20:41:12.45Z" }, - { url = "https://files.pythonhosted.org/packages/e3/cc/e0c352624c1f2faad270aeb5cce6e173977ef66b9b5e918aa6f32af896bf/siphash24-1.8-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ac6fa84ebfd47677262aa0bcb0f5a70f796f5fc5704b287ee1b65a3bd4fb7a5d", size = 103217, upload-time = "2025-09-02T20:41:13.746Z" }, - { url = "https://files.pythonhosted.org/packages/5b/f6/0b1675bea4d40affcae642d9c7337702a4138b93c544230280712403e968/siphash24-1.8-cp312-cp312-win32.whl", hash = "sha256:6582f73615552ca055e51e03cb02a28e570a641a7f500222c86c2d811b5037eb", size = 63114, upload-time = "2025-09-02T20:41:14.972Z" }, - { url = "https://files.pythonhosted.org/packages/3d/39/afefef85d72ed8b5cf1aa9283f712e3cd43c9682fabbc809dec54baa8452/siphash24-1.8-cp312-cp312-win_amd64.whl", hash = "sha256:44ea6d794a7cbe184e1e1da2df81c5ebb672ab3867935c3e87c08bb0c2fa4879", size = 76232, upload-time = "2025-09-02T20:41:16.112Z" }, -] - [[package]] name = "six" version = "1.17.0" From 35241a5fb871623b69f793946188b41964d82196 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 1 Feb 2026 16:03:18 -0800 Subject: [PATCH 36/46] cleanup pyproject (#37060) * cleanup pyproject * lil more * fix warning --- pyproject.toml | 26 +++++-------------- tools/plotjuggler/juggle.py | 2 +- uv.lock | 51 ++----------------------------------- 3 files changed, 9 insertions(+), 70 deletions(-) diff --git a/pyproject.toml b/pyproject.toml index 76b02d0c28..bba80ee8db 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -5,7 +5,7 @@ license = {text = "MIT License"} version = "0.1.0" description = "an open source driver assistance system" authors = [ - {name ="Vehicle Researcher", email="user@comma.ai"} + {name = "Vehicle Researcher", email="user@comma.ai"} ] dependencies = [ @@ -74,6 +74,7 @@ dependencies = [ "raylib > 5.5.0.3", "qrcode", "mapbox-earcut", + "jeepney", ] [project.optional-dependencies] @@ -93,7 +94,6 @@ testing = [ # https://github.com/pytest-dev/pytest-xdist/pull/1229 "pytest-xdist @ git+https://github.com/sshane/pytest-xdist@2b4372bd62699fb412c4fe2f95bf9f01bd2018da", "pytest-timeout", - "pytest-randomly", "pytest-asyncio", "pytest-mock", "pytest-repeat", @@ -107,16 +107,12 @@ dev = [ "azure-identity", "azure-storage-blob", "dictdiffer", - "jeepney", "matplotlib", "opencv-python-headless", "parameterized >=0.8, <0.9", "pyautogui", "pywinctl", - "pyprof2calltree", "tabulate", - "types-requests", - "types-tabulate", ] tools = [ @@ -153,19 +149,9 @@ markers = [ testpaths = [ "common", "selfdrive", - "system/manager", - "system/updated", - "system/athena", - "system/camerad", - "system/hardware", - "system/loggerd", - "system/tests", - "system/ubloxd", - "system/webrtc", - "tools/lib/tests", - "tools/replay", - "tools/cabana", - "cereal/messaging/tests", + "system", + "tools", + "cereal", ] [tool.codespell] @@ -175,7 +161,7 @@ ignore-words-list = "bu,ro,te,ue,alo,hda,ois,nam,nams,ned,som,parm,setts,inout,w builtin = "clear,rare,informal,code,names,en-GB_to_en-US" skip = "./third_party/*, ./tinygrad/*, ./tinygrad_repo/*, ./msgq/*, ./panda/*, ./opendbc/*, ./opendbc_repo/*, ./rednose/*, ./rednose_repo/*, ./teleoprtc/*, ./teleoprtc_repo/*, *.po, uv.lock, *.onnx, ./cereal/gen/*, */c_generated_code/*, docs/assets/*, tools/plotjuggler/layouts/*, selfdrive/assets/offroad/mici_fcc.html" -# https://beta.ruff.rs/docs/configuration/#using-pyprojecttoml +# https://docs.astral.sh/ruff/configuration/#using-pyprojecttoml [tool.ruff] indent-width = 2 lint.select = [ diff --git a/tools/plotjuggler/juggle.py b/tools/plotjuggler/juggle.py index 34f33d1959..142e640504 100755 --- a/tools/plotjuggler/juggle.py +++ b/tools/plotjuggler/juggle.py @@ -47,7 +47,7 @@ def install(): tmpf.write(chunk) with tarfile.open(tmp.name) as tar: - tar.extractall(path=INSTALL_DIR) + tar.extractall(path=INSTALL_DIR, filter="data") def get_plotjuggler_version(): diff --git a/uv.lock b/uv.lock index 85f12bb055..3e3522eb39 100644 --- a/uv.lock +++ b/uv.lock @@ -1294,6 +1294,7 @@ dependencies = [ { name = "crcmod-plus" }, { name = "cython" }, { name = "inputs" }, + { name = "jeepney" }, { name = "json-rpc" }, { name = "kaitaistruct" }, { name = "libusb1" }, @@ -1331,16 +1332,12 @@ dev = [ { name = "azure-identity" }, { name = "azure-storage-blob" }, { name = "dictdiffer" }, - { name = "jeepney" }, { name = "matplotlib" }, { name = "opencv-python-headless" }, { name = "parameterized" }, { name = "pyautogui" }, - { name = "pyprof2calltree" }, { name = "pywinctl" }, { name = "tabulate" }, - { name = "types-requests" }, - { name = "types-tabulate" }, ] docs = [ { name = "jinja2" }, @@ -1356,7 +1353,6 @@ testing = [ { name = "pytest-asyncio" }, { name = "pytest-cpp" }, { name = "pytest-mock" }, - { name = "pytest-randomly" }, { name = "pytest-repeat" }, { name = "pytest-subtests" }, { name = "pytest-timeout" }, @@ -1386,7 +1382,7 @@ requires-dist = [ { name = "dictdiffer", marker = "extra == 'dev'" }, { name = "hypothesis", marker = "extra == 'testing'", specifier = "==6.47.*" }, { name = "inputs" }, - { name = "jeepney", marker = "extra == 'dev'" }, + { name = "jeepney" }, { name = "jinja2", marker = "extra == 'docs'" }, { name = "json-rpc" }, { name = "kaitaistruct" }, @@ -1408,13 +1404,11 @@ requires-dist = [ { name = "pycryptodome" }, { name = "pyjwt" }, { name = "pyopenssl", specifier = "<24.3.0" }, - { name = "pyprof2calltree", marker = "extra == 'dev'" }, { name = "pyserial" }, { name = "pytest", marker = "extra == 'testing'" }, { name = "pytest-asyncio", marker = "extra == 'testing'" }, { name = "pytest-cpp", marker = "extra == 'testing'" }, { name = "pytest-mock", marker = "extra == 'testing'" }, - { name = "pytest-randomly", marker = "extra == 'testing'" }, { name = "pytest-repeat", marker = "extra == 'testing'" }, { name = "pytest-subtests", marker = "extra == 'testing'" }, { name = "pytest-timeout", marker = "extra == 'testing'" }, @@ -1436,8 +1430,6 @@ requires-dist = [ { name = "tabulate", marker = "extra == 'dev'" }, { name = "tqdm" }, { name = "ty", marker = "extra == 'testing'" }, - { name = "types-requests", marker = "extra == 'dev'" }, - { name = "types-tabulate", marker = "extra == 'dev'" }, { name = "websocket-client" }, { name = "xattr" }, { name = "zstandard" }, @@ -4273,12 +4265,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/df/80/fc9d01d5ed37ba4c42ca2b55b4339ae6e200b456be3a1aaddf4a9fa99b8c/pyperclip-1.11.0-py3-none-any.whl", hash = "sha256:299403e9ff44581cb9ba2ffeed69c7aa96a008622ad0c46cb575ca75b5b84273", size = 11063, upload-time = "2025-09-26T14:40:36.069Z" }, ] -[[package]] -name = "pyprof2calltree" -version = "1.4.5" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/ca/2a/e9a76261183b4b5e059a6625d7aae0bcb0a77622bc767d4497148ce2e218/pyprof2calltree-1.4.5.tar.gz", hash = "sha256:a635672ff31677486350b2be9a823ef92f740e6354a6aeda8fa4a8a3768e8f2f", size = 10080, upload-time = "2020-04-19T10:39:09.819Z" } - [[package]] name = "pyrect" version = "0.2.0" @@ -4356,18 +4342,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/5a/cc/06253936f4a7fa2e0f48dfe6d851d9c56df896a9ab09ac019d70b760619c/pytest_mock-3.15.1-py3-none-any.whl", hash = "sha256:0a25e2eb88fe5168d535041d09a4529a188176ae608a6d249ee65abc0949630d", size = 10095, upload-time = "2025-09-16T16:37:25.734Z" }, ] -[[package]] -name = "pytest-randomly" -version = "4.0.1" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "pytest" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/c4/1d/258a4bf1109258c00c35043f40433be5c16647387b6e7cd5582d638c116b/pytest_randomly-4.0.1.tar.gz", hash = "sha256:174e57bb12ac2c26f3578188490bd333f0e80620c3f47340158a86eca0593cd8", size = 14130, upload-time = "2025-09-12T15:23:00.085Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/33/3e/a4a9227807b56869790aad3e24472a554b585974fe7e551ea350f50897ae/pytest_randomly-4.0.1-py3-none-any.whl", hash = "sha256:e0dfad2fd4f35e07beff1e47c17fbafcf98f9bf4531fd369d9260e2f858bfcb7", size = 8304, upload-time = "2025-09-12T15:22:58.946Z" }, -] - [[package]] name = "pytest-repeat" version = "0.9.4" @@ -4864,27 +4838,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/2d/c2/05fdd64ac003a560d4fbd1faa7d9a31d75df8f901675e5bed1ee2ceeff87/ty-0.0.13-py3-none-win_arm64.whl", hash = "sha256:1c9630333497c77bb9bcabba42971b96ee1f36c601dd3dcac66b4134f9fa38f0", size = 9808316, upload-time = "2026-01-21T13:20:54.053Z" }, ] -[[package]] -name = "types-requests" -version = "2.32.4.20260107" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "urllib3" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/0f/f3/a0663907082280664d745929205a89d41dffb29e89a50f753af7d57d0a96/types_requests-2.32.4.20260107.tar.gz", hash = "sha256:018a11ac158f801bfa84857ddec1650750e393df8a004a8a9ae2a9bec6fcb24f", size = 23165, upload-time = "2026-01-07T03:20:54.091Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/1c/12/709ea261f2bf91ef0a26a9eed20f2623227a8ed85610c1e54c5805692ecb/types_requests-2.32.4.20260107-py3-none-any.whl", hash = "sha256:b703fe72f8ce5b31ef031264fe9395cac8f46a04661a79f7ed31a80fb308730d", size = 20676, upload-time = "2026-01-07T03:20:52.929Z" }, -] - -[[package]] -name = "types-tabulate" -version = "0.9.0.20241207" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/3f/43/16030404a327e4ff8c692f2273854019ed36718667b2993609dc37d14dd4/types_tabulate-0.9.0.20241207.tar.gz", hash = "sha256:ac1ac174750c0a385dfd248edc6279fa328aaf4ea317915ab879a2ec47833230", size = 8195, upload-time = "2024-12-07T02:54:42.554Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/5e/86/a9ebfd509cbe74471106dffed320e208c72537f9aeb0a55eaa6b1b5e4d17/types_tabulate-0.9.0.20241207-py3-none-any.whl", hash = "sha256:b8dad1343c2a8ba5861c5441370c3e35908edd234ff036d4298708a1d4cf8a85", size = 8307, upload-time = "2024-12-07T02:54:41.031Z" }, -] - [[package]] name = "typing-extensions" version = "4.15.0" From b03e7821d46d2876c1ddd5995bad24b9f59ca76e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 1 Feb 2026 17:26:58 -0800 Subject: [PATCH 37/46] replace smbus2 package with minimal implementation (#37061) * replace smbus2 package with minimal implementation * cleanup * fix up --- common/i2c.py | 81 ++++++++++++++++++++++++++++ pyproject.toml | 3 -- system/hardware/tici/amplifier.py | 3 +- system/sensord/sensors/i2c_sensor.py | 5 +- uv.lock | 11 ---- 5 files changed, 86 insertions(+), 17 deletions(-) create mode 100644 common/i2c.py diff --git a/common/i2c.py b/common/i2c.py new file mode 100644 index 0000000000..1dfaa659ad --- /dev/null +++ b/common/i2c.py @@ -0,0 +1,81 @@ +import os +import fcntl +import ctypes + +# I2C constants from /usr/include/linux/i2c-dev.h +I2C_SLAVE = 0x0703 +I2C_SLAVE_FORCE = 0x0706 +I2C_SMBUS = 0x0720 + +# SMBus transfer types +I2C_SMBUS_READ = 1 +I2C_SMBUS_WRITE = 0 +I2C_SMBUS_BYTE_DATA = 2 +I2C_SMBUS_I2C_BLOCK_DATA = 8 + +I2C_SMBUS_BLOCK_MAX = 32 + + +class _I2cSmbusData(ctypes.Union): + _fields_ = [ + ("byte", ctypes.c_uint8), + ("word", ctypes.c_uint16), + ("block", ctypes.c_uint8 * (I2C_SMBUS_BLOCK_MAX + 2)), + ] + + +class _I2cSmbusIoctlData(ctypes.Structure): + _fields_ = [ + ("read_write", ctypes.c_uint8), + ("command", ctypes.c_uint8), + ("size", ctypes.c_uint32), + ("data", ctypes.POINTER(_I2cSmbusData)), + ] + + +class SMBus: + def __init__(self, bus: int): + self._fd = os.open(f'/dev/i2c-{bus}', os.O_RDWR) + + def __enter__(self) -> 'SMBus': + return self + + def __exit__(self, *args) -> None: + self.close() + + def close(self) -> None: + if hasattr(self, '_fd') and self._fd >= 0: + os.close(self._fd) + self._fd = -1 + + def _set_address(self, addr: int, force: bool = False) -> None: + ioctl_arg = I2C_SLAVE_FORCE if force else I2C_SLAVE + fcntl.ioctl(self._fd, ioctl_arg, addr) + + def _smbus_access(self, read_write: int, command: int, size: int, data: _I2cSmbusData) -> None: + ioctl_data = _I2cSmbusIoctlData(read_write, command, size, ctypes.pointer(data)) + fcntl.ioctl(self._fd, I2C_SMBUS, ioctl_data) + + def read_byte_data(self, addr: int, register: int, force: bool = False) -> int: + self._set_address(addr, force) + data = _I2cSmbusData() + self._smbus_access(I2C_SMBUS_READ, register, I2C_SMBUS_BYTE_DATA, data) + return int(data.byte) + + def write_byte_data(self, addr: int, register: int, value: int, force: bool = False) -> None: + self._set_address(addr, force) + data = _I2cSmbusData() + data.byte = value & 0xFF + self._smbus_access(I2C_SMBUS_WRITE, register, I2C_SMBUS_BYTE_DATA, data) + + def read_i2c_block_data(self, addr: int, register: int, length: int, force: bool = False) -> list[int]: + self._set_address(addr, force) + if not (0 <= length <= I2C_SMBUS_BLOCK_MAX): + raise ValueError(f"length must be 0..{I2C_SMBUS_BLOCK_MAX}") + + data = _I2cSmbusData() + data.block[0] = length + self._smbus_access(I2C_SMBUS_READ, register, I2C_SMBUS_I2C_BLOCK_DATA, data) + read_len = int(data.block[0]) or length + read_len = min(read_len, length) + return [int(b) for b in data.block[1 : read_len + 1]] diff --git a/pyproject.toml b/pyproject.toml index bba80ee8db..19491ba532 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -17,9 +17,6 @@ dependencies = [ "crcmod-plus", # cars + qcomgpsd "tqdm", # cars (fw_versions.py) on start + many one-off uses - # hardwared - "smbus2", # configuring amp - # core "cffi", "scons", diff --git a/system/hardware/tici/amplifier.py b/system/hardware/tici/amplifier.py index d714837bb3..09436e6ff4 100755 --- a/system/hardware/tici/amplifier.py +++ b/system/hardware/tici/amplifier.py @@ -1,8 +1,9 @@ #!/usr/bin/env python3 import time -from smbus2 import SMBus from collections import namedtuple +from openpilot.common.i2c import SMBus + # https://datasheets.maximintegrated.com/en/ds/MAX98089.pdf AmpConfig = namedtuple('AmpConfig', ['name', 'value', 'register', 'offset', 'mask']) diff --git a/system/sensord/sensors/i2c_sensor.py b/system/sensord/sensors/i2c_sensor.py index 336ebb1fd3..57edcc52d9 100644 --- a/system/sensord/sensors/i2c_sensor.py +++ b/system/sensord/sensors/i2c_sensor.py @@ -1,9 +1,10 @@ import time -import smbus2 import ctypes from collections.abc import Iterable from cereal import log +from openpilot.common.i2c import SMBus + class Sensor: class SensorException(Exception): @@ -13,7 +14,7 @@ class Sensor: pass def __init__(self, bus: int) -> None: - self.bus = smbus2.SMBus(bus) + self.bus = SMBus(bus) self.source = log.SensorEventData.SensorSource.velodyne # unknown self.start_ts = 0. diff --git a/uv.lock b/uv.lock index 3e3522eb39..2c5f32ec7b 100644 --- a/uv.lock +++ b/uv.lock @@ -1316,7 +1316,6 @@ dependencies = [ { name = "sentry-sdk" }, { name = "setproctitle" }, { name = "setuptools" }, - { name = "smbus2" }, { name = "sounddevice" }, { name = "spidev", marker = "sys_platform == 'linux'" }, { name = "sympy" }, @@ -1423,7 +1422,6 @@ requires-dist = [ { name = "sentry-sdk" }, { name = "setproctitle" }, { name = "setuptools" }, - { name = "smbus2" }, { name = "sounddevice" }, { name = "spidev", marker = "sys_platform == 'linux'" }, { name = "sympy" }, @@ -4741,15 +4739,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/b7/ce/149a00dd41f10bc29e5921b496af8b574d8413afcd5e30dfa0ed46c2cc5e/six-1.17.0-py2.py3-none-any.whl", hash = "sha256:4721f391ed90541fddacab5acf947aa0d3dc7d27b2e1e8eda2be8970586c3274", size = 11050, upload-time = "2024-12-04T17:35:26.475Z" }, ] -[[package]] -name = "smbus2" -version = "0.6.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/4e/36/afafd43770caae69f04e21402552a8f94a072def46a002fab9357f4852ce/smbus2-0.6.0.tar.gz", hash = "sha256:9b5ff1e998e114730f9dfe0c4babbef06c92468cfb61eaa684e30f225661b95b", size = 17403, upload-time = "2025-12-20T09:02:52.017Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/a5/cf/2e1d6805da6f9c9b3a4358076ff2e072d828ba7fed124edc1b729e210c55/smbus2-0.6.0-py2.py3-none-any.whl", hash = "sha256:03d83d2a9a4afc5ddca0698ccabf101cb3de52bc5aefd7b76778ffb27ff654e0", size = 11849, upload-time = "2025-12-20T09:02:51.219Z" }, -] - [[package]] name = "sortedcontainers" version = "2.4.0" From 5fc4c2b25cce04ce6229da76893a2b46d010ccde Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 1 Feb 2026 20:00:55 -0800 Subject: [PATCH 38/46] ubloxd: remove kaitai (#37055) * rm kaitai * lil less * bs * lil less * lil less --- SConstruct | 2 - pyproject.toml | 3 - system/ubloxd/SConscript | 11 -- system/ubloxd/binary_struct.py | 280 +++++++++++++++++++++++++++ system/ubloxd/generated/glonass.py | 247 ------------------------ system/ubloxd/generated/gps.py | 193 ------------------- system/ubloxd/generated/ubx.py | 273 --------------------------- system/ubloxd/glonass.ksy | 176 ----------------- system/ubloxd/glonass.py | 156 +++++++++++++++ system/ubloxd/gps.ksy | 189 ------------------- system/ubloxd/gps.py | 116 ++++++++++++ system/ubloxd/ubloxd.py | 33 +++- system/ubloxd/ubx.ksy | 293 ----------------------------- system/ubloxd/ubx.py | 180 ++++++++++++++++++ uv.lock | 11 -- 15 files changed, 756 insertions(+), 1407 deletions(-) delete mode 100644 system/ubloxd/SConscript create mode 100644 system/ubloxd/binary_struct.py delete mode 100644 system/ubloxd/generated/glonass.py delete mode 100644 system/ubloxd/generated/gps.py delete mode 100644 system/ubloxd/generated/ubx.py delete mode 100644 system/ubloxd/glonass.ksy create mode 100644 system/ubloxd/glonass.py delete mode 100644 system/ubloxd/gps.ksy create mode 100644 system/ubloxd/gps.py delete mode 100644 system/ubloxd/ubx.ksy create mode 100644 system/ubloxd/ubx.py diff --git a/SConstruct b/SConstruct index 094503cfa7..ca5b7b6cb7 100644 --- a/SConstruct +++ b/SConstruct @@ -14,7 +14,6 @@ Decider('MD5-timestamp') SetOption('num_jobs', max(1, int(os.cpu_count()/2))) -AddOption('--kaitai', action='store_true', help='Regenerate kaitai struct parsers') AddOption('--asan', action='store_true', help='turn on ASAN') AddOption('--ubsan', action='store_true', help='turn on UBSan') AddOption('--mutation', action='store_true', help='generate mutation-ready code') @@ -202,7 +201,6 @@ SConscript(['rednose/SConscript']) # Build system services SConscript([ - 'system/ubloxd/SConscript', 'system/loggerd/SConscript', ]) diff --git a/pyproject.toml b/pyproject.toml index 19491ba532..1be5c395f1 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -33,9 +33,6 @@ dependencies = [ "pyopenssl < 24.3.0", "pyaudio", - # ubloxd (TODO: just use struct) - "kaitaistruct", - # panda "libusb1", "spidev; platform_system == 'Linux'", diff --git a/system/ubloxd/SConscript b/system/ubloxd/SConscript deleted file mode 100644 index 9eb50760ba..0000000000 --- a/system/ubloxd/SConscript +++ /dev/null @@ -1,11 +0,0 @@ -Import('env') - -if GetOption('kaitai'): - current_dir = Dir('./generated/').srcnode().abspath - python_cmd = f"kaitai-struct-compiler --target python --outdir {current_dir} $SOURCES" - env.Command(File('./generated/ubx.py'), 'ubx.ksy', python_cmd) - env.Command(File('./generated/gps.py'), 'gps.ksy', python_cmd) - env.Command(File('./generated/glonass.py'), 'glonass.ksy', python_cmd) - # kaitai issue: https://github.com/kaitai-io/kaitai_struct/issues/910 - py_glonass_fix = env.Command(None, File('./generated/glonass.py'), "sed -i 's/self._io.align_to_byte()/# self._io.align_to_byte()/' $SOURCES") - env.Depends(py_glonass_fix, File('./generated/glonass.py')) diff --git a/system/ubloxd/binary_struct.py b/system/ubloxd/binary_struct.py new file mode 100644 index 0000000000..7b229620a2 --- /dev/null +++ b/system/ubloxd/binary_struct.py @@ -0,0 +1,280 @@ +""" +Binary struct parsing DSL. + +Defines a declarative schema for binary messages using dataclasses +and type annotations. +""" + +import struct +from enum import Enum +from dataclasses import dataclass, is_dataclass +from typing import Annotated, Any, TypeVar, get_args, get_origin + + +class FieldType: + """Base class for field type descriptors.""" + + +@dataclass(frozen=True) +class IntType(FieldType): + bits: int + signed: bool + big_endian: bool = False + +@dataclass(frozen=True) +class FloatType(FieldType): + bits: int + +@dataclass(frozen=True) +class BitsType(FieldType): + bits: int + +@dataclass(frozen=True) +class BytesType(FieldType): + size: int + +@dataclass(frozen=True) +class ArrayType(FieldType): + element_type: Any + count_field: str + +@dataclass(frozen=True) +class SwitchType(FieldType): + selector: str + cases: dict[Any, Any] + default: Any = None + +@dataclass(frozen=True) +class EnumType(FieldType): + base_type: FieldType + enum_cls: type[Enum] + +@dataclass(frozen=True) +class ConstType(FieldType): + base_type: FieldType + expected: Any + +@dataclass(frozen=True) +class SubstreamType(FieldType): + length_field: str + element_type: Any + +# Common types - little endian +u8 = IntType(8, False) +u16 = IntType(16, False) +u32 = IntType(32, False) +s8 = IntType(8, True) +s16 = IntType(16, True) +s32 = IntType(32, True) +f32 = FloatType(32) +f64 = FloatType(64) +# Big endian variants +u16be = IntType(16, False, big_endian=True) +u32be = IntType(32, False, big_endian=True) +s16be = IntType(16, True, big_endian=True) +s32be = IntType(32, True, big_endian=True) + + +def bits(n: int) -> BitsType: + """Create a bit-level field type.""" + return BitsType(n) + +def bytes_field(size: int) -> BytesType: + """Create a fixed-size bytes field.""" + return BytesType(size) + +def array(element_type: Any, count_field: str) -> ArrayType: + """Create an array/repeated field.""" + return ArrayType(element_type, count_field) + +def switch(selector: str, cases: dict[Any, Any], default: Any = None) -> SwitchType: + """Create a switch-on field.""" + return SwitchType(selector, cases, default) + +def enum(base_type: Any, enum_cls: type[Enum]) -> EnumType: + """Create an enum-wrapped field.""" + field_type = _field_type_from_spec(base_type) + if field_type is None: + raise TypeError(f"Unsupported field type: {base_type!r}") + return EnumType(field_type, enum_cls) + +def const(base_type: Any, expected: Any) -> ConstType: + """Create a constant-value field.""" + field_type = _field_type_from_spec(base_type) + if field_type is None: + raise TypeError(f"Unsupported field type: {base_type!r}") + return ConstType(field_type, expected) + +def substream(length_field: str, element_type: Any) -> SubstreamType: + """Parse a fixed-length substream using an inner schema.""" + return SubstreamType(length_field, element_type) + + +class BinaryReader: + def __init__(self, data: bytes): + self.data = data + self.pos = 0 + self.bit_pos = 0 # 0-7, position within current byte + + def _require(self, n: int) -> None: + if self.pos + n > len(self.data): + raise EOFError("Unexpected end of data") + + def _read_struct(self, fmt: str): + self._align_to_byte() + size = struct.calcsize(fmt) + self._require(size) + value = struct.unpack_from(fmt, self.data, self.pos)[0] + self.pos += size + return value + + def read_bytes(self, n: int) -> bytes: + self._align_to_byte() + self._require(n) + result = self.data[self.pos : self.pos + n] + self.pos += n + return result + + def read_bits_int_be(self, n: int) -> int: + result = 0 + bits_remaining = n + while bits_remaining > 0: + if self.pos >= len(self.data): + raise EOFError("Unexpected end of data while reading bits") + bits_in_byte = 8 - self.bit_pos + bits_to_read = min(bits_remaining, bits_in_byte) + byte_val = self.data[self.pos] + shift = bits_in_byte - bits_to_read + mask = (1 << bits_to_read) - 1 + extracted = (byte_val >> shift) & mask + result = (result << bits_to_read) | extracted + self.bit_pos += bits_to_read + bits_remaining -= bits_to_read + if self.bit_pos >= 8: + self.bit_pos = 0 + self.pos += 1 + return result + + def _align_to_byte(self) -> None: + if self.bit_pos > 0: + self.bit_pos = 0 + self.pos += 1 + + +T = TypeVar('T', bound='BinaryStruct') + + +class BinaryStruct: + """Base class for binary struct definitions.""" + + def __init_subclass__(cls, **kwargs) -> None: + super().__init_subclass__(**kwargs) + if cls is BinaryStruct: + return + if not is_dataclass(cls): + dataclass(init=False)(cls) + fields = list(getattr(cls, '__annotations__', {}).items()) + cls.__binary_fields__ = fields # type: ignore[attr-defined] + + @classmethod + def _read(inner_cls, reader: BinaryReader): + obj = inner_cls.__new__(inner_cls) + for name, spec in inner_cls.__binary_fields__: + value = _parse_field(spec, reader, obj) + setattr(obj, name, value) + return obj + + cls._read = _read # type: ignore[attr-defined] + + @classmethod + def from_bytes(cls: type[T], data: bytes) -> T: + """Parse struct from bytes.""" + reader = BinaryReader(data) + return cls._read(reader) + + @classmethod + def _read(cls: type[T], reader: BinaryReader) -> T: + """Override in subclasses to implement parsing.""" + raise NotImplementedError + + +def _resolve_path(obj: Any, path: str) -> Any: + cur = obj + for part in path.split('.'): + cur = getattr(cur, part) + return cur + +def _unwrap_annotated(spec: Any) -> tuple[Any, ...]: + if get_origin(spec) is Annotated: + return get_args(spec)[1:] + return () + +def _field_type_from_spec(spec: Any) -> FieldType | None: + if isinstance(spec, FieldType): + return spec + for item in _unwrap_annotated(spec): + if isinstance(item, FieldType): + return item + return None + + +def _int_format(field_type: IntType) -> str: + if field_type.bits == 8: + return 'b' if field_type.signed else 'B' + endian = '>' if field_type.big_endian else '<' + if field_type.bits == 16: + code = 'h' if field_type.signed else 'H' + elif field_type.bits == 32: + code = 'i' if field_type.signed else 'I' + else: + raise ValueError(f"Unsupported integer size: {field_type.bits}") + return f"{endian}{code}" + +def _float_format(field_type: FloatType) -> str: + if field_type.bits == 32: + return ' Any: + field_type = _field_type_from_spec(spec) + if field_type is not None: + spec = field_type + if isinstance(spec, ConstType): + value = _parse_field(spec.base_type, reader, obj) + if value != spec.expected: + raise ValueError(f"Invalid constant: expected {spec.expected!r}, got {value!r}") + return value + if isinstance(spec, EnumType): + raw = _parse_field(spec.base_type, reader, obj) + try: + return spec.enum_cls(raw) + except ValueError: + return raw + if isinstance(spec, SwitchType): + key = _resolve_path(obj, spec.selector) + target = spec.cases.get(key, spec.default) + if target is None: + return None + return _parse_field(target, reader, obj) + if isinstance(spec, ArrayType): + count = _resolve_path(obj, spec.count_field) + return [_parse_field(spec.element_type, reader, obj) for _ in range(int(count))] + if isinstance(spec, SubstreamType): + length = _resolve_path(obj, spec.length_field) + data = reader.read_bytes(int(length)) + sub_reader = BinaryReader(data) + return _parse_field(spec.element_type, sub_reader, obj) + if isinstance(spec, IntType): + return reader._read_struct(_int_format(spec)) + if isinstance(spec, FloatType): + return reader._read_struct(_float_format(spec)) + if isinstance(spec, BitsType): + value = reader.read_bits_int_be(spec.bits) + return bool(value) if spec.bits == 1 else value + if isinstance(spec, BytesType): + return reader.read_bytes(spec.size) + if isinstance(spec, type) and issubclass(spec, BinaryStruct): + return spec._read(reader) + raise TypeError(f"Unsupported field spec: {spec!r}") diff --git a/system/ubloxd/generated/glonass.py b/system/ubloxd/generated/glonass.py deleted file mode 100644 index 40aa16bb6f..0000000000 --- a/system/ubloxd/generated/glonass.py +++ /dev/null @@ -1,247 +0,0 @@ -# This is a generated file! Please edit source .ksy file and use kaitai-struct-compiler to rebuild - -import kaitaistruct -from kaitaistruct import KaitaiStruct, KaitaiStream, BytesIO - - -if getattr(kaitaistruct, 'API_VERSION', (0, 9)) < (0, 9): - raise Exception("Incompatible Kaitai Struct Python API: 0.9 or later is required, but you have %s" % (kaitaistruct.__version__)) - -class Glonass(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.idle_chip = self._io.read_bits_int_be(1) != 0 - self.string_number = self._io.read_bits_int_be(4) - # workaround for kaitai bit alignment issue (see glonass_fix.patch for C++) - # self._io.align_to_byte() - _on = self.string_number - if _on == 4: - self.data = Glonass.String4(self._io, self, self._root) - elif _on == 1: - self.data = Glonass.String1(self._io, self, self._root) - elif _on == 3: - self.data = Glonass.String3(self._io, self, self._root) - elif _on == 5: - self.data = Glonass.String5(self._io, self, self._root) - elif _on == 2: - self.data = Glonass.String2(self._io, self, self._root) - else: - self.data = Glonass.StringNonImmediate(self._io, self, self._root) - self.hamming_code = self._io.read_bits_int_be(8) - self.pad_1 = self._io.read_bits_int_be(11) - self.superframe_number = self._io.read_bits_int_be(16) - self.pad_2 = self._io.read_bits_int_be(8) - self.frame_number = self._io.read_bits_int_be(8) - - class String4(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.tau_n_sign = self._io.read_bits_int_be(1) != 0 - self.tau_n_value = self._io.read_bits_int_be(21) - self.delta_tau_n_sign = self._io.read_bits_int_be(1) != 0 - self.delta_tau_n_value = self._io.read_bits_int_be(4) - self.e_n = self._io.read_bits_int_be(5) - self.not_used_1 = self._io.read_bits_int_be(14) - self.p4 = self._io.read_bits_int_be(1) != 0 - self.f_t = self._io.read_bits_int_be(4) - self.not_used_2 = self._io.read_bits_int_be(3) - self.n_t = self._io.read_bits_int_be(11) - self.n = self._io.read_bits_int_be(5) - self.m = self._io.read_bits_int_be(2) - - @property - def tau_n(self): - if hasattr(self, '_m_tau_n'): - return self._m_tau_n - - self._m_tau_n = ((self.tau_n_value * -1) if self.tau_n_sign else self.tau_n_value) - return getattr(self, '_m_tau_n', None) - - @property - def delta_tau_n(self): - if hasattr(self, '_m_delta_tau_n'): - return self._m_delta_tau_n - - self._m_delta_tau_n = ((self.delta_tau_n_value * -1) if self.delta_tau_n_sign else self.delta_tau_n_value) - return getattr(self, '_m_delta_tau_n', None) - - - class StringNonImmediate(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.data_1 = self._io.read_bits_int_be(64) - self.data_2 = self._io.read_bits_int_be(8) - - - class String5(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.n_a = self._io.read_bits_int_be(11) - self.tau_c = self._io.read_bits_int_be(32) - self.not_used = self._io.read_bits_int_be(1) != 0 - self.n_4 = self._io.read_bits_int_be(5) - self.tau_gps = self._io.read_bits_int_be(22) - self.l_n = self._io.read_bits_int_be(1) != 0 - - - class String1(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.not_used = self._io.read_bits_int_be(2) - self.p1 = self._io.read_bits_int_be(2) - self.t_k = self._io.read_bits_int_be(12) - self.x_vel_sign = self._io.read_bits_int_be(1) != 0 - self.x_vel_value = self._io.read_bits_int_be(23) - self.x_accel_sign = self._io.read_bits_int_be(1) != 0 - self.x_accel_value = self._io.read_bits_int_be(4) - self.x_sign = self._io.read_bits_int_be(1) != 0 - self.x_value = self._io.read_bits_int_be(26) - - @property - def x_vel(self): - if hasattr(self, '_m_x_vel'): - return self._m_x_vel - - self._m_x_vel = ((self.x_vel_value * -1) if self.x_vel_sign else self.x_vel_value) - return getattr(self, '_m_x_vel', None) - - @property - def x_accel(self): - if hasattr(self, '_m_x_accel'): - return self._m_x_accel - - self._m_x_accel = ((self.x_accel_value * -1) if self.x_accel_sign else self.x_accel_value) - return getattr(self, '_m_x_accel', None) - - @property - def x(self): - if hasattr(self, '_m_x'): - return self._m_x - - self._m_x = ((self.x_value * -1) if self.x_sign else self.x_value) - return getattr(self, '_m_x', None) - - - class String2(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.b_n = self._io.read_bits_int_be(3) - self.p2 = self._io.read_bits_int_be(1) != 0 - self.t_b = self._io.read_bits_int_be(7) - self.not_used = self._io.read_bits_int_be(5) - self.y_vel_sign = self._io.read_bits_int_be(1) != 0 - self.y_vel_value = self._io.read_bits_int_be(23) - self.y_accel_sign = self._io.read_bits_int_be(1) != 0 - self.y_accel_value = self._io.read_bits_int_be(4) - self.y_sign = self._io.read_bits_int_be(1) != 0 - self.y_value = self._io.read_bits_int_be(26) - - @property - def y_vel(self): - if hasattr(self, '_m_y_vel'): - return self._m_y_vel - - self._m_y_vel = ((self.y_vel_value * -1) if self.y_vel_sign else self.y_vel_value) - return getattr(self, '_m_y_vel', None) - - @property - def y_accel(self): - if hasattr(self, '_m_y_accel'): - return self._m_y_accel - - self._m_y_accel = ((self.y_accel_value * -1) if self.y_accel_sign else self.y_accel_value) - return getattr(self, '_m_y_accel', None) - - @property - def y(self): - if hasattr(self, '_m_y'): - return self._m_y - - self._m_y = ((self.y_value * -1) if self.y_sign else self.y_value) - return getattr(self, '_m_y', None) - - - class String3(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.p3 = self._io.read_bits_int_be(1) != 0 - self.gamma_n_sign = self._io.read_bits_int_be(1) != 0 - self.gamma_n_value = self._io.read_bits_int_be(10) - self.not_used = self._io.read_bits_int_be(1) != 0 - self.p = self._io.read_bits_int_be(2) - self.l_n = self._io.read_bits_int_be(1) != 0 - self.z_vel_sign = self._io.read_bits_int_be(1) != 0 - self.z_vel_value = self._io.read_bits_int_be(23) - self.z_accel_sign = self._io.read_bits_int_be(1) != 0 - self.z_accel_value = self._io.read_bits_int_be(4) - self.z_sign = self._io.read_bits_int_be(1) != 0 - self.z_value = self._io.read_bits_int_be(26) - - @property - def gamma_n(self): - if hasattr(self, '_m_gamma_n'): - return self._m_gamma_n - - self._m_gamma_n = ((self.gamma_n_value * -1) if self.gamma_n_sign else self.gamma_n_value) - return getattr(self, '_m_gamma_n', None) - - @property - def z_vel(self): - if hasattr(self, '_m_z_vel'): - return self._m_z_vel - - self._m_z_vel = ((self.z_vel_value * -1) if self.z_vel_sign else self.z_vel_value) - return getattr(self, '_m_z_vel', None) - - @property - def z_accel(self): - if hasattr(self, '_m_z_accel'): - return self._m_z_accel - - self._m_z_accel = ((self.z_accel_value * -1) if self.z_accel_sign else self.z_accel_value) - return getattr(self, '_m_z_accel', None) - - @property - def z(self): - if hasattr(self, '_m_z'): - return self._m_z - - self._m_z = ((self.z_value * -1) if self.z_sign else self.z_value) - return getattr(self, '_m_z', None) - - diff --git a/system/ubloxd/generated/gps.py b/system/ubloxd/generated/gps.py deleted file mode 100644 index a999016f3e..0000000000 --- a/system/ubloxd/generated/gps.py +++ /dev/null @@ -1,193 +0,0 @@ -# This is a generated file! Please edit source .ksy file and use kaitai-struct-compiler to rebuild - -import kaitaistruct -from kaitaistruct import KaitaiStruct, KaitaiStream, BytesIO - - -if getattr(kaitaistruct, 'API_VERSION', (0, 9)) < (0, 9): - raise Exception("Incompatible Kaitai Struct Python API: 0.9 or later is required, but you have %s" % (kaitaistruct.__version__)) - -class Gps(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.tlm = Gps.Tlm(self._io, self, self._root) - self.how = Gps.How(self._io, self, self._root) - _on = self.how.subframe_id - if _on == 1: - self.body = Gps.Subframe1(self._io, self, self._root) - elif _on == 2: - self.body = Gps.Subframe2(self._io, self, self._root) - elif _on == 3: - self.body = Gps.Subframe3(self._io, self, self._root) - elif _on == 4: - self.body = Gps.Subframe4(self._io, self, self._root) - - class Subframe1(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.week_no = self._io.read_bits_int_be(10) - self.code = self._io.read_bits_int_be(2) - self.sv_accuracy = self._io.read_bits_int_be(4) - self.sv_health = self._io.read_bits_int_be(6) - self.iodc_msb = self._io.read_bits_int_be(2) - self.l2_p_data_flag = self._io.read_bits_int_be(1) != 0 - self.reserved1 = self._io.read_bits_int_be(23) - self.reserved2 = self._io.read_bits_int_be(24) - self.reserved3 = self._io.read_bits_int_be(24) - self.reserved4 = self._io.read_bits_int_be(16) - self._io.align_to_byte() - self.t_gd = self._io.read_s1() - self.iodc_lsb = self._io.read_u1() - self.t_oc = self._io.read_u2be() - self.af_2 = self._io.read_s1() - self.af_1 = self._io.read_s2be() - self.af_0_sign = self._io.read_bits_int_be(1) != 0 - self.af_0_value = self._io.read_bits_int_be(21) - self.reserved5 = self._io.read_bits_int_be(2) - - @property - def af_0(self): - if hasattr(self, '_m_af_0'): - return self._m_af_0 - - self._m_af_0 = ((self.af_0_value - (1 << 21)) if self.af_0_sign else self.af_0_value) - return getattr(self, '_m_af_0', None) - - - class Subframe3(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.c_ic = self._io.read_s2be() - self.omega_0 = self._io.read_s4be() - self.c_is = self._io.read_s2be() - self.i_0 = self._io.read_s4be() - self.c_rc = self._io.read_s2be() - self.omega = self._io.read_s4be() - self.omega_dot_sign = self._io.read_bits_int_be(1) != 0 - self.omega_dot_value = self._io.read_bits_int_be(23) - self._io.align_to_byte() - self.iode = self._io.read_u1() - self.idot_sign = self._io.read_bits_int_be(1) != 0 - self.idot_value = self._io.read_bits_int_be(13) - self.reserved = self._io.read_bits_int_be(2) - - @property - def omega_dot(self): - if hasattr(self, '_m_omega_dot'): - return self._m_omega_dot - - self._m_omega_dot = ((self.omega_dot_value - (1 << 23)) if self.omega_dot_sign else self.omega_dot_value) - return getattr(self, '_m_omega_dot', None) - - @property - def idot(self): - if hasattr(self, '_m_idot'): - return self._m_idot - - self._m_idot = ((self.idot_value - (1 << 13)) if self.idot_sign else self.idot_value) - return getattr(self, '_m_idot', None) - - - class Subframe4(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.data_id = self._io.read_bits_int_be(2) - self.page_id = self._io.read_bits_int_be(6) - self._io.align_to_byte() - _on = self.page_id - if _on == 56: - self.body = Gps.Subframe4.IonosphereData(self._io, self, self._root) - - class IonosphereData(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.a0 = self._io.read_s1() - self.a1 = self._io.read_s1() - self.a2 = self._io.read_s1() - self.a3 = self._io.read_s1() - self.b0 = self._io.read_s1() - self.b1 = self._io.read_s1() - self.b2 = self._io.read_s1() - self.b3 = self._io.read_s1() - - - - class How(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.tow_count = self._io.read_bits_int_be(17) - self.alert = self._io.read_bits_int_be(1) != 0 - self.anti_spoof = self._io.read_bits_int_be(1) != 0 - self.subframe_id = self._io.read_bits_int_be(3) - self.reserved = self._io.read_bits_int_be(2) - - - class Tlm(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.preamble = self._io.read_bytes(1) - if not self.preamble == b"\x8B": - raise kaitaistruct.ValidationNotEqualError(b"\x8B", self.preamble, self._io, u"/types/tlm/seq/0") - self.tlm = self._io.read_bits_int_be(14) - self.integrity_status = self._io.read_bits_int_be(1) != 0 - self.reserved = self._io.read_bits_int_be(1) != 0 - - - class Subframe2(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.iode = self._io.read_u1() - self.c_rs = self._io.read_s2be() - self.delta_n = self._io.read_s2be() - self.m_0 = self._io.read_s4be() - self.c_uc = self._io.read_s2be() - self.e = self._io.read_s4be() - self.c_us = self._io.read_s2be() - self.sqrt_a = self._io.read_u4be() - self.t_oe = self._io.read_u2be() - self.fit_interval_flag = self._io.read_bits_int_be(1) != 0 - self.aoda = self._io.read_bits_int_be(5) - self.reserved = self._io.read_bits_int_be(2) - - - diff --git a/system/ubloxd/generated/ubx.py b/system/ubloxd/generated/ubx.py deleted file mode 100644 index 9946584388..0000000000 --- a/system/ubloxd/generated/ubx.py +++ /dev/null @@ -1,273 +0,0 @@ -# This is a generated file! Please edit source .ksy file and use kaitai-struct-compiler to rebuild - -import kaitaistruct -from kaitaistruct import KaitaiStruct, KaitaiStream, BytesIO -from enum import Enum - - -if getattr(kaitaistruct, 'API_VERSION', (0, 9)) < (0, 9): - raise Exception("Incompatible Kaitai Struct Python API: 0.9 or later is required, but you have %s" % (kaitaistruct.__version__)) - -class Ubx(KaitaiStruct): - - class GnssType(Enum): - gps = 0 - sbas = 1 - galileo = 2 - beidou = 3 - imes = 4 - qzss = 5 - glonass = 6 - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.magic = self._io.read_bytes(2) - if not self.magic == b"\xB5\x62": - raise kaitaistruct.ValidationNotEqualError(b"\xB5\x62", self.magic, self._io, u"/seq/0") - self.msg_type = self._io.read_u2be() - self.length = self._io.read_u2le() - _on = self.msg_type - if _on == 2569: - self.body = Ubx.MonHw(self._io, self, self._root) - elif _on == 533: - self.body = Ubx.RxmRawx(self._io, self, self._root) - elif _on == 531: - self.body = Ubx.RxmSfrbx(self._io, self, self._root) - elif _on == 309: - self.body = Ubx.NavSat(self._io, self, self._root) - elif _on == 2571: - self.body = Ubx.MonHw2(self._io, self, self._root) - elif _on == 263: - self.body = Ubx.NavPvt(self._io, self, self._root) - - class RxmRawx(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.rcv_tow = self._io.read_f8le() - self.week = self._io.read_u2le() - self.leap_s = self._io.read_s1() - self.num_meas = self._io.read_u1() - self.rec_stat = self._io.read_u1() - self.reserved1 = self._io.read_bytes(3) - self._raw_meas = [] - self.meas = [] - for i in range(self.num_meas): - self._raw_meas.append(self._io.read_bytes(32)) - _io__raw_meas = KaitaiStream(BytesIO(self._raw_meas[i])) - self.meas.append(Ubx.RxmRawx.Measurement(_io__raw_meas, self, self._root)) - - - class Measurement(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.pr_mes = self._io.read_f8le() - self.cp_mes = self._io.read_f8le() - self.do_mes = self._io.read_f4le() - self.gnss_id = KaitaiStream.resolve_enum(Ubx.GnssType, self._io.read_u1()) - self.sv_id = self._io.read_u1() - self.reserved2 = self._io.read_bytes(1) - self.freq_id = self._io.read_u1() - self.lock_time = self._io.read_u2le() - self.cno = self._io.read_u1() - self.pr_stdev = self._io.read_u1() - self.cp_stdev = self._io.read_u1() - self.do_stdev = self._io.read_u1() - self.trk_stat = self._io.read_u1() - self.reserved3 = self._io.read_bytes(1) - - - - class RxmSfrbx(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.gnss_id = KaitaiStream.resolve_enum(Ubx.GnssType, self._io.read_u1()) - self.sv_id = self._io.read_u1() - self.reserved1 = self._io.read_bytes(1) - self.freq_id = self._io.read_u1() - self.num_words = self._io.read_u1() - self.reserved2 = self._io.read_bytes(1) - self.version = self._io.read_u1() - self.reserved3 = self._io.read_bytes(1) - self.body = [] - for i in range(self.num_words): - self.body.append(self._io.read_u4le()) - - - - class NavSat(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.itow = self._io.read_u4le() - self.version = self._io.read_u1() - self.num_svs = self._io.read_u1() - self.reserved = self._io.read_bytes(2) - self._raw_svs = [] - self.svs = [] - for i in range(self.num_svs): - self._raw_svs.append(self._io.read_bytes(12)) - _io__raw_svs = KaitaiStream(BytesIO(self._raw_svs[i])) - self.svs.append(Ubx.NavSat.Nav(_io__raw_svs, self, self._root)) - - - class Nav(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.gnss_id = KaitaiStream.resolve_enum(Ubx.GnssType, self._io.read_u1()) - self.sv_id = self._io.read_u1() - self.cno = self._io.read_u1() - self.elev = self._io.read_s1() - self.azim = self._io.read_s2le() - self.pr_res = self._io.read_s2le() - self.flags = self._io.read_u4le() - - - - class NavPvt(KaitaiStruct): - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.i_tow = self._io.read_u4le() - self.year = self._io.read_u2le() - self.month = self._io.read_u1() - self.day = self._io.read_u1() - self.hour = self._io.read_u1() - self.min = self._io.read_u1() - self.sec = self._io.read_u1() - self.valid = self._io.read_u1() - self.t_acc = self._io.read_u4le() - self.nano = self._io.read_s4le() - self.fix_type = self._io.read_u1() - self.flags = self._io.read_u1() - self.flags2 = self._io.read_u1() - self.num_sv = self._io.read_u1() - self.lon = self._io.read_s4le() - self.lat = self._io.read_s4le() - self.height = self._io.read_s4le() - self.h_msl = self._io.read_s4le() - self.h_acc = self._io.read_u4le() - self.v_acc = self._io.read_u4le() - self.vel_n = self._io.read_s4le() - self.vel_e = self._io.read_s4le() - self.vel_d = self._io.read_s4le() - self.g_speed = self._io.read_s4le() - self.head_mot = self._io.read_s4le() - self.s_acc = self._io.read_s4le() - self.head_acc = self._io.read_u4le() - self.p_dop = self._io.read_u2le() - self.flags3 = self._io.read_u1() - self.reserved1 = self._io.read_bytes(5) - self.head_veh = self._io.read_s4le() - self.mag_dec = self._io.read_s2le() - self.mag_acc = self._io.read_u2le() - - - class MonHw2(KaitaiStruct): - - class ConfigSource(Enum): - flash = 102 - otp = 111 - config_pins = 112 - rom = 113 - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.ofs_i = self._io.read_s1() - self.mag_i = self._io.read_u1() - self.ofs_q = self._io.read_s1() - self.mag_q = self._io.read_u1() - self.cfg_source = KaitaiStream.resolve_enum(Ubx.MonHw2.ConfigSource, self._io.read_u1()) - self.reserved1 = self._io.read_bytes(3) - self.low_lev_cfg = self._io.read_u4le() - self.reserved2 = self._io.read_bytes(8) - self.post_status = self._io.read_u4le() - self.reserved3 = self._io.read_bytes(4) - - - class MonHw(KaitaiStruct): - - class AntennaStatus(Enum): - init = 0 - dontknow = 1 - ok = 2 - short = 3 - open = 4 - - class AntennaPower(Enum): - false = 0 - true = 1 - dontknow = 2 - def __init__(self, _io, _parent=None, _root=None): - self._io = _io - self._parent = _parent - self._root = _root if _root else self - self._read() - - def _read(self): - self.pin_sel = self._io.read_u4le() - self.pin_bank = self._io.read_u4le() - self.pin_dir = self._io.read_u4le() - self.pin_val = self._io.read_u4le() - self.noise_per_ms = self._io.read_u2le() - self.agc_cnt = self._io.read_u2le() - self.a_status = KaitaiStream.resolve_enum(Ubx.MonHw.AntennaStatus, self._io.read_u1()) - self.a_power = KaitaiStream.resolve_enum(Ubx.MonHw.AntennaPower, self._io.read_u1()) - self.flags = self._io.read_u1() - self.reserved1 = self._io.read_bytes(1) - self.used_mask = self._io.read_u4le() - self.vp = self._io.read_bytes(17) - self.jam_ind = self._io.read_u1() - self.reserved2 = self._io.read_bytes(2) - self.pin_irq = self._io.read_u4le() - self.pull_h = self._io.read_u4le() - self.pull_l = self._io.read_u4le() - - - @property - def checksum(self): - if hasattr(self, '_m_checksum'): - return self._m_checksum - - _pos = self._io.pos() - self._io.seek((self.length + 6)) - self._m_checksum = self._io.read_u2le() - self._io.seek(_pos) - return getattr(self, '_m_checksum', None) - - diff --git a/system/ubloxd/glonass.ksy b/system/ubloxd/glonass.ksy deleted file mode 100644 index be99f6e497..0000000000 --- a/system/ubloxd/glonass.ksy +++ /dev/null @@ -1,176 +0,0 @@ -# http://gauss.gge.unb.ca/GLONASS.ICD.pdf -# some variables are misprinted but good in the old doc -# https://www.unavco.org/help/glossary/docs/ICD_GLONASS_4.0_(1998)_en.pdf -meta: - id: glonass - endian: be - bit-endian: be -seq: - - id: idle_chip - type: b1 - - id: string_number - type: b4 - - id: data - type: - switch-on: string_number - cases: - 1: string_1 - 2: string_2 - 3: string_3 - 4: string_4 - 5: string_5 - _: string_non_immediate - - id: hamming_code - type: b8 - - id: pad_1 - type: b11 - - id: superframe_number - type: b16 - - id: pad_2 - type: b8 - - id: frame_number - type: b8 - -types: - string_1: - seq: - - id: not_used - type: b2 - - id: p1 - type: b2 - - id: t_k - type: b12 - - id: x_vel_sign - type: b1 - - id: x_vel_value - type: b23 - - id: x_accel_sign - type: b1 - - id: x_accel_value - type: b4 - - id: x_sign - type: b1 - - id: x_value - type: b26 - instances: - x_vel: - value: 'x_vel_sign ? (x_vel_value * (-1)) : x_vel_value' - x_accel: - value: 'x_accel_sign ? (x_accel_value * (-1)) : x_accel_value' - x: - value: 'x_sign ? (x_value * (-1)) : x_value' - string_2: - seq: - - id: b_n - type: b3 - - id: p2 - type: b1 - - id: t_b - type: b7 - - id: not_used - type: b5 - - id: y_vel_sign - type: b1 - - id: y_vel_value - type: b23 - - id: y_accel_sign - type: b1 - - id: y_accel_value - type: b4 - - id: y_sign - type: b1 - - id: y_value - type: b26 - instances: - y_vel: - value: 'y_vel_sign ? (y_vel_value * (-1)) : y_vel_value' - y_accel: - value: 'y_accel_sign ? (y_accel_value * (-1)) : y_accel_value' - y: - value: 'y_sign ? (y_value * (-1)) : y_value' - string_3: - seq: - - id: p3 - type: b1 - - id: gamma_n_sign - type: b1 - - id: gamma_n_value - type: b10 - - id: not_used - type: b1 - - id: p - type: b2 - - id: l_n - type: b1 - - id: z_vel_sign - type: b1 - - id: z_vel_value - type: b23 - - id: z_accel_sign - type: b1 - - id: z_accel_value - type: b4 - - id: z_sign - type: b1 - - id: z_value - type: b26 - instances: - gamma_n: - value: 'gamma_n_sign ? (gamma_n_value * (-1)) : gamma_n_value' - z_vel: - value: 'z_vel_sign ? (z_vel_value * (-1)) : z_vel_value' - z_accel: - value: 'z_accel_sign ? (z_accel_value * (-1)) : z_accel_value' - z: - value: 'z_sign ? (z_value * (-1)) : z_value' - string_4: - seq: - - id: tau_n_sign - type: b1 - - id: tau_n_value - type: b21 - - id: delta_tau_n_sign - type: b1 - - id: delta_tau_n_value - type: b4 - - id: e_n - type: b5 - - id: not_used_1 - type: b14 - - id: p4 - type: b1 - - id: f_t - type: b4 - - id: not_used_2 - type: b3 - - id: n_t - type: b11 - - id: n - type: b5 - - id: m - type: b2 - instances: - tau_n: - value: 'tau_n_sign ? (tau_n_value * (-1)) : tau_n_value' - delta_tau_n: - value: 'delta_tau_n_sign ? (delta_tau_n_value * (-1)) : delta_tau_n_value' - string_5: - seq: - - id: n_a - type: b11 - - id: tau_c - type: b32 - - id: not_used - type: b1 - - id: n_4 - type: b5 - - id: tau_gps - type: b22 - - id: l_n - type: b1 - string_non_immediate: - seq: - - id: data_1 - type: b64 - - id: data_2 - type: b8 diff --git a/system/ubloxd/glonass.py b/system/ubloxd/glonass.py new file mode 100644 index 0000000000..144ccdde6e --- /dev/null +++ b/system/ubloxd/glonass.py @@ -0,0 +1,156 @@ +""" +Parses GLONASS navigation strings per GLONASS ICD specification. +http://gauss.gge.unb.ca/GLONASS.ICD.pdf +https://www.unavco.org/help/glossary/docs/ICD_GLONASS_4.0_(1998)_en.pdf +""" + +from typing import Annotated + +from openpilot.system.ubloxd import binary_struct as bs + + +class Glonass(bs.BinaryStruct): + class String1(bs.BinaryStruct): + not_used: Annotated[int, bs.bits(2)] + p1: Annotated[int, bs.bits(2)] + t_k: Annotated[int, bs.bits(12)] + x_vel_sign: Annotated[bool, bs.bits(1)] + x_vel_value: Annotated[int, bs.bits(23)] + x_accel_sign: Annotated[bool, bs.bits(1)] + x_accel_value: Annotated[int, bs.bits(4)] + x_sign: Annotated[bool, bs.bits(1)] + x_value: Annotated[int, bs.bits(26)] + + @property + def x_vel(self) -> int: + """Computed x_vel from sign-magnitude representation.""" + return (self.x_vel_value * -1) if self.x_vel_sign else self.x_vel_value + + @property + def x_accel(self) -> int: + """Computed x_accel from sign-magnitude representation.""" + return (self.x_accel_value * -1) if self.x_accel_sign else self.x_accel_value + + @property + def x(self) -> int: + """Computed x from sign-magnitude representation.""" + return (self.x_value * -1) if self.x_sign else self.x_value + + class String2(bs.BinaryStruct): + b_n: Annotated[int, bs.bits(3)] + p2: Annotated[bool, bs.bits(1)] + t_b: Annotated[int, bs.bits(7)] + not_used: Annotated[int, bs.bits(5)] + y_vel_sign: Annotated[bool, bs.bits(1)] + y_vel_value: Annotated[int, bs.bits(23)] + y_accel_sign: Annotated[bool, bs.bits(1)] + y_accel_value: Annotated[int, bs.bits(4)] + y_sign: Annotated[bool, bs.bits(1)] + y_value: Annotated[int, bs.bits(26)] + + @property + def y_vel(self) -> int: + """Computed y_vel from sign-magnitude representation.""" + return (self.y_vel_value * -1) if self.y_vel_sign else self.y_vel_value + + @property + def y_accel(self) -> int: + """Computed y_accel from sign-magnitude representation.""" + return (self.y_accel_value * -1) if self.y_accel_sign else self.y_accel_value + + @property + def y(self) -> int: + """Computed y from sign-magnitude representation.""" + return (self.y_value * -1) if self.y_sign else self.y_value + + class String3(bs.BinaryStruct): + p3: Annotated[bool, bs.bits(1)] + gamma_n_sign: Annotated[bool, bs.bits(1)] + gamma_n_value: Annotated[int, bs.bits(10)] + not_used: Annotated[bool, bs.bits(1)] + p: Annotated[int, bs.bits(2)] + l_n: Annotated[bool, bs.bits(1)] + z_vel_sign: Annotated[bool, bs.bits(1)] + z_vel_value: Annotated[int, bs.bits(23)] + z_accel_sign: Annotated[bool, bs.bits(1)] + z_accel_value: Annotated[int, bs.bits(4)] + z_sign: Annotated[bool, bs.bits(1)] + z_value: Annotated[int, bs.bits(26)] + + @property + def gamma_n(self) -> int: + """Computed gamma_n from sign-magnitude representation.""" + return (self.gamma_n_value * -1) if self.gamma_n_sign else self.gamma_n_value + + @property + def z_vel(self) -> int: + """Computed z_vel from sign-magnitude representation.""" + return (self.z_vel_value * -1) if self.z_vel_sign else self.z_vel_value + + @property + def z_accel(self) -> int: + """Computed z_accel from sign-magnitude representation.""" + return (self.z_accel_value * -1) if self.z_accel_sign else self.z_accel_value + + @property + def z(self) -> int: + """Computed z from sign-magnitude representation.""" + return (self.z_value * -1) if self.z_sign else self.z_value + + class String4(bs.BinaryStruct): + tau_n_sign: Annotated[bool, bs.bits(1)] + tau_n_value: Annotated[int, bs.bits(21)] + delta_tau_n_sign: Annotated[bool, bs.bits(1)] + delta_tau_n_value: Annotated[int, bs.bits(4)] + e_n: Annotated[int, bs.bits(5)] + not_used_1: Annotated[int, bs.bits(14)] + p4: Annotated[bool, bs.bits(1)] + f_t: Annotated[int, bs.bits(4)] + not_used_2: Annotated[int, bs.bits(3)] + n_t: Annotated[int, bs.bits(11)] + n: Annotated[int, bs.bits(5)] + m: Annotated[int, bs.bits(2)] + + @property + def tau_n(self) -> int: + """Computed tau_n from sign-magnitude representation.""" + return (self.tau_n_value * -1) if self.tau_n_sign else self.tau_n_value + + @property + def delta_tau_n(self) -> int: + """Computed delta_tau_n from sign-magnitude representation.""" + return (self.delta_tau_n_value * -1) if self.delta_tau_n_sign else self.delta_tau_n_value + + class String5(bs.BinaryStruct): + n_a: Annotated[int, bs.bits(11)] + tau_c: Annotated[int, bs.bits(32)] + not_used: Annotated[bool, bs.bits(1)] + n_4: Annotated[int, bs.bits(5)] + tau_gps: Annotated[int, bs.bits(22)] + l_n: Annotated[bool, bs.bits(1)] + + class StringNonImmediate(bs.BinaryStruct): + data_1: Annotated[int, bs.bits(64)] + data_2: Annotated[int, bs.bits(8)] + + idle_chip: Annotated[bool, bs.bits(1)] + string_number: Annotated[int, bs.bits(4)] + data: Annotated[ + object, + bs.switch( + 'string_number', + { + 1: String1, + 2: String2, + 3: String3, + 4: String4, + 5: String5, + }, + default=StringNonImmediate, + ), + ] + hamming_code: Annotated[int, bs.bits(8)] + pad_1: Annotated[int, bs.bits(11)] + superframe_number: Annotated[int, bs.bits(16)] + pad_2: Annotated[int, bs.bits(8)] + frame_number: Annotated[int, bs.bits(8)] diff --git a/system/ubloxd/gps.ksy b/system/ubloxd/gps.ksy deleted file mode 100644 index 893ad1b25b..0000000000 --- a/system/ubloxd/gps.ksy +++ /dev/null @@ -1,189 +0,0 @@ -# https://www.gps.gov/technical/icwg/IS-GPS-200E.pdf -meta: - id: gps - endian: be - bit-endian: be -seq: - - id: tlm - type: tlm - - id: how - type: how - - id: body - type: - switch-on: how.subframe_id - cases: - 1: subframe_1 - 2: subframe_2 - 3: subframe_3 - 4: subframe_4 -types: - tlm: - seq: - - id: preamble - contents: [0x8b] - - id: tlm - type: b14 - - id: integrity_status - type: b1 - - id: reserved - type: b1 - how: - seq: - - id: tow_count - type: b17 - - id: alert - type: b1 - - id: anti_spoof - type: b1 - - id: subframe_id - type: b3 - - id: reserved - type: b2 - subframe_1: - seq: - # Word 3 - - id: week_no - type: b10 - - id: code - type: b2 - - id: sv_accuracy - type: b4 - - id: sv_health - type: b6 - - id: iodc_msb - type: b2 - # Word 4 - - id: l2_p_data_flag - type: b1 - - id: reserved1 - type: b23 - # Word 5 - - id: reserved2 - type: b24 - # Word 6 - - id: reserved3 - type: b24 - # Word 7 - - id: reserved4 - type: b16 - - id: t_gd - type: s1 - # Word 8 - - id: iodc_lsb - type: u1 - - id: t_oc - type: u2 - # Word 9 - - id: af_2 - type: s1 - - id: af_1 - type: s2 - # Word 10 - - id: af_0_sign - type: b1 - - id: af_0_value - type: b21 - - id: reserved5 - type: b2 - instances: - af_0: - value: 'af_0_sign ? (af_0_value - (1 << 21)) : af_0_value' - subframe_2: - seq: - # Word 3 - - id: iode - type: u1 - - id: c_rs - type: s2 - # Word 4 & 5 - - id: delta_n - type: s2 - - id: m_0 - type: s4 - # Word 6 & 7 - - id: c_uc - type: s2 - - id: e - type: s4 - # Word 8 & 9 - - id: c_us - type: s2 - - id: sqrt_a - type: u4 - # Word 10 - - id: t_oe - type: u2 - - id: fit_interval_flag - type: b1 - - id: aoda - type: b5 - - id: reserved - type: b2 - subframe_3: - seq: - # Word 3 & 4 - - id: c_ic - type: s2 - - id: omega_0 - type: s4 - # Word 5 & 6 - - id: c_is - type: s2 - - id: i_0 - type: s4 - # Word 7 & 8 - - id: c_rc - type: s2 - - id: omega - type: s4 - # Word 9 - - id: omega_dot_sign - type: b1 - - id: omega_dot_value - type: b23 - # Word 10 - - id: iode - type: u1 - - id: idot_sign - type: b1 - - id: idot_value - type: b13 - - id: reserved - type: b2 - instances: - omega_dot: - value: 'omega_dot_sign ? (omega_dot_value - (1 << 23)) : omega_dot_value' - idot: - value: 'idot_sign ? (idot_value - (1 << 13)) : idot_value' - subframe_4: - seq: - # Word 3 - - id: data_id - type: b2 - - id: page_id - type: b6 - - id: body - type: - switch-on: page_id - cases: - 56: ionosphere_data - types: - ionosphere_data: - seq: - - id: a0 - type: s1 - - id: a1 - type: s1 - - id: a2 - type: s1 - - id: a3 - type: s1 - - id: b0 - type: s1 - - id: b1 - type: s1 - - id: b2 - type: s1 - - id: b3 - type: s1 - diff --git a/system/ubloxd/gps.py b/system/ubloxd/gps.py new file mode 100644 index 0000000000..1c0833bd92 --- /dev/null +++ b/system/ubloxd/gps.py @@ -0,0 +1,116 @@ +""" +Parses GPS navigation subframes per IS-GPS-200E specification. +https://www.gps.gov/technical/icwg/IS-GPS-200E.pdf +""" + +from typing import Annotated + +from openpilot.system.ubloxd import binary_struct as bs + + +class Gps(bs.BinaryStruct): + class Tlm(bs.BinaryStruct): + preamble: Annotated[bytes, bs.const(bs.bytes_field(1), b"\x8b")] + tlm: Annotated[int, bs.bits(14)] + integrity_status: Annotated[bool, bs.bits(1)] + reserved: Annotated[bool, bs.bits(1)] + + class How(bs.BinaryStruct): + tow_count: Annotated[int, bs.bits(17)] + alert: Annotated[bool, bs.bits(1)] + anti_spoof: Annotated[bool, bs.bits(1)] + subframe_id: Annotated[int, bs.bits(3)] + reserved: Annotated[int, bs.bits(2)] + + class Subframe1(bs.BinaryStruct): + week_no: Annotated[int, bs.bits(10)] + code: Annotated[int, bs.bits(2)] + sv_accuracy: Annotated[int, bs.bits(4)] + sv_health: Annotated[int, bs.bits(6)] + iodc_msb: Annotated[int, bs.bits(2)] + l2_p_data_flag: Annotated[bool, bs.bits(1)] + reserved1: Annotated[int, bs.bits(23)] + reserved2: Annotated[int, bs.bits(24)] + reserved3: Annotated[int, bs.bits(24)] + reserved4: Annotated[int, bs.bits(16)] + t_gd: Annotated[int, bs.s8] + iodc_lsb: Annotated[int, bs.u8] + t_oc: Annotated[int, bs.u16be] + af_2: Annotated[int, bs.s8] + af_1: Annotated[int, bs.s16be] + af_0_sign: Annotated[bool, bs.bits(1)] + af_0_value: Annotated[int, bs.bits(21)] + reserved5: Annotated[int, bs.bits(2)] + + @property + def af_0(self) -> int: + """Computed af_0 from sign-magnitude representation.""" + return (self.af_0_value - (1 << 21)) if self.af_0_sign else self.af_0_value + + class Subframe2(bs.BinaryStruct): + iode: Annotated[int, bs.u8] + c_rs: Annotated[int, bs.s16be] + delta_n: Annotated[int, bs.s16be] + m_0: Annotated[int, bs.s32be] + c_uc: Annotated[int, bs.s16be] + e: Annotated[int, bs.s32be] + c_us: Annotated[int, bs.s16be] + sqrt_a: Annotated[int, bs.u32be] + t_oe: Annotated[int, bs.u16be] + fit_interval_flag: Annotated[bool, bs.bits(1)] + aoda: Annotated[int, bs.bits(5)] + reserved: Annotated[int, bs.bits(2)] + + class Subframe3(bs.BinaryStruct): + c_ic: Annotated[int, bs.s16be] + omega_0: Annotated[int, bs.s32be] + c_is: Annotated[int, bs.s16be] + i_0: Annotated[int, bs.s32be] + c_rc: Annotated[int, bs.s16be] + omega: Annotated[int, bs.s32be] + omega_dot_sign: Annotated[bool, bs.bits(1)] + omega_dot_value: Annotated[int, bs.bits(23)] + iode: Annotated[int, bs.u8] + idot_sign: Annotated[bool, bs.bits(1)] + idot_value: Annotated[int, bs.bits(13)] + reserved: Annotated[int, bs.bits(2)] + + @property + def omega_dot(self) -> int: + """Computed omega_dot from sign-magnitude representation.""" + return (self.omega_dot_value - (1 << 23)) if self.omega_dot_sign else self.omega_dot_value + + @property + def idot(self) -> int: + """Computed idot from sign-magnitude representation.""" + return (self.idot_value - (1 << 13)) if self.idot_sign else self.idot_value + + class Subframe4(bs.BinaryStruct): + class IonosphereData(bs.BinaryStruct): + a0: Annotated[int, bs.s8] + a1: Annotated[int, bs.s8] + a2: Annotated[int, bs.s8] + a3: Annotated[int, bs.s8] + b0: Annotated[int, bs.s8] + b1: Annotated[int, bs.s8] + b2: Annotated[int, bs.s8] + b3: Annotated[int, bs.s8] + + data_id: Annotated[int, bs.bits(2)] + page_id: Annotated[int, bs.bits(6)] + body: Annotated[object, bs.switch('page_id', {56: IonosphereData})] + + tlm: Tlm + how: How + body: Annotated[ + object, + bs.switch( + 'how.subframe_id', + { + 1: Subframe1, + 2: Subframe2, + 3: Subframe3, + 4: Subframe4, + }, + ), + ] diff --git a/system/ubloxd/ubloxd.py b/system/ubloxd/ubloxd.py index 6882ad0955..e55cadcf78 100755 --- a/system/ubloxd/ubloxd.py +++ b/system/ubloxd/ubloxd.py @@ -8,9 +8,9 @@ from dataclasses import dataclass from cereal import log from cereal import messaging -from openpilot.system.ubloxd.generated.ubx import Ubx -from openpilot.system.ubloxd.generated.gps import Gps -from openpilot.system.ubloxd.generated.glonass import Glonass +from openpilot.system.ubloxd.ubx import Ubx +from openpilot.system.ubloxd.gps import Gps +from openpilot.system.ubloxd.glonass import Glonass SECS_IN_MIN = 60 @@ -52,7 +52,7 @@ class UbxFramer: # find preamble if len(self.buf) < 2: break - start = self.buf.find(b"\xB5\x62") + start = self.buf.find(b"\xb5\x62") if start < 0: # no preamble in buffer self.buf.clear() @@ -98,9 +98,22 @@ class UbloxMsgParser: # user range accuracy in meters glonass_URA_lookup: dict[int, float] = { - 0: 1, 1: 2, 2: 2.5, 3: 4, 4: 5, 5: 7, - 6: 10, 7: 12, 8: 14, 9: 16, 10: 32, - 11: 64, 12: 128, 13: 256, 14: 512, 15: 1024, + 0: 1, + 1: 2, + 2: 2.5, + 3: 4, + 4: 5, + 5: 7, + 6: 10, + 7: 12, + 8: 14, + 9: 16, + 10: 32, + 11: 64, + 12: 128, + 13: 256, + 14: 512, + 15: 1024, } def __init__(self) -> None: @@ -121,7 +134,7 @@ class UbloxMsgParser: body = Ubx.NavPvt.from_bytes(payload) return self._gen_nav_pvt(body) if msg_type == 0x0213: - # Manually parse RXM-SFRBX to avoid Kaitai EOF on some frames + # Manually parse RXM-SFRBX to avoid EOF on some frames if len(payload) < 8: return None gnss_id = payload[0] @@ -134,7 +147,7 @@ class UbloxMsgParser: words: list[int] = [] off = 8 for _ in range(num_words): - words.append(int.from_bytes(payload[off:off+4], 'little')) + words.append(int.from_bytes(payload[off : off + 4], 'little')) off += 4 class _SfrbxView: @@ -143,6 +156,7 @@ class UbloxMsgParser: self.sv_id = sid self.freq_id = fid self.body = body + view = _SfrbxView(gnss_id, sv_id, freq_id, words) return self._gen_rxm_sfrbx(view) if msg_type == 0x0215: @@ -515,5 +529,6 @@ def main(): service, dat = res pm.send(service, dat) + if __name__ == '__main__': main() diff --git a/system/ubloxd/ubx.ksy b/system/ubloxd/ubx.ksy deleted file mode 100644 index 02c757fe71..0000000000 --- a/system/ubloxd/ubx.ksy +++ /dev/null @@ -1,293 +0,0 @@ -meta: - id: ubx - endian: le -seq: - - id: magic - contents: [0xb5, 0x62] - - id: msg_type - type: u2be - - id: length - type: u2 - - id: body - type: - switch-on: msg_type - cases: - 0x0107: nav_pvt - 0x0213: rxm_sfrbx - 0x0215: rxm_rawx - 0x0a09: mon_hw - 0x0a0b: mon_hw2 - 0x0135: nav_sat -instances: - checksum: - pos: length + 6 - type: u2 - -types: - mon_hw: - seq: - - id: pin_sel - type: u4 - - id: pin_bank - type: u4 - - id: pin_dir - type: u4 - - id: pin_val - type: u4 - - id: noise_per_ms - type: u2 - - id: agc_cnt - type: u2 - - id: a_status - type: u1 - enum: antenna_status - - id: a_power - type: u1 - enum: antenna_power - - id: flags - type: u1 - - id: reserved1 - size: 1 - - id: used_mask - type: u4 - - id: vp - size: 17 - - id: jam_ind - type: u1 - - id: reserved2 - size: 2 - - id: pin_irq - type: u4 - - id: pull_h - type: u4 - - id: pull_l - type: u4 - enums: - antenna_status: - 0: init - 1: dontknow - 2: ok - 3: short - 4: open - antenna_power: - 0: off - 1: on - 2: dontknow - - mon_hw2: - seq: - - id: ofs_i - type: s1 - - id: mag_i - type: u1 - - id: ofs_q - type: s1 - - id: mag_q - type: u1 - - id: cfg_source - type: u1 - enum: config_source - - id: reserved1 - size: 3 - - id: low_lev_cfg - type: u4 - - id: reserved2 - size: 8 - - id: post_status - type: u4 - - id: reserved3 - size: 4 - - enums: - config_source: - 113: rom - 111: otp - 112: config_pins - 102: flash - - rxm_sfrbx: - seq: - - id: gnss_id - type: u1 - enum: gnss_type - - id: sv_id - type: u1 - - id: reserved1 - size: 1 - - id: freq_id - type: u1 - - id: num_words - type: u1 - - id: reserved2 - size: 1 - - id: version - type: u1 - - id: reserved3 - size: 1 - - id: body - type: u4 - repeat: expr - repeat-expr: num_words - - rxm_rawx: - seq: - - id: rcv_tow - type: f8 - - id: week - type: u2 - - id: leap_s - type: s1 - - id: num_meas - type: u1 - - id: rec_stat - type: u1 - - id: reserved1 - size: 3 - - id: meas - type: measurement - size: 32 - repeat: expr - repeat-expr: num_meas - types: - measurement: - seq: - - id: pr_mes - type: f8 - - id: cp_mes - type: f8 - - id: do_mes - type: f4 - - id: gnss_id - type: u1 - enum: gnss_type - - id: sv_id - type: u1 - - id: reserved2 - size: 1 - - id: freq_id - type: u1 - - id: lock_time - type: u2 - - id: cno - type: u1 - - id: pr_stdev - type: u1 - - id: cp_stdev - type: u1 - - id: do_stdev - type: u1 - - id: trk_stat - type: u1 - - id: reserved3 - size: 1 - nav_sat: - seq: - - id: itow - type: u4 - - id: version - type: u1 - - id: num_svs - type: u1 - - id: reserved - size: 2 - - id: svs - type: nav - size: 12 - repeat: expr - repeat-expr: num_svs - types: - nav: - seq: - - id: gnss_id - type: u1 - enum: gnss_type - - id: sv_id - type: u1 - - id: cno - type: u1 - - id: elev - type: s1 - - id: azim - type: s2 - - id: pr_res - type: s2 - - id: flags - type: u4 - - nav_pvt: - seq: - - id: i_tow - type: u4 - - id: year - type: u2 - - id: month - type: u1 - - id: day - type: u1 - - id: hour - type: u1 - - id: min - type: u1 - - id: sec - type: u1 - - id: valid - type: u1 - - id: t_acc - type: u4 - - id: nano - type: s4 - - id: fix_type - type: u1 - - id: flags - type: u1 - - id: flags2 - type: u1 - - id: num_sv - type: u1 - - id: lon - type: s4 - - id: lat - type: s4 - - id: height - type: s4 - - id: h_msl - type: s4 - - id: h_acc - type: u4 - - id: v_acc - type: u4 - - id: vel_n - type: s4 - - id: vel_e - type: s4 - - id: vel_d - type: s4 - - id: g_speed - type: s4 - - id: head_mot - type: s4 - - id: s_acc - type: s4 - - id: head_acc - type: u4 - - id: p_dop - type: u2 - - id: flags3 - type: u1 - - id: reserved1 - size: 5 - - id: head_veh - type: s4 - - id: mag_dec - type: s2 - - id: mag_acc - type: u2 -enums: - gnss_type: - 0: gps - 1: sbas - 2: galileo - 3: beidou - 4: imes - 5: qzss - 6: glonass diff --git a/system/ubloxd/ubx.py b/system/ubloxd/ubx.py new file mode 100644 index 0000000000..857498ebf1 --- /dev/null +++ b/system/ubloxd/ubx.py @@ -0,0 +1,180 @@ +""" +UBX protocol parser +""" + +from enum import IntEnum +from typing import Annotated + +from openpilot.system.ubloxd import binary_struct as bs + + +class GnssType(IntEnum): + gps = 0 + sbas = 1 + galileo = 2 + beidou = 3 + imes = 4 + qzss = 5 + glonass = 6 + + +class Ubx(bs.BinaryStruct): + GnssType = GnssType + + class RxmRawx(bs.BinaryStruct): + class Measurement(bs.BinaryStruct): + pr_mes: Annotated[float, bs.f64] + cp_mes: Annotated[float, bs.f64] + do_mes: Annotated[float, bs.f32] + gnss_id: Annotated[GnssType | int, bs.enum(bs.u8, GnssType)] + sv_id: Annotated[int, bs.u8] + reserved2: Annotated[bytes, bs.bytes_field(1)] + freq_id: Annotated[int, bs.u8] + lock_time: Annotated[int, bs.u16] + cno: Annotated[int, bs.u8] + pr_stdev: Annotated[int, bs.u8] + cp_stdev: Annotated[int, bs.u8] + do_stdev: Annotated[int, bs.u8] + trk_stat: Annotated[int, bs.u8] + reserved3: Annotated[bytes, bs.bytes_field(1)] + + rcv_tow: Annotated[float, bs.f64] + week: Annotated[int, bs.u16] + leap_s: Annotated[int, bs.s8] + num_meas: Annotated[int, bs.u8] + rec_stat: Annotated[int, bs.u8] + reserved1: Annotated[bytes, bs.bytes_field(3)] + meas: Annotated[list[Measurement], bs.array(Measurement, count_field='num_meas')] + + class RxmSfrbx(bs.BinaryStruct): + gnss_id: Annotated[GnssType | int, bs.enum(bs.u8, GnssType)] + sv_id: Annotated[int, bs.u8] + reserved1: Annotated[bytes, bs.bytes_field(1)] + freq_id: Annotated[int, bs.u8] + num_words: Annotated[int, bs.u8] + reserved2: Annotated[bytes, bs.bytes_field(1)] + version: Annotated[int, bs.u8] + reserved3: Annotated[bytes, bs.bytes_field(1)] + body: Annotated[list[int], bs.array(bs.u32, count_field='num_words')] + + class NavSat(bs.BinaryStruct): + class Nav(bs.BinaryStruct): + gnss_id: Annotated[GnssType | int, bs.enum(bs.u8, GnssType)] + sv_id: Annotated[int, bs.u8] + cno: Annotated[int, bs.u8] + elev: Annotated[int, bs.s8] + azim: Annotated[int, bs.s16] + pr_res: Annotated[int, bs.s16] + flags: Annotated[int, bs.u32] + + itow: Annotated[int, bs.u32] + version: Annotated[int, bs.u8] + num_svs: Annotated[int, bs.u8] + reserved: Annotated[bytes, bs.bytes_field(2)] + svs: Annotated[list[Nav], bs.array(Nav, count_field='num_svs')] + + class NavPvt(bs.BinaryStruct): + i_tow: Annotated[int, bs.u32] + year: Annotated[int, bs.u16] + month: Annotated[int, bs.u8] + day: Annotated[int, bs.u8] + hour: Annotated[int, bs.u8] + min: Annotated[int, bs.u8] + sec: Annotated[int, bs.u8] + valid: Annotated[int, bs.u8] + t_acc: Annotated[int, bs.u32] + nano: Annotated[int, bs.s32] + fix_type: Annotated[int, bs.u8] + flags: Annotated[int, bs.u8] + flags2: Annotated[int, bs.u8] + num_sv: Annotated[int, bs.u8] + lon: Annotated[int, bs.s32] + lat: Annotated[int, bs.s32] + height: Annotated[int, bs.s32] + h_msl: Annotated[int, bs.s32] + h_acc: Annotated[int, bs.u32] + v_acc: Annotated[int, bs.u32] + vel_n: Annotated[int, bs.s32] + vel_e: Annotated[int, bs.s32] + vel_d: Annotated[int, bs.s32] + g_speed: Annotated[int, bs.s32] + head_mot: Annotated[int, bs.s32] + s_acc: Annotated[int, bs.s32] + head_acc: Annotated[int, bs.u32] + p_dop: Annotated[int, bs.u16] + flags3: Annotated[int, bs.u8] + reserved1: Annotated[bytes, bs.bytes_field(5)] + head_veh: Annotated[int, bs.s32] + mag_dec: Annotated[int, bs.s16] + mag_acc: Annotated[int, bs.u16] + + class MonHw2(bs.BinaryStruct): + class ConfigSource(IntEnum): + flash = 102 + otp = 111 + config_pins = 112 + rom = 113 + + ofs_i: Annotated[int, bs.s8] + mag_i: Annotated[int, bs.u8] + ofs_q: Annotated[int, bs.s8] + mag_q: Annotated[int, bs.u8] + cfg_source: Annotated[ConfigSource | int, bs.enum(bs.u8, ConfigSource)] + reserved1: Annotated[bytes, bs.bytes_field(3)] + low_lev_cfg: Annotated[int, bs.u32] + reserved2: Annotated[bytes, bs.bytes_field(8)] + post_status: Annotated[int, bs.u32] + reserved3: Annotated[bytes, bs.bytes_field(4)] + + class MonHw(bs.BinaryStruct): + class AntennaStatus(IntEnum): + init = 0 + dontknow = 1 + ok = 2 + short = 3 + open = 4 + + class AntennaPower(IntEnum): + false = 0 + true = 1 + dontknow = 2 + + pin_sel: Annotated[int, bs.u32] + pin_bank: Annotated[int, bs.u32] + pin_dir: Annotated[int, bs.u32] + pin_val: Annotated[int, bs.u32] + noise_per_ms: Annotated[int, bs.u16] + agc_cnt: Annotated[int, bs.u16] + a_status: Annotated[AntennaStatus | int, bs.enum(bs.u8, AntennaStatus)] + a_power: Annotated[AntennaPower | int, bs.enum(bs.u8, AntennaPower)] + flags: Annotated[int, bs.u8] + reserved1: Annotated[bytes, bs.bytes_field(1)] + used_mask: Annotated[int, bs.u32] + vp: Annotated[bytes, bs.bytes_field(17)] + jam_ind: Annotated[int, bs.u8] + reserved2: Annotated[bytes, bs.bytes_field(2)] + pin_irq: Annotated[int, bs.u32] + pull_h: Annotated[int, bs.u32] + pull_l: Annotated[int, bs.u32] + + magic: Annotated[bytes, bs.const(bs.bytes_field(2), b"\xb5\x62")] + msg_type: Annotated[int, bs.u16be] + length: Annotated[int, bs.u16] + body: Annotated[ + object, + bs.substream( + 'length', + bs.switch( + 'msg_type', + { + 0x0107: NavPvt, + 0x0213: RxmSfrbx, + 0x0215: RxmRawx, + 0x0A09: MonHw, + 0x0A0B: MonHw2, + 0x0135: NavSat, + }, + ), + ), + ] + checksum: Annotated[int, bs.u16] diff --git a/uv.lock b/uv.lock index 2c5f32ec7b..572305f08c 100644 --- a/uv.lock +++ b/uv.lock @@ -768,15 +768,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/94/9e/820c4b086ad01ba7d77369fb8b11470a01fac9b4977f02e18659cf378b6b/json_rpc-1.15.0-py2.py3-none-any.whl", hash = "sha256:4a4668bbbe7116feb4abbd0f54e64a4adcf4b8f648f19ffa0848ad0f6606a9bf", size = 39450, upload-time = "2023-06-11T09:45:47.136Z" }, ] -[[package]] -name = "kaitaistruct" -version = "0.11" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/27/b8/ca7319556912f68832daa4b81425314857ec08dfccd8dbc8c0f65c992108/kaitaistruct-0.11.tar.gz", hash = "sha256:053ee764288e78b8e53acf748e9733268acbd579b8d82a427b1805453625d74b", size = 11519, upload-time = "2025-09-08T15:46:25.037Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/4a/4a/cf14bf3b1f5ffb13c69cf5f0ea78031247790558ee88984a8bdd22fae60d/kaitaistruct-0.11-py2.py3-none-any.whl", hash = "sha256:5c6ce79177b4e193a577ecd359e26516d1d6d000a0bffd6e1010f2a46a62a561", size = 11372, upload-time = "2025-09-08T15:46:23.635Z" }, -] - [[package]] name = "kiwisolver" version = "1.4.9" @@ -1296,7 +1287,6 @@ dependencies = [ { name = "inputs" }, { name = "jeepney" }, { name = "json-rpc" }, - { name = "kaitaistruct" }, { name = "libusb1" }, { name = "mapbox-earcut" }, { name = "numpy" }, @@ -1384,7 +1374,6 @@ requires-dist = [ { name = "jeepney" }, { name = "jinja2", marker = "extra == 'docs'" }, { name = "json-rpc" }, - { name = "kaitaistruct" }, { name = "libusb1" }, { name = "mapbox-earcut" }, { name = "matplotlib", marker = "extra == 'dev'" }, From 831f2396d9a60eb8c73b7d0af4c4961353c73e51 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 2 Feb 2026 08:08:09 -0800 Subject: [PATCH 39/46] bump opendbc --- opendbc_repo | 2 +- pyproject.toml | 1 - uv.lock | 11 ----------- 3 files changed, 1 insertion(+), 13 deletions(-) diff --git a/opendbc_repo b/opendbc_repo index e76c2cf5bb..7c78ee87b7 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit e76c2cf5bb0042bc5822efa78fff0362feed7b54 +Subproject commit 7c78ee87b7b54bb2179d86d5e28c1f65bbf96669 diff --git a/pyproject.toml b/pyproject.toml index 1be5c395f1..c80d23b8eb 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -74,7 +74,6 @@ dependencies = [ [project.optional-dependencies] docs = [ "Jinja2", - "natsort", "mkdocs", ] diff --git a/uv.lock b/uv.lock index 572305f08c..054a67cc9a 100644 --- a/uv.lock +++ b/uv.lock @@ -1183,15 +1183,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/81/08/7036c080d7117f28a4af526d794aab6a84463126db031b007717c1a6676e/multidict-6.7.1-py3-none-any.whl", hash = "sha256:55d97cc6dae627efa6a6e548885712d4864b81110ac76fa4e534c03819fa4a56", size = 12319, upload-time = "2026-01-26T02:46:44.004Z" }, ] -[[package]] -name = "natsort" -version = "8.4.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e2/a9/a0c57aee75f77794adaf35322f8b6404cbd0f89ad45c87197a937764b7d0/natsort-8.4.0.tar.gz", hash = "sha256:45312c4a0e5507593da193dedd04abb1469253b601ecaf63445ad80f0a1ea581", size = 76575, upload-time = "2023-06-20T04:17:19.925Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/ef/82/7a9d0550484a62c6da82858ee9419f3dd1ccc9aa1c26a1e43da3ecd20b0d/natsort-8.4.0-py3-none-any.whl", hash = "sha256:4732914fb471f56b5cce04d7bae6f164a592c7712e1c85f9ef585e197299521c", size = 38268, upload-time = "2023-06-20T04:17:17.522Z" }, -] - [[package]] name = "numpy" version = "2.4.1" @@ -1331,7 +1322,6 @@ dev = [ docs = [ { name = "jinja2" }, { name = "mkdocs" }, - { name = "natsort" }, ] testing = [ { name = "codespell" }, @@ -1379,7 +1369,6 @@ requires-dist = [ { name = "matplotlib", marker = "extra == 'dev'" }, { name = "metadrive-simulator", marker = "platform_machine != 'aarch64' and extra == 'tools'", url = "https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal-0.4.2.4/metadrive_simulator-0.4.2.4-py3-none-any.whl" }, { name = "mkdocs", marker = "extra == 'docs'" }, - { name = "natsort", marker = "extra == 'docs'" }, { name = "numpy", specifier = ">=2.0" }, { name = "onnx", specifier = ">=1.14.0" }, { name = "opencv-python-headless", marker = "extra == 'dev'" }, From fd50941cff09b6710358aa9651c7dfeb94ffe79c Mon Sep 17 00:00:00 2001 From: Trey Moen <50057480+greatgitsby@users.noreply.github.com> Date: Mon, 2 Feb 2026 09:13:49 -0700 Subject: [PATCH 40/46] chore: bump minimum Python version to 3.12.3 (#37052) --- pyproject.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pyproject.toml b/pyproject.toml index c80d23b8eb..2400364c70 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,6 +1,6 @@ [project] name = "openpilot" -requires-python = ">= 3.11, < 3.13" +requires-python = ">= 3.12.3, < 3.13" license = {text = "MIT License"} version = "0.1.0" description = "an open source driver assistance system" From a668bc9edad0223a79c797b8943fe8daaa95ade1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 2 Feb 2026 16:58:45 -0800 Subject: [PATCH 41/46] comma four setup improvements (#37066) * always check, no flickering from has inter -> waiting -> has inter from the reset * 1s interval. i see read timeouts at 0.5s sometimes * clean up * cursor * Revert "cursor" This reverts commit 13ec6312aa7f71b58771f8789456e97c4481856a. * clean up --- system/ui/mici_setup.py | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/system/ui/mici_setup.py b/system/ui/mici_setup.py index 2c6090b4ac..fac26f06ea 100755 --- a/system/ui/mici_setup.py +++ b/system/ui/mici_setup.py @@ -49,7 +49,7 @@ exec ./launch_openpilot.sh class NetworkConnectivityMonitor: - def __init__(self, should_check: Callable[[], bool] | None = None, check_interval: float = 0.5): + def __init__(self, should_check: Callable[[], bool] | None = None, check_interval: float = 1.0): self.network_connected = threading.Event() self.wifi_connected = threading.Event() self._should_check = should_check or (lambda: True) @@ -78,7 +78,7 @@ class NetworkConnectivityMonitor: if self._should_check(): try: request = urllib.request.Request(OPENPILOT_URL, method="HEAD") - urllib.request.urlopen(request, timeout=0.5) + urllib.request.urlopen(request, timeout=1.0) self.network_connected.set() if HARDWARE.get_network_type() == NetworkType.wifi: self.wifi_connected.set() @@ -528,9 +528,8 @@ class Setup(Widget): self.download_thread = None self._wifi_manager = WifiManager() self._wifi_manager.set_active(True) - self._network_monitor = NetworkConnectivityMonitor( - lambda: self.state in (SetupState.NETWORK_SETUP, SetupState.NETWORK_SETUP_CUSTOM_SOFTWARE) - ) + self._network_monitor = NetworkConnectivityMonitor() + self._network_monitor.start() self._prev_has_internet = False gui_app.set_modal_overlay_tick(self._modal_overlay_tick) @@ -569,10 +568,8 @@ class Setup(Widget): if self.state in (SetupState.NETWORK_SETUP, SetupState.NETWORK_SETUP_CUSTOM_SOFTWARE): self._network_setup_page.show_event() self._network_monitor.reset() - self._network_monitor.start() else: self._network_setup_page.hide_event() - self._network_monitor.stop() def _render(self, rect: rl.Rectangle): if self.state == SetupState.GETTING_STARTED: @@ -618,7 +615,6 @@ class Setup(Widget): self._set_state(SetupState.SOFTWARE_SELECTION) def _network_setup_continue_button_callback(self): - self._network_monitor.stop() if self.state == SetupState.NETWORK_SETUP: self.download(OPENPILOT_URL) elif self.state == SetupState.NETWORK_SETUP_CUSTOM_SOFTWARE: @@ -628,10 +624,10 @@ class Setup(Widget): self._network_monitor.stop() def render_network_setup(self, rect: rl.Rectangle): - self._network_setup_page.render(rect) has_internet = self._network_monitor.network_connected.is_set() self._prev_has_internet = has_internet self._network_setup_page.set_has_internet(has_internet) + self._network_setup_page.render(rect) def render_downloading(self, rect: rl.Rectangle): self._downloading_page.set_progress(self.download_progress) From 85b9f8962e8330283f3ec59a025ee97328dc29ae Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 2 Feb 2026 22:32:52 -0800 Subject: [PATCH 42/46] Clean up four keyboard text rects (#37068) * start clean up * rm * not really needed * more * clean up --- selfdrive/ui/mici/widgets/dialog.py | 43 ++++++++++++----------------- 1 file changed, 17 insertions(+), 26 deletions(-) diff --git a/selfdrive/ui/mici/widgets/dialog.py b/selfdrive/ui/mici/widgets/dialog.py index 67123d33a7..b23abe6080 100644 --- a/selfdrive/ui/mici/widgets/dialog.py +++ b/selfdrive/ui/mici/widgets/dialog.py @@ -132,6 +132,7 @@ class BigConfirmationDialogV2(BigDialogBase): class BigInputDialog(BigDialogBase): BACK_TOUCH_AREA_PERCENTAGE = 0.2 BACKSPACE_RATE = 25 # hz + TEXT_INPUT_SIZE = 35 def __init__(self, hint: str, @@ -179,53 +180,44 @@ class BigInputDialog(BigDialogBase): self._backspace_held_time = None def _render(self, _): - text_input_size = 35 - # draw current text so far below everything. text floats left but always stays in view text = self._keyboard.text() candidate_char = self._keyboard.get_candidate_character() - text_size = measure_text_cached(gui_app.font(FontWeight.ROMAN), text + candidate_char or self._hint_label.text, text_input_size) - text_x = PADDING * 2 + self._enter_img.width + text_size = measure_text_cached(gui_app.font(FontWeight.ROMAN), text + candidate_char or self._hint_label.text, self.TEXT_INPUT_SIZE) - # text needs to move left if we're at the end where right button is - text_rect = rl.Rectangle(text_x, - int(self._rect.y + PADDING), - # clip width to right button when in view - int(self._rect.width - text_x - PADDING * 2 - self._enter_img.width + 5), # TODO: why 5? - int(text_size.y)) - - # draw rounded background for text input bg_block_margin = 5 - text_field_rect = rl.Rectangle(text_rect.x - bg_block_margin, text_rect.y - bg_block_margin, - text_rect.width + bg_block_margin * 2, text_input_size + bg_block_margin * 2) + text_x = PADDING * 2 + self._enter_img.width + bg_block_margin + text_field_rect = rl.Rectangle(text_x, int(self._rect.y + PADDING) - bg_block_margin, + int(self._rect.width - text_x - PADDING * 2 - self._enter_img.width) - bg_block_margin * 2, + int(text_size.y)) # draw text input # push text left with a gradient on left side if too long - if text_size.x > text_rect.width: - text_x -= text_size.x - text_rect.width + if text_size.x > text_field_rect.width: + text_x -= text_size.x - text_field_rect.width - rl.begin_scissor_mode(int(text_rect.x), int(text_rect.y), int(text_rect.width), int(text_rect.height)) - rl.draw_text_ex(gui_app.font(FontWeight.ROMAN), text, rl.Vector2(text_x, text_rect.y), text_input_size, 0, rl.WHITE) + rl.begin_scissor_mode(int(text_field_rect.x), int(text_field_rect.y), int(text_field_rect.width), int(text_field_rect.height)) + rl.draw_text_ex(gui_app.font(FontWeight.ROMAN), text, rl.Vector2(text_x, text_field_rect.y), self.TEXT_INPUT_SIZE, 0, rl.WHITE) # draw grayed out character user is hovering over if candidate_char: - candidate_char_size = measure_text_cached(gui_app.font(FontWeight.ROMAN), candidate_char, text_input_size) + candidate_char_size = measure_text_cached(gui_app.font(FontWeight.ROMAN), candidate_char, self.TEXT_INPUT_SIZE) rl.draw_text_ex(gui_app.font(FontWeight.ROMAN), candidate_char, - rl.Vector2(min(text_x + text_size.x, text_rect.x + text_rect.width) - candidate_char_size.x, text_rect.y), - text_input_size, 0, rl.Color(255, 255, 255, 128)) + rl.Vector2(min(text_x + text_size.x, text_field_rect.x + text_field_rect.width) - candidate_char_size.x, text_field_rect.y), + self.TEXT_INPUT_SIZE, 0, rl.Color(255, 255, 255, 128)) rl.end_scissor_mode() # draw gradient on left side to indicate more text - if text_size.x > text_rect.width: - rl.draw_rectangle_gradient_h(int(text_rect.x), int(text_rect.y), 80, int(text_rect.height), + if text_size.x > text_field_rect.width: + rl.draw_rectangle_gradient_h(int(text_field_rect.x), int(text_field_rect.y), 80, int(text_field_rect.height), rl.BLACK, rl.BLANK) # draw cursor if text: blink_alpha = (math.sin(rl.get_time() * 6) + 1) / 2 - cursor_x = min(text_x + text_size.x + 3, text_rect.x + text_rect.width) - rl.draw_rectangle_rounded(rl.Rectangle(int(cursor_x), int(text_rect.y), 4, int(text_size.y)), + cursor_x = min(text_x + text_size.x + 3, text_field_rect.x + text_field_rect.width) + rl.draw_rectangle_rounded(rl.Rectangle(int(cursor_x), int(text_field_rect.y), 4, int(text_size.y)), 1, 4, rl.Color(255, 255, 255, int(255 * blink_alpha))) # draw backspace icon with nice fade @@ -255,7 +247,6 @@ class BigInputDialog(BigDialogBase): # draw debugging rect bounds if DEBUG: rl.draw_rectangle_lines_ex(text_field_rect, 1, rl.Color(100, 100, 100, 255)) - rl.draw_rectangle_lines_ex(text_rect, 1, rl.Color(0, 255, 0, 255)) rl.draw_rectangle_lines_ex(self._top_right_button_rect, 1, rl.Color(0, 255, 0, 255)) rl.draw_rectangle_lines_ex(self._top_left_button_rect, 1, rl.Color(0, 255, 0, 255)) From aac90dd11b449996307b863e1ef0564cfdc771fe Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Tue, 3 Feb 2026 13:59:45 -0800 Subject: [PATCH 43/46] Bump tg (#37069) bump tg --- tinygrad_repo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tinygrad_repo b/tinygrad_repo index 774a454bb5..2f55005ad9 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit 774a454bb5e6d0fe3756a8add9302c0a3d592bd9 +Subproject commit 2f55005ad93c777cca69b20dddc28c7f02f0eb01 From 54cf8d6a5ecb59714c4ac8991e53fa85269b31a1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 3 Feb 2026 15:55:05 -0800 Subject: [PATCH 44/46] four keyboard: fix keys lagging behind parent widget (#37073) * fix keys lagging behind * use parent rect * use parent rect * cmt --- system/ui/widgets/mici_keyboard.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/system/ui/widgets/mici_keyboard.py b/system/ui/widgets/mici_keyboard.py index 7fc3847809..6d2e08e053 100644 --- a/system/ui/widgets/mici_keyboard.py +++ b/system/ui/widgets/mici_keyboard.py @@ -53,20 +53,23 @@ class Key(Widget): self.original_position = rl.Vector2(0, 0) def set_position(self, x: float, y: float, smooth: bool = True): - # TODO: swipe up from NavWidget has the keys lag behind other elements a bit + # Smooth keys within parent rect + base_y = self._parent_rect.y if self._parent_rect else 0.0 + local_y = y - base_y + if not self._position_initialized: self._x_filter.x = x - self._y_filter.x = y + self._y_filter.x = local_y # keep track of original position so dragging around feels consistent. also move touch area down a bit self.original_position = rl.Vector2(x, y + KEY_TOUCH_AREA_OFFSET) self._position_initialized = True if not smooth: self._x_filter.x = x - self._y_filter.x = y + self._y_filter.x = local_y self._rect.x = self._x_filter.update(x) - self._rect.y = self._y_filter.update(y) + self._rect.y = base_y + self._y_filter.update(local_y) def set_alpha(self, alpha: float): self._alpha_filter.update(alpha) @@ -367,6 +370,7 @@ class MiciKeyboard(Widget): key.set_font_size(font_size) # TODO: I like the push amount, so we should clip the pos inside the keyboard rect + key.set_parent_rect(self._rect) key.set_position(key_x, key_y) def _render(self, _): From ee7601ae9db36708281fa42c35b5c9e31b74a888 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Harald=20Sch=C3=A4fer?= Date: Tue, 3 Feb 2026 15:55:13 -0800 Subject: [PATCH 45/46] long planner: Min(stopping) is also important (#37074) Min(stopping) is also important --- selfdrive/controls/lib/longitudinal_planner.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index ad84ecf24f..c5c03eba18 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -152,10 +152,11 @@ class LongitudinalPlanner: output_a_target_e2e = sm['modelV2'].action.desiredAcceleration output_should_stop_e2e = sm['modelV2'].action.shouldStop - if (output_a_target_e2e < output_a_target_mpc) and sm['selfdriveState'].experimentalMode: - output_a_target = output_a_target_e2e - self.output_should_stop = output_should_stop_e2e - self.mpc.source = SOURCES[3] + if sm['selfdriveState'].experimentalMode: + output_a_target = min(output_a_target_e2e, output_a_target_mpc) + self.output_should_stop = output_should_stop_e2e or output_should_stop_mpc + if output_a_target < output_a_target_mpc: + self.mpc.source = SOURCES[3] else: output_a_target = output_a_target_mpc self.output_should_stop = output_should_stop_mpc From 5b6436a90cf6902b8aaa71c2b6f3d7164d8ae391 Mon Sep 17 00:00:00 2001 From: YassineYousfi Date: Tue, 3 Feb 2026 19:14:02 -0800 Subject: [PATCH 46/46] CD210 model (#37050) a27b3122-733e-4a65-938b-acfebebbe5e8/100 --- selfdrive/modeld/models/driving_policy.onnx | 4 ++-- selfdrive/modeld/models/driving_vision.onnx | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/modeld/models/driving_policy.onnx b/selfdrive/modeld/models/driving_policy.onnx index 92c81954d2..611ae9fe85 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:1edea5bb56f876db4cec97c150799513f6a59373f3ad152d55e4dcaab1b809e3 -size 13926324 +oid sha256:78477124cbf3ffe30fa951ebada8410b43c4242c6054584d656f1d329b067e15 +size 14060847 diff --git a/selfdrive/modeld/models/driving_vision.onnx b/selfdrive/modeld/models/driving_vision.onnx index 76c96670a9..6c9fc4c84d 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:1dc66bc06f250b577653ccbeaa2c6521b3d46749f601d0a1a366419e929ca438 -size 46271942 +oid sha256:ee29ee5bce84d1ce23e9ff381280de9b4e4d96d2934cd751740354884e112c66 +size 46877473