gwm-driving
Yassine Yousfi 5 days ago
commit 1cd9f9d6f7
  1. 2
      .github/workflows/release.yaml
  2. 2
      .github/workflows/selfdrive_tests.yaml
  3. 32
      Jenkinsfile
  4. 6
      README.md
  5. 4
      RELEASES.md
  6. 2
      cereal/log.capnp
  7. 2
      cereal/messaging/socketmaster.cc
  8. 4
      cereal/services.py
  9. 1
      common/params_keys.h
  10. 2
      docs/CONTRIBUTING.md
  11. 18
      docs/SAFETY.md
  12. 8
      docs/how-to/connect-to-comma.md
  13. 2
      docs/how-to/replay-a-drive.md
  14. 2
      docs/how-to/turn-the-speed-blue.md
  15. 2
      launch_env.sh
  16. 2
      mkdocs.yml
  17. 2
      opendbc_repo
  18. 2
      panda
  19. 3
      pyproject.toml
  20. 23
      release/build_stripped.sh
  21. 45
      selfdrive/car/tests/test_car_interfaces.py
  22. 6
      selfdrive/controls/lib/latcontrol_torque.py
  23. 70
      selfdrive/controls/tests/test_torqued_lat_accel_offset.py
  24. 9
      selfdrive/modeld/constants.py
  25. 2
      selfdrive/modeld/fill_model_msg.py
  26. 96
      selfdrive/modeld/modeld.py
  27. 1
      selfdrive/pandad/pandad.cc
  28. 5
      selfdrive/pandad/pandad.py
  29. BIN
      selfdrive/pandad/tests/bootstub.panda.bin
  30. 6
      selfdrive/pandad/tests/test_pandad.py
  31. 3
      selfdrive/pandad/tests/test_pandad_spi.py
  32. 4
      selfdrive/selfdrived/alerts_offroad.json
  33. 10
      selfdrive/selfdrived/selfdrived.py
  34. 2
      selfdrive/test/process_replay/process_replay.py
  35. 2
      selfdrive/test/process_replay/ref_commit
  36. 17
      selfdrive/test/test_onroad.py
  37. 12
      selfdrive/ui/layouts/main.py
  38. 17
      selfdrive/ui/layouts/network.py
  39. 6
      selfdrive/ui/layouts/settings/firehose.py
  40. 22
      selfdrive/ui/layouts/settings/settings.py
  41. 14
      selfdrive/ui/lib/api_helpers.py
  42. 5
      selfdrive/ui/lib/prime_state.py
  43. 2
      selfdrive/ui/tests/test_ui/run.py
  44. 3
      selfdrive/ui/ui.cc
  45. 5
      selfdrive/ui/ui_state.py
  46. 2
      system/camerad/SConscript
  47. 2
      system/camerad/cameras/hw.h
  48. 3
      system/camerad/cameras/spectra.cc
  49. 136
      system/camerad/sensors/ar0231.cc
  50. 34
      system/camerad/sensors/ar0231_cl.h
  51. 121
      system/camerad/sensors/ar0231_registers.h
  52. 58
      system/camerad/sensors/os04c10_cl.h
  53. 47
      system/camerad/sensors/ox03c10_cl.h
  54. 12
      system/camerad/sensors/sensor.h
  55. 7
      system/hardware/base.py
  56. 27
      system/hardware/esim.py
  57. 7
      system/hardware/hardwared.py
  58. 28
      system/hardware/tici/agnos.json
  59. 52
      system/hardware/tici/all-partitions.json
  60. 12
      system/hardware/tici/amplifier.py
  61. 29
      system/hardware/tici/esim.py
  62. 25
      system/hardware/tici/hardware.py
  63. 5
      system/hardware/tici/pins.py
  64. 4
      system/hardware/tici/tests/test_power_draw.py
  65. 13
      system/loggerd/tests/vidc_debug.sh
  66. 44
      system/ui/lib/networkmanager.py
  67. 1019
      system/ui/lib/wifi_manager.py
  68. 5
      system/ui/reset.py
  69. 5
      system/ui/setup.py
  70. 5
      system/ui/updater.py
  71. 7
      system/ui/widgets/__init__.py
  72. 4
      system/ui/widgets/list_view.py
  73. 223
      system/ui/widgets/network.py
  74. 2
      system/updated/updated.py
  75. 2
      tinygrad_repo
  76. 4
      tools/auto_source.py
  77. 1
      tools/op.sh
  78. 347
      uv.lock

@ -39,4 +39,4 @@ jobs:
git config --global --add safe.directory '*' git config --global --add safe.directory '*'
git lfs pull git lfs pull
- name: Push master-ci - name: Push master-ci
run: BRANCH=__nightly release/build_devel.sh run: BRANCH=__nightly release/build_stripped.sh

@ -52,7 +52,7 @@ jobs:
command: git lfs pull command: git lfs pull
- name: Build devel - name: Build devel
timeout-minutes: 1 timeout-minutes: 1
run: TARGET_DIR=$STRIPPED_DIR release/build_devel.sh run: TARGET_DIR=$STRIPPED_DIR release/build_stripped.sh
- uses: ./.github/workflows/setup-with-retry - uses: ./.github/workflows/setup-with-retry
- name: Build openpilot and run checks - name: Build openpilot and run checks
timeout-minutes: ${{ ((steps.restore-scons-cache.outputs.cache-hit == 'true') && 10 || 30) }} # allow more time when we missed the scons cache timeout-minutes: ${{ ((steps.restore-scons-cache.outputs.cache-hit == 'true') && 10 || 30) }} # allow more time when we missed the scons cache

32
Jenkinsfile vendored

@ -178,7 +178,7 @@ node {
try { try {
if (env.BRANCH_NAME == 'devel-staging') { if (env.BRANCH_NAME == 'devel-staging') {
deviceStage("build release3-staging", "tici-needs-can", [], [ deviceStage("build release3-staging", "tizi-needs-can", [], [
step("build release3-staging", "RELEASE_BRANCH=release3-staging $SOURCE_DIR/release/build_release.sh"), step("build release3-staging", "RELEASE_BRANCH=release3-staging $SOURCE_DIR/release/build_release.sh"),
]) ])
} }
@ -186,12 +186,12 @@ node {
if (env.BRANCH_NAME == '__nightly') { if (env.BRANCH_NAME == '__nightly') {
parallel ( parallel (
'nightly': { 'nightly': {
deviceStage("build nightly", "tici-needs-can", [], [ deviceStage("build nightly", "tizi-needs-can", [], [
step("build nightly", "RELEASE_BRANCH=nightly $SOURCE_DIR/release/build_release.sh"), step("build nightly", "RELEASE_BRANCH=nightly $SOURCE_DIR/release/build_release.sh"),
]) ])
}, },
'nightly-dev': { 'nightly-dev': {
deviceStage("build nightly-dev", "tici-needs-can", [], [ deviceStage("build nightly-dev", "tizi-needs-can", [], [
step("build nightly-dev", "PANDA_DEBUG_BUILD=1 RELEASE_BRANCH=nightly-dev $SOURCE_DIR/release/build_release.sh"), step("build nightly-dev", "PANDA_DEBUG_BUILD=1 RELEASE_BRANCH=nightly-dev $SOURCE_DIR/release/build_release.sh"),
]) ])
}, },
@ -200,39 +200,30 @@ node {
if (!env.BRANCH_NAME.matches(excludeRegex)) { if (!env.BRANCH_NAME.matches(excludeRegex)) {
parallel ( parallel (
// tici tests
'onroad tests': { 'onroad tests': {
deviceStage("onroad", "tici-needs-can", ["UNSAFE=1"], [ deviceStage("onroad", "tizi-needs-can", ["UNSAFE=1"], [
step("build openpilot", "cd system/manager && ./build.py"), step("build openpilot", "cd system/manager && ./build.py"),
step("check dirty", "release/check-dirty.sh"), step("check dirty", "release/check-dirty.sh"),
step("onroad tests", "pytest selfdrive/test/test_onroad.py -s", [timeout: 60]), step("onroad tests", "pytest selfdrive/test/test_onroad.py -s", [timeout: 60]),
]) ])
}, },
'HW + Unit Tests': { 'HW + Unit Tests': {
deviceStage("tici-hardware", "tici-common", ["UNSAFE=1"], [ deviceStage("tizi-hardware", "tizi-common", ["UNSAFE=1"], [
step("build", "cd system/manager && ./build.py"), step("build", "cd system/manager && ./build.py"),
step("test pandad", "pytest selfdrive/pandad/tests/test_pandad.py", [diffPaths: ["panda", "selfdrive/pandad/"]]), step("test pandad", "pytest selfdrive/pandad/tests/test_pandad.py", [diffPaths: ["panda", "selfdrive/pandad/"]]),
step("test power draw", "pytest -s system/hardware/tici/tests/test_power_draw.py"), step("test power draw", "pytest -s system/hardware/tici/tests/test_power_draw.py"),
step("test encoder", "LD_LIBRARY_PATH=/usr/local/lib pytest system/loggerd/tests/test_encoder.py", [diffPaths: ["system/loggerd/"]]), step("test encoder", "LD_LIBRARY_PATH=/usr/local/lib pytest system/loggerd/tests/test_encoder.py", [diffPaths: ["system/loggerd/"]]),
step("test pigeond", "pytest system/ubloxd/tests/test_pigeond.py", [diffPaths: ["system/ubloxd/"]]),
step("test manager", "pytest system/manager/test/test_manager.py"), step("test manager", "pytest system/manager/test/test_manager.py"),
]) ])
}, },
'loopback': { 'loopback': {
deviceStage("loopback", "tici-loopback", ["UNSAFE=1"], [ deviceStage("loopback", "tizi-loopback", ["UNSAFE=1"], [
step("build openpilot", "cd system/manager && ./build.py"), step("build openpilot", "cd system/manager && ./build.py"),
step("test pandad loopback", "pytest selfdrive/pandad/tests/test_pandad_loopback.py"), step("test pandad loopback", "pytest selfdrive/pandad/tests/test_pandad_loopback.py"),
]) ])
}, },
'camerad AR0231': {
deviceStage("AR0231", "tici-ar0231", ["UNSAFE=1"], [
step("build", "cd system/manager && ./build.py"),
step("test camerad", "pytest system/camerad/test/test_camerad.py", [timeout: 60]),
step("test exposure", "pytest system/camerad/test/test_exposure.py"),
])
},
'camerad OX03C10': { 'camerad OX03C10': {
deviceStage("OX03C10", "tici-ox03c10", ["UNSAFE=1"], [ deviceStage("OX03C10", "tizi-ox03c10", ["UNSAFE=1"], [
step("build", "cd system/manager && ./build.py"), step("build", "cd system/manager && ./build.py"),
step("test camerad", "pytest system/camerad/test/test_camerad.py", [timeout: 60]), step("test camerad", "pytest system/camerad/test/test_camerad.py", [timeout: 60]),
step("test exposure", "pytest system/camerad/test/test_exposure.py"), step("test exposure", "pytest system/camerad/test/test_exposure.py"),
@ -246,17 +237,13 @@ node {
]) ])
}, },
'sensord': { 'sensord': {
deviceStage("LSM + MMC", "tici-lsmc", ["UNSAFE=1"], [ deviceStage("LSM + MMC", "tizi-lsmc", ["UNSAFE=1"], [
step("build", "cd system/manager && ./build.py"),
step("test sensord", "pytest system/sensord/tests/test_sensord.py"),
])
deviceStage("BMX + LSM", "tici-bmx-lsm", ["UNSAFE=1"], [
step("build", "cd system/manager && ./build.py"), step("build", "cd system/manager && ./build.py"),
step("test sensord", "pytest system/sensord/tests/test_sensord.py"), step("test sensord", "pytest system/sensord/tests/test_sensord.py"),
]) ])
}, },
'replay': { 'replay': {
deviceStage("model-replay", "tici-replay", ["UNSAFE=1"], [ deviceStage("model-replay", "tizi-replay", ["UNSAFE=1"], [
step("build", "cd system/manager && ./build.py", [diffPaths: ["selfdrive/modeld/", "tinygrad_repo", "selfdrive/test/process_replay/model_replay.py"]]), step("build", "cd system/manager && ./build.py", [diffPaths: ["selfdrive/modeld/", "tinygrad_repo", "selfdrive/test/process_replay/model_replay.py"]]),
step("model replay", "selfdrive/test/process_replay/model_replay.py", [diffPaths: ["selfdrive/modeld/", "tinygrad_repo", "selfdrive/test/process_replay/model_replay.py"]]), step("model replay", "selfdrive/test/process_replay/model_replay.py", [diffPaths: ["selfdrive/modeld/", "tinygrad_repo", "selfdrive/test/process_replay/model_replay.py"]]),
]) ])
@ -266,7 +253,6 @@ node {
step("build openpilot", "cd system/manager && ./build.py"), step("build openpilot", "cd system/manager && ./build.py"),
step("test pandad loopback", "SINGLE_PANDA=1 pytest selfdrive/pandad/tests/test_pandad_loopback.py"), step("test pandad loopback", "SINGLE_PANDA=1 pytest selfdrive/pandad/tests/test_pandad_loopback.py"),
step("test pandad spi", "pytest selfdrive/pandad/tests/test_pandad_spi.py"), step("test pandad spi", "pytest selfdrive/pandad/tests/test_pandad_spi.py"),
step("test pandad", "pytest selfdrive/pandad/tests/test_pandad.py", [diffPaths: ["panda", "selfdrive/pandad/"]]),
step("test amp", "pytest system/hardware/tici/tests/test_amplifier.py"), step("test amp", "pytest system/hardware/tici/tests/test_amplifier.py"),
// TODO: enable once new AGNOS is available // TODO: enable once new AGNOS is available
// step("test esim", "pytest system/hardware/tici/tests/test_esim.py"), // step("test esim", "pytest system/hardware/tici/tests/test_esim.py"),

@ -42,10 +42,10 @@ Using openpilot in a car
------ ------
To use openpilot in a car, you need four things: To use openpilot in a car, you need four things:
1. **Supported Device:** a comma 3/3X, available at [comma.ai/shop](https://comma.ai/shop/comma-3x). 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 3/3X allows users to enter a URL for custom software. Use the URL `openpilot.comma.ai` to install the release version. 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). 3. **Supported Car:** Ensure that you have one of [the 275+ supported cars](docs/CARS.md).
4. **Car Harness:** You will also need a [car harness](https://comma.ai/shop/car-harness) to connect your comma 3/3X to your car. 4. **Car Harness:** You will also need a [car harness](https://comma.ai/shop/car-harness) to connect your comma 3X to your car.
We have detailed instructions for [how to install the harness and device in a car](https://comma.ai/setup). Note that it's possible to run openpilot on [other hardware](https://blog.comma.ai/self-driving-car-for-free/), although it's not plug-and-play. 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.

@ -1,5 +1,9 @@
Version 0.10.1 (2025-09-08) Version 0.10.1 (2025-09-08)
======================== ========================
* New driving model
* World Model: removed global localization inputs
* World Model: 2x the number of parameters
* World Model: trained on 4x the number of segments
* Record driving feedback using LKAS button * Record driving feedback using LKAS button
* Honda City 2023 support thanks to drFritz! * Honda City 2023 support thanks to drFritz!

@ -585,7 +585,6 @@ struct PandaState @0xa7649e2575e4591e {
heartbeatLost @22 :Bool; heartbeatLost @22 :Bool;
interruptLoad @25 :Float32; interruptLoad @25 :Float32;
fanPower @28 :UInt8; fanPower @28 :UInt8;
fanStallCount @34 :UInt8;
spiErrorCount @33 :UInt16; spiErrorCount @33 :UInt16;
@ -714,6 +713,7 @@ struct PandaState @0xa7649e2575e4591e {
usbPowerModeDEPRECATED @12 :PeripheralState.UsbPowerModeDEPRECATED; usbPowerModeDEPRECATED @12 :PeripheralState.UsbPowerModeDEPRECATED;
safetyParamDEPRECATED @20 :Int16; safetyParamDEPRECATED @20 :Int16;
safetyParam2DEPRECATED @26 :UInt32; safetyParam2DEPRECATED @26 :UInt32;
fanStallCountDEPRECATED @34 :UInt8;
} }
struct PeripheralState { struct PeripheralState {

@ -33,7 +33,7 @@ MessageContext message_context;
struct SubMaster::SubMessage { struct SubMaster::SubMessage {
std::string name; std::string name;
SubSocket *socket = nullptr; SubSocket *socket = nullptr;
int freq = 0; float freq = 0.0f;
bool updated = false, alive = false, valid = false, ignore_alive; bool updated = false, alive = false, valid = false, ignore_alive;
uint64_t rcv_time = 0, rcv_frame = 0; uint64_t rcv_time = 0, rcv_frame = 0;
void *allocated_msg_reader = nullptr; void *allocated_msg_reader = nullptr;

@ -109,12 +109,12 @@ def build_header():
h += "#include <map>\n" h += "#include <map>\n"
h += "#include <string>\n" h += "#include <string>\n"
h += "struct service { std::string name; bool should_log; int frequency; int decimation; };\n" h += "struct service { std::string name; bool should_log; float frequency; int decimation; };\n"
h += "static std::map<std::string, service> services = {\n" h += "static std::map<std::string, service> services = {\n"
for k, v in SERVICE_LIST.items(): for k, v in SERVICE_LIST.items():
should_log = "true" if v.should_log else "false" should_log = "true" if v.should_log else "false"
decimation = -1 if v.decimation is None else v.decimation decimation = -1 if v.decimation is None else v.decimation
h += ' { "%s", {"%s", %s, %d, %d}},\n' % \ h += ' { "%s", {"%s", %s, %f, %d}},\n' % \
(k, k, should_log, v.frequency, decimation) (k, k, should_log, v.frequency, decimation)
h += "};\n" h += "};\n"

@ -94,7 +94,6 @@ inline static std::unordered_map<std::string, ParamKeyAttributes> keys = {
{"Offroad_NeosUpdate", {CLEAR_ON_MANAGER_START, JSON}}, {"Offroad_NeosUpdate", {CLEAR_ON_MANAGER_START, JSON}},
{"Offroad_NoFirmware", {CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION, JSON}}, {"Offroad_NoFirmware", {CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION, JSON}},
{"Offroad_Recalibration", {CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION, JSON}}, {"Offroad_Recalibration", {CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION, JSON}},
{"Offroad_StorageMissing", {CLEAR_ON_MANAGER_START, JSON}},
{"Offroad_TemperatureTooHigh", {CLEAR_ON_MANAGER_START, JSON}}, {"Offroad_TemperatureTooHigh", {CLEAR_ON_MANAGER_START, JSON}},
{"Offroad_UnregisteredHardware", {CLEAR_ON_MANAGER_START, JSON}}, {"Offroad_UnregisteredHardware", {CLEAR_ON_MANAGER_START, JSON}},
{"Offroad_UpdateFailed", {CLEAR_ON_MANAGER_START, JSON}}, {"Offroad_UpdateFailed", {CLEAR_ON_MANAGER_START, JSON}},

@ -39,7 +39,7 @@ All of these are examples of good PRs:
### First contribution ### 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. [Projects / openpilot bounties](https://github.com/orgs/commaai/projects/26/views/1?pane=info) is the best place to get started and goes in-depth on what's expected when working on a bounty.
There's lot of bounties that don't require a comma 3/3X or a car. There's lot of bounties that don't require a comma 3X or a car.
## Pull Requests ## Pull Requests

@ -16,7 +16,7 @@ industry standards of safety for Level 2 Driver Assistance Systems. In particula
ISO26262 guidelines, including those from [pertinent documents](https://www.nhtsa.gov/sites/nhtsa.dot.gov/files/documents/13498a_812_573_alcsystemreport.pdf) ISO26262 guidelines, including those from [pertinent documents](https://www.nhtsa.gov/sites/nhtsa.dot.gov/files/documents/13498a_812_573_alcsystemreport.pdf)
released by NHTSA. In addition, we impose strict coding guidelines (like [MISRA C : 2012](https://www.misra.org.uk/what-is-misra/)) released by NHTSA. In addition, we impose strict coding guidelines (like [MISRA C : 2012](https://www.misra.org.uk/what-is-misra/))
on parts of openpilot that are safety relevant. We also perform software-in-the-loop, on parts of openpilot that are safety relevant. We also perform software-in-the-loop,
hardware-in-the-loop and in-vehicle tests before each software release. hardware-in-the-loop, and in-vehicle tests before each software release.
Following Hazard and Risk Analysis and FMEA, at a very high level, we have designed openpilot Following Hazard and Risk Analysis and FMEA, at a very high level, we have designed openpilot
ensuring two main safety requirements. ensuring two main safety requirements.
@ -29,8 +29,18 @@ ensuring two main safety requirements.
For additional safety implementation details, refer to [panda safety model](https://github.com/commaai/panda#safety-model). For vehicle specific implementation of the safety concept, refer to [opendbc/safety/safety](https://github.com/commaai/opendbc/tree/master/opendbc/safety/safety). For additional safety implementation details, refer to [panda safety model](https://github.com/commaai/panda#safety-model). For vehicle specific implementation of the safety concept, refer to [opendbc/safety/safety](https://github.com/commaai/opendbc/tree/master/opendbc/safety/safety).
**Extra note**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or [^1]: For these actuator limits we observe ISO11270 and ISO15622. Lateral limits described there translate to 0.9 seconds of maximum actuation to achieve a 1m lateral deviation.
not fully meeting the above requirements.
[^1]: For these actuator limits we observe ISO11270 and ISO15622. Lateral limits described there translate to 0.9 seconds of maximum actuation to achieve a 1m lateral deviation. ---
### Forks of openpilot
* Do not disable or nerf [driver monitoring](https://github.com/commaai/openpilot/tree/master/selfdrive/monitoring)
* Do not disable or nerf [excessive actuation checks](https://github.com/commaai/openpilot/tree/master/selfdrive/selfdrived/helpers.py)
* If your fork modifies any of the code in `opendbc/safety/`:
* your fork cannot use the openpilot trademark
* your fork must preserve the full [safety test suite](https://github.com/commaai/opendbc/tree/master/opendbc/safety/tests) and all tests must pass, including any new coverage required by the fork's changes
Failure to comply with these standards will get you and your users banned from comma.ai servers.
**comma.ai strongly discourages the use of openpilot forks with safety code either missing or not fully meeting the above requirements.**

@ -1,11 +1,11 @@
# connect to a comma 3/3X # connect to a comma 3X
A comma 3/3X is a normal [Linux](https://github.com/commaai/agnos-builder) computer that exposes [SSH](https://wiki.archlinux.org/title/Secure_Shell) and a [serial console](https://wiki.archlinux.org/title/Working_with_the_serial_console). A comma 3X is a normal [Linux](https://github.com/commaai/agnos-builder) computer that exposes [SSH](https://wiki.archlinux.org/title/Secure_Shell) and a [serial console](https://wiki.archlinux.org/title/Working_with_the_serial_console).
## Serial Console ## Serial Console
On both the comma three and 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 3/3X to your computer with a normal USB C cable, or use a [comma serial](https://comma.ai/shop/comma-serial) for steady 12V power. Connect the comma 3X to your computer with a normal USB C cable, or use a [comma serial](https://comma.ai/shop/comma-serial) for steady 12V power.
On the comma three, the serial console is exposed through a UART-to-USB chip, and `tools/scripts/serial.sh` can be used to connect. On the comma three, the serial console is exposed through a UART-to-USB chip, and `tools/scripts/serial.sh` can be used to connect.
@ -45,7 +45,7 @@ In order to use ADB on your device, you'll need to perform the following steps u
* Here's an example command for connecting to your device using its tethered connection: `adb connect 192.168.43.1:5555` * Here's an example command for connecting to your device using its tethered connection: `adb connect 192.168.43.1:5555`
> [!NOTE] > [!NOTE]
> The default port for ADB is 5555 on the comma 3/3X. > The default port for ADB is 5555 on the comma 3X.
For more info on ADB, see the [Android Debug Bridge (ADB) documentation](https://developer.android.com/tools/adb). For more info on ADB, see the [Android Debug Bridge (ADB) documentation](https://developer.android.com/tools/adb).

@ -8,7 +8,7 @@ Replaying is a critical tool for openpilot development and debugging.
Just run `tools/replay/replay --demo`. Just run `tools/replay/replay --demo`.
## Replaying CAN data ## Replaying CAN data
*Hardware required: jungle and comma 3/3X* *Hardware required: jungle and comma 3X*
1. Connect your PC to a jungle. 1. Connect your PC to a jungle.
2. 2.

@ -3,7 +3,7 @@
In 30 minutes, we'll get an openpilot development environment set up on your computer and make some changes to openpilot's UI. In 30 minutes, we'll get an openpilot development environment set up on your computer and make some changes to openpilot's UI.
And if you have a comma 3/3X, we'll deploy the change to your device for testing. And if you have a comma 3X, we'll deploy the change to your device for testing.
## 1. Set up your development environment ## 1. Set up your development environment

@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1
export VECLIB_MAXIMUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1
if [ -z "$AGNOS_VERSION" ]; then if [ -z "$AGNOS_VERSION" ]; then
export AGNOS_VERSION="12.8" export AGNOS_VERSION="13"
fi fi
export STAGING_ROOT="/data/safe_staging" export STAGING_ROOT="/data/safe_staging"

@ -21,7 +21,7 @@ nav:
- What is openpilot?: getting-started/what-is-openpilot.md - What is openpilot?: getting-started/what-is-openpilot.md
- How-to: - How-to:
- Turn the speed blue: how-to/turn-the-speed-blue.md - Turn the speed blue: how-to/turn-the-speed-blue.md
- Connect to a comma 3/3X: how-to/connect-to-comma.md - Connect to a comma 3X: how-to/connect-to-comma.md
# - Make your first pull request: how-to/make-first-pr.md # - Make your first pull request: how-to/make-first-pr.md
#- Replay a drive: how-to/replay-a-drive.md #- Replay a drive: how-to/replay-a-drive.md
- Concepts: - Concepts:

@ -1 +1 @@
Subproject commit 43006b9a41e233325cb7cbcb6ff40de0234217a0 Subproject commit 7afc25d8d4096bb31e25c0b7ae0b961ea05f5394

@ -1 +1 @@
Subproject commit 3dc21386239e3073a623156b75901aa302340d6c Subproject commit 819fa5854e2e75da7f982f7d06be69c61793d6e1

@ -101,8 +101,9 @@ dev = [
"av", "av",
"azure-identity", "azure-identity",
"azure-storage-blob", "azure-storage-blob",
"dbus-next", "dbus-next", # TODO: remove once we moved everything to jeepney
"dictdiffer", "dictdiffer",
"jeepney",
"matplotlib", "matplotlib",
"opencv-python-headless", "opencv-python-headless",
"parameterized >=0.8, <0.9", "parameterized >=0.8, <0.9",

@ -17,29 +17,23 @@ rm -rf $TARGET_DIR
mkdir -p $TARGET_DIR mkdir -p $TARGET_DIR
cd $TARGET_DIR cd $TARGET_DIR
cp -r $SOURCE_DIR/.git $TARGET_DIR cp -r $SOURCE_DIR/.git $TARGET_DIR
pre-commit uninstall || true
echo "[-] bringing __nightly and devel in sync T=$SECONDS" echo "[-] setting up stripped branch sync T=$SECONDS"
cd $TARGET_DIR cd $TARGET_DIR
git fetch --depth 1 origin __nightly # tmp branch
git fetch --depth 1 origin devel git checkout --orphan tmp
git checkout -f --track origin/__nightly
git reset --hard __nightly
git checkout __nightly
git reset --hard origin/devel
git clean -xdff
git submodule foreach --recursive git clean -xdff
git lfs uninstall
# remove everything except .git # remove everything except .git
echo "[-] erasing old openpilot T=$SECONDS" echo "[-] erasing old openpilot T=$SECONDS"
git submodule deinit -f --all
git rm -rf --cached .
find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \; find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \;
# reset source tree # cleanup before the copy
cd $SOURCE_DIR cd $SOURCE_DIR
git clean -xdff git clean -xdff
git submodule foreach --recursive git clean -xdff
# do the files copy # do the files copy
echo "[-] copying files T=$SECONDS" echo "[-] copying files T=$SECONDS"
@ -48,6 +42,7 @@ cp -pR --parents $(./release/release_files.py) $TARGET_DIR/
# in the directory # in the directory
cd $TARGET_DIR cd $TARGET_DIR
rm -rf .git/modules/
rm -f panda/board/obj/panda.bin.signed rm -f panda/board/obj/panda.bin.signed
# include source commit hash and build date in commit # include source commit hash and build date in commit
@ -86,7 +81,7 @@ fi
if [ ! -z "$BRANCH" ]; then if [ ! -z "$BRANCH" ]; then
echo "[-] Pushing to $BRANCH T=$SECONDS" echo "[-] Pushing to $BRANCH T=$SECONDS"
git push -f origin __nightly:$BRANCH git push -f origin tmp:$BRANCH
fi fi
echo "[-] done T=$SECONDS, ready at $TARGET_DIR" echo "[-] done T=$SECONDS, ready at $TARGET_DIR"

@ -1,15 +1,12 @@
import os import os
import math
import hypothesis.strategies as st import hypothesis.strategies as st
from hypothesis import Phase, given, settings from hypothesis import Phase, given, settings
from parameterized import parameterized from parameterized import parameterized
from cereal import car from cereal import car
from opendbc.car import DT_CTRL from opendbc.car import DT_CTRL
from opendbc.car.car_helpers import interfaces
from opendbc.car.structs import CarParams from opendbc.car.structs import CarParams
from opendbc.car.tests.test_car_interfaces import get_fuzzy_car_interface_args from opendbc.car.tests.test_car_interfaces import get_fuzzy_car_interface
from opendbc.car.fw_versions import FW_VERSIONS, FW_QUERY_CONFIGS
from opendbc.car.mock.values import CAR as MOCK from opendbc.car.mock.values import CAR as MOCK
from opendbc.car.values import PLATFORMS from opendbc.car.values import PLATFORMS
from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle
@ -18,11 +15,6 @@ from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque
from openpilot.selfdrive.controls.lib.longcontrol import LongControl from openpilot.selfdrive.controls.lib.longcontrol import LongControl
from openpilot.selfdrive.test.fuzzy_generation import FuzzyGenerator from openpilot.selfdrive.test.fuzzy_generation import FuzzyGenerator
ALL_ECUS = {ecu for ecus in FW_VERSIONS.values() for ecu in ecus.keys()}
ALL_ECUS |= {ecu for config in FW_QUERY_CONFIGS.values() for ecu in config.extra_ecus}
ALL_REQUESTS = {tuple(r.request) for config in FW_QUERY_CONFIGS.values() for r in config.requests}
MAX_EXAMPLES = int(os.environ.get('MAX_EXAMPLES', '60')) MAX_EXAMPLES = int(os.environ.get('MAX_EXAMPLES', '60'))
@ -34,39 +26,8 @@ class TestCarInterfaces:
phases=(Phase.reuse, Phase.generate, Phase.shrink)) phases=(Phase.reuse, Phase.generate, Phase.shrink))
@given(data=st.data()) @given(data=st.data())
def test_car_interfaces(self, car_name, data): def test_car_interfaces(self, car_name, data):
CarInterface = interfaces[car_name] car_interface = get_fuzzy_car_interface(car_name, data.draw)
car_params = car_interface.CP.as_reader()
args = get_fuzzy_car_interface_args(data.draw)
car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'],
alpha_long=args['alpha_long'], is_release=False, docs=False)
car_params = car_params.as_reader()
car_interface = CarInterface(car_params)
assert car_params
assert car_interface
assert car_params.mass > 1
assert car_params.wheelbase > 0
# centerToFront is center of gravity to front wheels, assert a reasonable range
assert car_params.wheelbase * 0.3 < car_params.centerToFront < car_params.wheelbase * 0.7
assert car_params.maxLateralAccel > 0
# Longitudinal sanity checks
assert len(car_params.longitudinalTuning.kpV) == len(car_params.longitudinalTuning.kpBP)
assert len(car_params.longitudinalTuning.kiV) == len(car_params.longitudinalTuning.kiBP)
# Lateral sanity checks
if car_params.steerControlType != CarParams.SteerControlType.angle:
tune = car_params.lateralTuning
if tune.which() == 'pid':
if car_name != MOCK.MOCK:
assert not math.isnan(tune.pid.kf) and tune.pid.kf > 0
assert len(tune.pid.kpV) > 0 and len(tune.pid.kpV) == len(tune.pid.kpBP)
assert len(tune.pid.kiV) > 0 and len(tune.pid.kiV) == len(tune.pid.kiBP)
elif tune.which() == 'torque':
assert not math.isnan(tune.torque.kf) and tune.torque.kf > 0
assert not math.isnan(tune.torque.friction) and tune.torque.friction > 0
cc_msg = FuzzyGenerator.get_random_msg(data.draw, car.CarControl, real_floats=True) cc_msg = FuzzyGenerator.get_random_msg(data.draw, car.CarControl, real_floats=True)
# Run car interface # Run car interface

@ -52,10 +52,8 @@ class LatControlTorque(LatControl):
actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll)
roll_compensation = params.roll * ACCELERATION_DUE_TO_GRAVITY 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)) curvature_deadzone = abs(VM.calc_curvature(math.radians(self.steering_angle_deadzone_deg), CS.vEgo, 0.0))
desired_lateral_accel = desired_curvature * CS.vEgo ** 2
# desired rate is the desired rate of change in the setpoint, not the absolute desired curvature desired_lateral_accel = desired_curvature * CS.vEgo ** 2
# desired_lateral_jerk = desired_curvature_rate * CS.vEgo ** 2
actual_lateral_accel = actual_curvature * CS.vEgo ** 2 actual_lateral_accel = actual_curvature * CS.vEgo ** 2
lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2 lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2
@ -67,6 +65,8 @@ class LatControlTorque(LatControl):
# do error correction in lateral acceleration space, convert at end to handle non-linear torque responses correctly # do error correction in lateral acceleration space, convert at end to handle non-linear torque responses correctly
pid_log.error = float(setpoint - measurement) pid_log.error = float(setpoint - measurement)
ff = gravity_adjusted_lateral_accel ff = gravity_adjusted_lateral_accel
# latAccelOffset corrects roll compensation bias from device roll misalignment relative to car roll
ff -= self.torque_params.latAccelOffset
ff += get_friction(desired_lateral_accel - actual_lateral_accel, lateral_accel_deadzone, FRICTION_THRESHOLD, self.torque_params) ff += get_friction(desired_lateral_accel - actual_lateral_accel, lateral_accel_deadzone, FRICTION_THRESHOLD, self.torque_params)
freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5 freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5

@ -0,0 +1,70 @@
import numpy as np
from cereal import car, messaging
from opendbc.car import ACCELERATION_DUE_TO_GRAVITY
from opendbc.car import structs
from opendbc.car.lateral import get_friction, FRICTION_THRESHOLD
from openpilot.common.realtime import DT_MDL
from openpilot.selfdrive.locationd.torqued import TorqueEstimator, MIN_BUCKET_POINTS, POINTS_PER_BUCKET, STEER_BUCKET_BOUNDS
np.random.seed(0)
LA_ERR_STD = 1.0
INPUT_NOISE_STD = 0.08
V_EGO = 30.0
WARMUP_BUCKET_POINTS = (1.5*MIN_BUCKET_POINTS).astype(int)
STRAIGHT_ROAD_LA_BOUNDS = (0.02, 0.03)
ROLL_BIAS_DEG = 2.0
ROLL_COMPENSATION_BIAS = ACCELERATION_DUE_TO_GRAVITY*float(np.sin(np.deg2rad(ROLL_BIAS_DEG)))
TORQUE_TUNE = structs.CarParams.LateralTorqueTuning(latAccelFactor=2.0, latAccelOffset=0.0, friction=0.2)
TORQUE_TUNE_BIASED = structs.CarParams.LateralTorqueTuning(latAccelFactor=2.0, latAccelOffset=-ROLL_COMPENSATION_BIAS, friction=0.2)
def generate_inputs(torque_tune, la_err_std, input_noise_std=None):
rng = np.random.default_rng(0)
steer_torques = np.concat([rng.uniform(bnd[0], bnd[1], pts) for bnd, pts in zip(STEER_BUCKET_BOUNDS, WARMUP_BUCKET_POINTS, strict=True)])
la_errs = rng.normal(scale=la_err_std, size=steer_torques.size)
frictions = np.array([get_friction(la_err, 0.0, FRICTION_THRESHOLD, torque_tune) for la_err in la_errs])
lat_accels = torque_tune.latAccelFactor*steer_torques + torque_tune.latAccelOffset + frictions
if input_noise_std is not None:
steer_torques += rng.normal(scale=input_noise_std, size=steer_torques.size)
lat_accels += rng.normal(scale=input_noise_std, size=steer_torques.size)
return steer_torques, lat_accels
def get_warmed_up_estimator(steer_torques, lat_accels):
est = TorqueEstimator(car.CarParams())
for steer_torque, lat_accel in zip(steer_torques, lat_accels, strict=True):
est.filtered_points.add_point(steer_torque, lat_accel)
return est
def simulate_straight_road_msgs(est):
carControl = messaging.new_message('carControl').carControl
carOutput = messaging.new_message('carOutput').carOutput
carState = messaging.new_message('carState').carState
livePose = messaging.new_message('livePose').livePose
carControl.latActive = True
carState.vEgo = V_EGO
carState.steeringPressed = False
ts = DT_MDL*np.arange(2*POINTS_PER_BUCKET)
steer_torques = np.concat((np.linspace(-0.03, -0.02, POINTS_PER_BUCKET), np.linspace(0.02, 0.03, POINTS_PER_BUCKET)))
lat_accels = TORQUE_TUNE.latAccelFactor * steer_torques
for t, steer_torque, lat_accel in zip(ts, steer_torques, lat_accels, strict=True):
carOutput.actuatorsOutput.torque = float(-steer_torque)
livePose.orientationNED.x = float(np.deg2rad(ROLL_BIAS_DEG))
livePose.angularVelocityDevice.z = float(lat_accel / V_EGO)
for which, msg in (('carControl', carControl), ('carOutput', carOutput), ('carState', carState), ('livePose', livePose)):
est.handle_log(t, which, msg)
def test_estimated_offset():
steer_torques, lat_accels = generate_inputs(TORQUE_TUNE_BIASED, la_err_std=LA_ERR_STD, input_noise_std=INPUT_NOISE_STD)
est = get_warmed_up_estimator(steer_torques, lat_accels)
msg = est.get_msg()
# TODO add lataccelfactor and friction check when we have more accurate estimates
assert abs(msg.liveTorqueParameters.latAccelOffsetRaw - TORQUE_TUNE_BIASED.latAccelOffset) < 0.1
def test_straight_road_roll_bias():
steer_torques, lat_accels = generate_inputs(TORQUE_TUNE, la_err_std=LA_ERR_STD, input_noise_std=INPUT_NOISE_STD)
est = get_warmed_up_estimator(steer_torques, lat_accels)
simulate_straight_road_msgs(est)
msg = est.get_msg()
assert (msg.liveTorqueParameters.latAccelOffsetRaw < -0.05) and np.isfinite(msg.liveTorqueParameters.latAccelOffsetRaw)

@ -13,12 +13,9 @@ class ModelConstants:
META_T_IDXS = [2., 4., 6., 8., 10.] META_T_IDXS = [2., 4., 6., 8., 10.]
# model inputs constants # model inputs constants
MODEL_FREQ = 20 N_FRAMES = 2
HISTORY_FREQ = 5 MODEL_RUN_FREQ = 20
HISTORY_LEN_SECONDS = 5 MODEL_CONTEXT_FREQ = 5 # "model_trained_fps"
TEMPORAL_SKIP = MODEL_FREQ // HISTORY_FREQ
FULL_HISTORY_BUFFER_LEN = MODEL_FREQ * HISTORY_LEN_SECONDS
INPUT_HISTORY_BUFFER_LEN = HISTORY_FREQ * HISTORY_LEN_SECONDS
FEATURE_LEN = 512 FEATURE_LEN = 512

@ -149,7 +149,7 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D
meta.hardBrakePredicted = hard_brake_predicted.item() meta.hardBrakePredicted = hard_brake_predicted.item()
# confidence # confidence
if vipc_frame_id % (2*ModelConstants.MODEL_FREQ) == 0: if vipc_frame_id % (2*ModelConstants.MODEL_RUN_FREQ) == 0:
# any disengage prob # any disengage prob
brake_disengage_probs = net_output_data['meta'][0,Meta.BRAKE_DISENGAGE] brake_disengage_probs = net_output_data['meta'][0,Meta.BRAKE_DISENGAGE]
gas_disengage_probs = net_output_data['meta'][0,Meta.GAS_DISENGAGE] gas_disengage_probs = net_output_data['meta'][0,Meta.GAS_DISENGAGE]

@ -77,6 +77,64 @@ class FrameMeta:
if vipc is not None: if vipc is not None:
self.frame_id, self.timestamp_sof, self.timestamp_eof = vipc.frame_id, vipc.timestamp_sof, vipc.timestamp_eof self.frame_id, self.timestamp_sof, self.timestamp_eof = vipc.frame_id, vipc.timestamp_sof, vipc.timestamp_eof
class InputQueues:
def __init__ (self, model_fps, env_fps, n_frames_input):
assert env_fps % model_fps == 0
assert env_fps >= model_fps
self.model_fps = model_fps
self.env_fps = env_fps
self.n_frames_input = n_frames_input
self.dtypes = {}
self.shapes = {}
self.q = {}
def update_dtypes_and_shapes(self, input_dtypes, input_shapes) -> None:
self.dtypes.update(input_dtypes)
if self.env_fps == self.model_fps:
self.shapes.update(input_shapes)
else:
for k in input_shapes:
shape = list(input_shapes[k])
if 'img' in k:
n_channels = shape[1] // self.n_frames_input
shape[1] = (self.env_fps // self.model_fps + (self.n_frames_input - 1)) * n_channels
else:
shape[1] = (self.env_fps // self.model_fps) * shape[1]
self.shapes[k] = tuple(shape)
def reset(self) -> None:
self.q = {k: np.zeros(self.shapes[k], dtype=self.dtypes[k]) for k in self.dtypes.keys()}
def enqueue(self, inputs:dict[str, np.ndarray]) -> None:
for k in inputs.keys():
if inputs[k].dtype != self.dtypes[k]:
raise ValueError(f'supplied input <{k}({inputs[k].dtype})> has wrong dtype, expected {self.dtypes[k]}')
input_shape = list(self.shapes[k])
input_shape[1] = -1
single_input = inputs[k].reshape(tuple(input_shape))
sz = single_input.shape[1]
self.q[k][:,:-sz] = self.q[k][:,sz:]
self.q[k][:,-sz:] = single_input
def get(self, *names) -> dict[str, np.ndarray]:
if self.env_fps == self.model_fps:
return {k: self.q[k] for k in names}
else:
out = {}
for k in names:
shape = self.shapes[k]
if 'img' in k:
n_channels = shape[1] // (self.env_fps // self.model_fps + (self.n_frames_input - 1))
out[k] = np.concatenate([self.q[k][:, s:s+n_channels] for s in np.linspace(0, shape[1] - n_channels, self.n_frames_input, dtype=int)], axis=1)
elif 'pulse' in k:
# any pulse within interval counts
out[k] = self.q[k].reshape((shape[0], shape[1] * self.model_fps // self.env_fps, self.env_fps // self.model_fps, -1)).max(axis=2)
else:
idxs = np.arange(-1, -shape[1], -self.env_fps // self.model_fps)[::-1]
out[k] = self.q[k][:, idxs]
return out
class ModelState: class ModelState:
frames: dict[str, DrivingModelFrame] frames: dict[str, DrivingModelFrame]
inputs: dict[str, np.ndarray] inputs: dict[str, np.ndarray]
@ -97,19 +155,15 @@ class ModelState:
self.policy_output_slices = policy_metadata['output_slices'] self.policy_output_slices = policy_metadata['output_slices']
policy_output_size = policy_metadata['output_shapes']['outputs'][1] policy_output_size = policy_metadata['output_shapes']['outputs'][1]
self.frames = {name: DrivingModelFrame(context, ModelConstants.TEMPORAL_SKIP) for name in self.vision_input_names} self.frames = {name: DrivingModelFrame(context, ModelConstants.MODEL_RUN_FREQ//ModelConstants.MODEL_CONTEXT_FREQ) for name in self.vision_input_names}
self.prev_desire = np.zeros(ModelConstants.DESIRE_LEN, dtype=np.float32) self.prev_desire = np.zeros(ModelConstants.DESIRE_LEN, dtype=np.float32)
self.full_features_buffer = np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32)
self.full_desire = np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.DESIRE_LEN), dtype=np.float32)
self.temporal_idxs = slice(-1-(ModelConstants.TEMPORAL_SKIP*(ModelConstants.INPUT_HISTORY_BUFFER_LEN-1)), None, ModelConstants.TEMPORAL_SKIP)
# policy inputs # policy inputs
self.numpy_inputs = { self.numpy_inputs = {k: np.zeros(self.policy_input_shapes[k], dtype=np.float32) for k in self.policy_input_shapes}
'desire': np.zeros((1, ModelConstants.INPUT_HISTORY_BUFFER_LEN, ModelConstants.DESIRE_LEN), dtype=np.float32), self.full_input_queues = InputQueues(ModelConstants.MODEL_CONTEXT_FREQ, ModelConstants.MODEL_RUN_FREQ, ModelConstants.N_FRAMES)
'traffic_convention': np.zeros((1, ModelConstants.TRAFFIC_CONVENTION_LEN), dtype=np.float32), for k in ['desire_pulse', 'features_buffer']:
'features_buffer': np.zeros((1, ModelConstants.INPUT_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32), self.full_input_queues.update_dtypes_and_shapes({k: self.numpy_inputs[k].dtype}, {k: self.numpy_inputs[k].shape})
} self.full_input_queues.reset()
# img buffers are managed in openCL transform code # img buffers are managed in openCL transform code
self.vision_inputs: dict[str, Tensor] = {} self.vision_inputs: dict[str, Tensor] = {}
@ -131,15 +185,10 @@ class ModelState:
def run(self, bufs: dict[str, VisionBuf], transforms: dict[str, np.ndarray], def run(self, bufs: dict[str, VisionBuf], transforms: dict[str, np.ndarray],
inputs: dict[str, np.ndarray], prepare_only: bool) -> dict[str, np.ndarray] | None: inputs: dict[str, np.ndarray], prepare_only: bool) -> dict[str, np.ndarray] | None:
# Model decides when action is completed, so desire input is just a pulse triggered on rising edge # Model decides when action is completed, so desire input is just a pulse triggered on rising edge
inputs['desire'][0] = 0 inputs['desire_pulse'][0] = 0
new_desire = np.where(inputs['desire'] - self.prev_desire > .99, inputs['desire'], 0) new_desire = np.where(inputs['desire_pulse'] - self.prev_desire > .99, inputs['desire_pulse'], 0)
self.prev_desire[:] = inputs['desire'] self.prev_desire[:] = inputs['desire_pulse']
self.full_desire[0,:-1] = self.full_desire[0,1:]
self.full_desire[0,-1] = new_desire
self.numpy_inputs['desire'][:] = self.full_desire.reshape((1,ModelConstants.INPUT_HISTORY_BUFFER_LEN,ModelConstants.TEMPORAL_SKIP,-1)).max(axis=2)
self.numpy_inputs['traffic_convention'][:] = inputs['traffic_convention']
imgs_cl = {name: self.frames[name].prepare(bufs[name], transforms[name].flatten()) for name in self.vision_input_names} imgs_cl = {name: self.frames[name].prepare(bufs[name], transforms[name].flatten()) for name in self.vision_input_names}
if TICI and not USBGPU: if TICI and not USBGPU:
@ -158,9 +207,10 @@ class ModelState:
self.vision_output = self.vision_run(**self.vision_inputs).contiguous().realize().uop.base.buffer.numpy() self.vision_output = self.vision_run(**self.vision_inputs).contiguous().realize().uop.base.buffer.numpy()
vision_outputs_dict = self.parser.parse_vision_outputs(self.slice_outputs(self.vision_output, self.vision_output_slices)) vision_outputs_dict = self.parser.parse_vision_outputs(self.slice_outputs(self.vision_output, self.vision_output_slices))
self.full_features_buffer[0,:-1] = self.full_features_buffer[0,1:] self.full_input_queues.enqueue({'features_buffer': vision_outputs_dict['hidden_state'], 'desire_pulse': new_desire})
self.full_features_buffer[0,-1] = vision_outputs_dict['hidden_state'][0, :] for k in ['desire_pulse', 'features_buffer']:
self.numpy_inputs['features_buffer'][:] = self.full_features_buffer[0, self.temporal_idxs] self.numpy_inputs[k][:] = self.full_input_queues.get(k)[k]
self.numpy_inputs['traffic_convention'][:] = inputs['traffic_convention']
self.policy_output = self.policy_run(**self.policy_inputs).contiguous().realize().uop.base.buffer.numpy() self.policy_output = self.policy_run(**self.policy_inputs).contiguous().realize().uop.base.buffer.numpy()
policy_outputs_dict = self.parser.parse_policy_outputs(self.slice_outputs(self.policy_output, self.policy_output_slices)) policy_outputs_dict = self.parser.parse_policy_outputs(self.slice_outputs(self.policy_output, self.policy_output_slices))
@ -218,7 +268,7 @@ def main(demo=False):
params = Params() params = Params()
# setup filter to track dropped frames # setup filter to track dropped frames
frame_dropped_filter = FirstOrderFilter(0., 10., 1. / ModelConstants.MODEL_FREQ) frame_dropped_filter = FirstOrderFilter(0., 10., 1. / ModelConstants.MODEL_RUN_FREQ)
frame_id = 0 frame_id = 0
last_vipc_frame_id = 0 last_vipc_frame_id = 0
run_count = 0 run_count = 0
@ -313,7 +363,7 @@ def main(demo=False):
bufs = {name: buf_extra if 'big' in name else buf_main for name in model.vision_input_names} bufs = {name: buf_extra if 'big' in name else buf_main for name in model.vision_input_names}
transforms = {name: model_transform_extra if 'big' in name else model_transform_main for name in model.vision_input_names} transforms = {name: model_transform_extra if 'big' in name else model_transform_main for name in model.vision_input_names}
inputs:dict[str, np.ndarray] = { inputs:dict[str, np.ndarray] = {
'desire': vec_desire, 'desire_pulse': vec_desire,
'traffic_convention': traffic_convention, 'traffic_convention': traffic_convention,
} }

@ -152,7 +152,6 @@ void fill_panda_state(cereal::PandaState::Builder &ps, cereal::PandaState::Panda
ps.setHarnessStatus(cereal::PandaState::HarnessStatus(health.car_harness_status_pkt)); ps.setHarnessStatus(cereal::PandaState::HarnessStatus(health.car_harness_status_pkt));
ps.setInterruptLoad(health.interrupt_load_pkt); ps.setInterruptLoad(health.interrupt_load_pkt);
ps.setFanPower(health.fan_power); ps.setFanPower(health.fan_power);
ps.setFanStallCount(health.fan_stall_count);
ps.setSafetyRxChecksInvalid((bool)(health.safety_rx_checks_invalid_pkt)); ps.setSafetyRxChecksInvalid((bool)(health.safety_rx_checks_invalid_pkt));
ps.setSpiErrorCount(health.spi_error_count_pkt); ps.setSpiErrorCount(health.spi_error_count_pkt);
ps.setSbu1Voltage(health.sbu1_voltage_mV / 1000.0f); ps.setSbu1Voltage(health.sbu1_voltage_mV / 1000.0f);

@ -85,11 +85,6 @@ def main() -> None:
cloudlog.event("pandad.flash_and_connect", count=count) cloudlog.event("pandad.flash_and_connect", count=count)
params.remove("PandaSignatures") params.remove("PandaSignatures")
# TODO: remove this in the next AGNOS
# wait until USB is up before counting
if time.monotonic() < 60.:
no_internal_panda_count = 0
# Handle missing internal panda # Handle missing internal panda
if no_internal_panda_count > 0: if no_internal_panda_count > 0:
if no_internal_panda_count == 3: if no_internal_panda_count == 3:

@ -22,8 +22,6 @@ class TestPandad:
if len(Panda.list()) == 0: if len(Panda.list()) == 0:
self._run_test(60) self._run_test(60)
self.spi = HARDWARE.get_device_type() != 'tici'
def teardown_method(self): def teardown_method(self):
managed_processes['pandad'].stop() managed_processes['pandad'].stop()
@ -106,11 +104,9 @@ class TestPandad:
# - 0.2s pandad -> pandad # - 0.2s pandad -> pandad
# - plus some buffer # - plus some buffer
print("startup times", ts, sum(ts) / len(ts)) print("startup times", ts, sum(ts) / len(ts))
assert 0.1 < (sum(ts)/len(ts)) < (0.7 if self.spi else 5.0) assert 0.1 < (sum(ts)/len(ts)) < 0.7
def test_protocol_version_check(self): def test_protocol_version_check(self):
if not self.spi:
pytest.skip("SPI test")
# flash old fw # flash old fw
fn = os.path.join(HERE, "bootstub.panda_h7_spiv0.bin") fn = os.path.join(HERE, "bootstub.panda_h7_spiv0.bin")
self._flash_bootstub_and_test(fn, expect_mismatch=True) self._flash_bootstub_and_test(fn, expect_mismatch=True)

@ -6,7 +6,6 @@ import random
import cereal.messaging as messaging import cereal.messaging as messaging
from cereal.services import SERVICE_LIST from cereal.services import SERVICE_LIST
from openpilot.system.hardware import HARDWARE
from openpilot.selfdrive.test.helpers import with_processes from openpilot.selfdrive.test.helpers import with_processes
from openpilot.selfdrive.pandad.tests.test_pandad_loopback import setup_pandad, send_random_can_messages from openpilot.selfdrive.pandad.tests.test_pandad_loopback import setup_pandad, send_random_can_messages
@ -16,8 +15,6 @@ JUNGLE_SPAM = "JUNGLE_SPAM" in os.environ
class TestBoarddSpi: class TestBoarddSpi:
@classmethod @classmethod
def setup_class(cls): def setup_class(cls):
if HARDWARE.get_device_type() == 'tici':
pytest.skip("only for spi pandas")
os.environ['STARTED'] = '1' os.environ['STARTED'] = '1'
os.environ['SPI_ERR_PROB'] = '0.001' os.environ['SPI_ERR_PROB'] = '0.001'
if not JUNGLE_SPAM: if not JUNGLE_SPAM:

@ -29,10 +29,6 @@
"text": "Device failed to register with the comma.ai backend. It will not connect or upload to comma.ai servers, and receives no support from comma.ai. If this is a device purchased at comma.ai/shop, open a ticket at https://comma.ai/support.", "text": "Device failed to register with the comma.ai backend. It will not connect or upload to comma.ai servers, and receives no support from comma.ai. If this is a device purchased at comma.ai/shop, open a ticket at https://comma.ai/support.",
"severity": 1 "severity": 1
}, },
"Offroad_StorageMissing": {
"text": "NVMe drive not mounted.",
"severity": 1
},
"Offroad_CarUnrecognized": { "Offroad_CarUnrecognized": {
"text": "openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai.", "text": "openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai.",
"severity": 0 "severity": 0

@ -21,7 +21,6 @@ from openpilot.selfdrive.selfdrived.helpers import ExcessiveActuationCheck
from openpilot.selfdrive.selfdrived.state import StateMachine from openpilot.selfdrive.selfdrived.state import StateMachine
from openpilot.selfdrive.selfdrived.alertmanager import AlertManager, set_offroad_alert from openpilot.selfdrive.selfdrived.alertmanager import AlertManager, set_offroad_alert
from openpilot.system.hardware import HARDWARE
from openpilot.system.version import get_build_metadata from openpilot.system.version import get_build_metadata
REPLAY = "REPLAY" in os.environ REPLAY = "REPLAY" in os.environ
@ -122,13 +121,6 @@ class SelfdriveD:
self.state_machine = StateMachine() self.state_machine = StateMachine()
self.rk = Ratekeeper(100, print_delay_threshold=None) self.rk = Ratekeeper(100, print_delay_threshold=None)
# some comma three with NVMe experience NVMe dropouts mid-drive that
# cause loggerd to crash on write, so ignore it only on that platform
self.ignored_processes = set()
nvme_expected = os.path.exists('/dev/nvme0n1') or (not os.path.isfile("/persist/comma/living-in-the-moment"))
if HARDWARE.get_device_type() == 'tici' and nvme_expected:
self.ignored_processes = {'loggerd', }
# Determine startup event # Determine startup event
self.startup_event = EventName.startup if build_metadata.openpilot.comma_remote and build_metadata.tested_channel else EventName.startupMaster self.startup_event = EventName.startup if build_metadata.openpilot.comma_remote and build_metadata.tested_channel else EventName.startupMaster
if not car_recognized: if not car_recognized:
@ -299,7 +291,7 @@ class SelfdriveD:
if not_running != self.not_running_prev: if not_running != self.not_running_prev:
cloudlog.event("process_not_running", not_running=not_running, error=True) cloudlog.event("process_not_running", not_running=not_running, error=True)
self.not_running_prev = not_running self.not_running_prev = not_running
if self.sm.recv_frame['managerState'] and (not_running - self.ignored_processes): if self.sm.recv_frame['managerState'] and not_running:
self.events.add(EventName.processNotRunning) self.events.add(EventName.processNotRunning)
else: else:
if not SIMULATION and not self.rk.lagging: if not SIMULATION and not self.rk.lagging:

@ -591,7 +591,7 @@ def get_custom_params_from_lr(lr: LogIterable, initial_state: str = "first") ->
if len(live_calibration) > 0: if len(live_calibration) > 0:
custom_params["CalibrationParams"] = live_calibration[msg_index].as_builder().to_bytes() custom_params["CalibrationParams"] = live_calibration[msg_index].as_builder().to_bytes()
if len(live_parameters) > 0: if len(live_parameters) > 0:
custom_params["LiveParameters"] = live_parameters[msg_index].as_builder().to_bytes() custom_params["LiveParametersV2"] = live_parameters[msg_index].as_builder().to_bytes()
if len(live_torque_parameters) > 0: if len(live_torque_parameters) > 0:
custom_params["LiveTorqueParameters"] = live_torque_parameters[msg_index].as_builder().to_bytes() custom_params["LiveTorqueParameters"] = live_torque_parameters[msg_index].as_builder().to_bytes()

@ -1 +1 @@
6d3219bca9f66a229b38a5382d301a92b0147edb afcab1abb62b9d5678342956cced4712f44e909e

@ -18,7 +18,6 @@ from openpilot.common.timeout import Timeout
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.selfdrive.selfdrived.events import EVENTS, ET from openpilot.selfdrive.selfdrived.events import EVENTS, ET
from openpilot.selfdrive.test.helpers import set_params_enabled, release_only from openpilot.selfdrive.test.helpers import set_params_enabled, release_only
from openpilot.system.hardware import HARDWARE
from openpilot.system.hardware.hw import Paths from openpilot.system.hardware.hw import Paths
from openpilot.tools.lib.logreader import LogReader from openpilot.tools.lib.logreader import LogReader
from openpilot.tools.lib.log_time_series import msgs_to_time_series from openpilot.tools.lib.log_time_series import msgs_to_time_series
@ -33,7 +32,7 @@ CPU usage budget
TEST_DURATION = 25 TEST_DURATION = 25
LOG_OFFSET = 8 LOG_OFFSET = 8
MAX_TOTAL_CPU = 280. # total for all 8 cores MAX_TOTAL_CPU = 287. # total for all 8 cores
PROCS = { PROCS = {
# Baseline CPU usage by process # Baseline CPU usage by process
"selfdrive.controls.controlsd": 16.0, "selfdrive.controls.controlsd": 16.0,
@ -67,20 +66,10 @@ PROCS = {
"system.statsd": 1.0, "system.statsd": 1.0,
"system.loggerd.uploader": 15.0, "system.loggerd.uploader": 15.0,
"system.loggerd.deleter": 1.0, "system.loggerd.deleter": 1.0,
"./pandad": 19.0,
"system.qcomgpsd.qcomgpsd": 1.0,
} }
PROCS.update({
"tici": {
"./pandad": 5.0,
"./ubloxd": 1.0,
"system.ubloxd.pigeond": 6.0,
},
"tizi": {
"./pandad": 19.0,
"system.qcomgpsd.qcomgpsd": 1.0,
}
}.get(HARDWARE.get_device_type(), {}))
TIMINGS = { TIMINGS = {
# rtols: max/min, rsd # rtols: max/min, rsd
"can": [2.5, 0.35], "can": [2.5, 0.35],

@ -63,14 +63,20 @@ class MainLayout(Widget):
# Don't hide sidebar from interactive timeout # Don't hide sidebar from interactive timeout
if self._current_mode != MainState.ONROAD: if self._current_mode != MainState.ONROAD:
self._sidebar.set_visible(False) self._sidebar.set_visible(False)
self._current_mode = MainState.ONROAD self._set_current_layout(MainState.ONROAD)
else: else:
self._current_mode = MainState.HOME self._set_current_layout(MainState.HOME)
self._sidebar.set_visible(True) self._sidebar.set_visible(True)
def _set_current_layout(self, layout: MainState):
if layout != self._current_mode:
self._layouts[self._current_mode].hide_event()
self._current_mode = layout
self._layouts[self._current_mode].show_event()
def open_settings(self, panel_type: PanelType): def open_settings(self, panel_type: PanelType):
self._layouts[MainState.SETTINGS].set_current_panel(panel_type) self._layouts[MainState.SETTINGS].set_current_panel(panel_type)
self._current_mode = MainState.SETTINGS self._set_current_layout(MainState.SETTINGS)
self._sidebar.set_visible(False) self._sidebar.set_visible(False)
def _on_settings_clicked(self): def _on_settings_clicked(self):

@ -1,17 +0,0 @@
import pyray as rl
from openpilot.system.ui.lib.wifi_manager import WifiManagerWrapper
from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.network import WifiManagerUI
class NetworkLayout(Widget):
def __init__(self):
super().__init__()
self.wifi_manager = WifiManagerWrapper()
self.wifi_ui = WifiManagerUI(self.wifi_manager)
def _render(self, rect: rl.Rectangle):
self.wifi_ui.render(rect)
def shutdown(self):
self.wifi_manager.shutdown()

@ -2,7 +2,7 @@ import pyray as rl
import time import time
import threading import threading
from openpilot.common.api import Api, api_get from openpilot.common.api import api_get
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.common.swaglog import cloudlog from openpilot.common.swaglog import cloudlog
from openpilot.selfdrive.ui.ui_state import ui_state from openpilot.selfdrive.ui.ui_state import ui_state
@ -11,7 +11,7 @@ from openpilot.system.ui.lib.application import gui_app, FontWeight
from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel
from openpilot.system.ui.lib.wrap_text import wrap_text from openpilot.system.ui.lib.wrap_text import wrap_text
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.selfdrive.ui.lib.api_helpers import get_token
TITLE = "Firehose Mode" TITLE = "Firehose Mode"
DESCRIPTION = ( DESCRIPTION = (
@ -163,7 +163,7 @@ class FirehoseLayout(Widget):
dongle_id = self.params.get("DongleId") dongle_id = self.params.get("DongleId")
if not dongle_id or dongle_id == UNREGISTERED_DONGLE_ID: if not dongle_id or dongle_id == UNREGISTERED_DONGLE_ID:
return return
identity_token = Api(dongle_id).get_token() identity_token = get_token(dongle_id)
response = api_get(f"v1/devices/{dongle_id}/firehose_stats", access_token=identity_token) response = api_get(f"v1/devices/{dongle_id}/firehose_stats", access_token=identity_token)
if response.status_code == 200: if response.status_code == 200:
data = response.json() data = response.json()

@ -2,7 +2,6 @@ import pyray as rl
from dataclasses import dataclass from dataclasses import dataclass
from enum import IntEnum from enum import IntEnum
from collections.abc import Callable from collections.abc import Callable
from openpilot.selfdrive.ui.layouts.network import NetworkLayout
from openpilot.selfdrive.ui.layouts.settings.developer import DeveloperLayout from openpilot.selfdrive.ui.layouts.settings.developer import DeveloperLayout
from openpilot.selfdrive.ui.layouts.settings.device import DeviceLayout from openpilot.selfdrive.ui.layouts.settings.device import DeviceLayout
from openpilot.selfdrive.ui.layouts.settings.firehose import FirehoseLayout from openpilot.selfdrive.ui.layouts.settings.firehose import FirehoseLayout
@ -10,7 +9,9 @@ from openpilot.selfdrive.ui.layouts.settings.software import SoftwareLayout
from openpilot.selfdrive.ui.layouts.settings.toggles import TogglesLayout from openpilot.selfdrive.ui.layouts.settings.toggles import TogglesLayout
from openpilot.system.ui.lib.application import gui_app, FontWeight, MousePos from openpilot.system.ui.lib.application import gui_app, FontWeight, MousePos
from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.text_measure import measure_text_cached
from openpilot.system.ui.lib.wifi_manager import WifiManager
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.network import WifiManagerUI
# Settings close button # Settings close button
SETTINGS_CLOSE_TEXT = "×" SETTINGS_CLOSE_TEXT = "×"
@ -43,7 +44,7 @@ class PanelType(IntEnum):
@dataclass @dataclass
class PanelInfo: class PanelInfo:
name: str name: str
instance: object instance: Widget
button_rect: rl.Rectangle = rl.Rectangle(0, 0, 0, 0) button_rect: rl.Rectangle = rl.Rectangle(0, 0, 0, 0)
@ -53,9 +54,12 @@ class SettingsLayout(Widget):
self._current_panel = PanelType.DEVICE self._current_panel = PanelType.DEVICE
# Panel configuration # Panel configuration
wifi_manager = WifiManager()
wifi_manager.set_active(False)
self._panels = { self._panels = {
PanelType.DEVICE: PanelInfo("Device", DeviceLayout()), PanelType.DEVICE: PanelInfo("Device", DeviceLayout()),
PanelType.NETWORK: PanelInfo("Network", NetworkLayout()), PanelType.NETWORK: PanelInfo("Network", WifiManagerUI(wifi_manager)),
PanelType.TOGGLES: PanelInfo("Toggles", TogglesLayout()), PanelType.TOGGLES: PanelInfo("Toggles", TogglesLayout()),
PanelType.SOFTWARE: PanelInfo("Software", SoftwareLayout()), PanelType.SOFTWARE: PanelInfo("Software", SoftwareLayout()),
PanelType.FIREHOSE: PanelInfo("Firehose", FirehoseLayout()), PanelType.FIREHOSE: PanelInfo("Firehose", FirehoseLayout()),
@ -149,8 +153,14 @@ class SettingsLayout(Widget):
def set_current_panel(self, panel_type: PanelType): def set_current_panel(self, panel_type: PanelType):
if panel_type != self._current_panel: if panel_type != self._current_panel:
self._panels[self._current_panel].instance.hide_event()
self._current_panel = panel_type self._current_panel = panel_type
self._panels[self._current_panel].instance.show_event()
def show_event(self):
super().show_event()
self._panels[self._current_panel].instance.show_event()
def close_settings(self): def hide_event(self):
if self._close_callback: super().hide_event()
self._close_callback() self._panels[self._current_panel].instance.hide_event()

@ -0,0 +1,14 @@
import time
from functools import lru_cache
from openpilot.common.api import Api
TOKEN_EXPIRY_HOURS = 2
@lru_cache(maxsize=1)
def _get_token(dongle_id: str, t: int):
return Api(dongle_id).get_token(expiry_hours=TOKEN_EXPIRY_HOURS)
def get_token(dongle_id: str):
return _get_token(dongle_id, int(time.monotonic() / (TOKEN_EXPIRY_HOURS / 2 * 60 * 60)))

@ -3,10 +3,11 @@ import os
import threading import threading
import time import time
from openpilot.common.api import Api, api_get from openpilot.common.api import api_get
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.common.swaglog import cloudlog from openpilot.common.swaglog import cloudlog
from openpilot.system.athena.registration import UNREGISTERED_DONGLE_ID from openpilot.system.athena.registration import UNREGISTERED_DONGLE_ID
from openpilot.selfdrive.ui.lib.api_helpers import get_token
class PrimeType(IntEnum): class PrimeType(IntEnum):
@ -49,7 +50,7 @@ class PrimeState:
return return
try: try:
identity_token = Api(dongle_id).get_token() identity_token = get_token(dongle_id)
response = api_get(f"v1.1/devices/{dongle_id}", timeout=self.API_TIMEOUT, access_token=identity_token) response = api_get(f"v1.1/devices/{dongle_id}", timeout=self.API_TIMEOUT, access_token=identity_token)
if response.status_code == 200: if response.status_code == 200:
data = response.json() data = response.json()

@ -29,7 +29,7 @@ UI_DELAY = 0.1 # may be slower on CI?
TEST_ROUTE = "a2a0ccea32023010|2023-07-27--13-01-19" TEST_ROUTE = "a2a0ccea32023010|2023-07-27--13-01-19"
STREAMS: list[tuple[VisionStreamType, CameraConfig, bytes]] = [] STREAMS: list[tuple[VisionStreamType, CameraConfig, bytes]] = []
OFFROAD_ALERTS = ['Offroad_StorageMissing', 'Offroad_IsTakingSnapshot'] OFFROAD_ALERTS = ['Offroad_IsTakingSnapshot', ]
DATA: dict[str, capnp.lib.capnp._DynamicStructBuilder] = dict.fromkeys( DATA: dict[str, capnp.lib.capnp._DynamicStructBuilder] = dict.fromkeys(
["carParams", "deviceState", "pandaStates", "controlsState", "selfdriveState", ["carParams", "deviceState", "pandaStates", "controlsState", "selfdriveState",
"liveCalibration", "modelV2", "radarState", "driverMonitoringState", "carState", "liveCalibration", "modelV2", "radarState", "driverMonitoringState", "carState",

@ -54,8 +54,7 @@ static void update_state(UIState *s) {
} }
if (sm.updated("wideRoadCameraState")) { if (sm.updated("wideRoadCameraState")) {
auto cam_state = sm["wideRoadCameraState"].getWideRoadCameraState(); auto cam_state = sm["wideRoadCameraState"].getWideRoadCameraState();
float scale = (cam_state.getSensor() == cereal::FrameData::ImageSensor::AR0231) ? 6.0f : 1.0f; scene.light_sensor = std::max(100.0f - cam_state.getExposureValPercent(), 0.0f);
scene.light_sensor = std::max(100.0f - scale * cam_state.getExposureValPercent(), 0.0f);
} else if (!sm.allAliveAndValid({"wideRoadCameraState"})) { } else if (!sm.allAliveAndValid({"wideRoadCameraState"})) {
scene.light_sensor = -1; scene.light_sensor = -1;
} }

@ -105,10 +105,7 @@ class UIState:
# Handle wide road camera state updates # Handle wide road camera state updates
if self.sm.updated["wideRoadCameraState"]: if self.sm.updated["wideRoadCameraState"]:
cam_state = self.sm["wideRoadCameraState"] cam_state = self.sm["wideRoadCameraState"]
self.light_sensor = max(100.0 - cam_state.exposureValPercent, 0.0)
# Scale factor based on sensor type
scale = 6.0 if cam_state.sensor == 'ar0231' else 1.0
self.light_sensor = max(100.0 - scale * cam_state.exposureValPercent, 0.0)
elif not self.sm.alive["wideRoadCameraState"] or not self.sm.valid["wideRoadCameraState"]: elif not self.sm.alive["wideRoadCameraState"] or not self.sm.valid["wideRoadCameraState"]:
self.light_sensor = -1 self.light_sensor = -1

@ -4,7 +4,7 @@ libs = [common, 'OpenCL', messaging, visionipc, gpucommon]
if arch != "Darwin": if arch != "Darwin":
camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/spectra.cc', camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/spectra.cc',
'cameras/cdm.cc', 'sensors/ar0231.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc']) 'cameras/cdm.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc'])
env.Program('camerad', ['main.cc', camera_obj], LIBS=libs) env.Program('camerad', ['main.cc', camera_obj], LIBS=libs)
if GetOption("extras") and arch == "x86_64": if GetOption("extras") and arch == "x86_64":

@ -13,7 +13,7 @@ typedef enum {
ISP_BPS_PROCESSED, // fully processed image through the BPS ISP_BPS_PROCESSED, // fully processed image through the BPS
} SpectraOutputType; } SpectraOutputType;
// For the comma 3/3X three camera platform // For the comma 3X three camera platform
struct CameraConfig { struct CameraConfig {
int camera_num; int camera_num;

@ -1004,8 +1004,7 @@ bool SpectraCamera::openSensor() {
}; };
// Figure out which sensor we have // Figure out which sensor we have
if (!init_sensor_lambda(new AR0231) && if (!init_sensor_lambda(new OX03C10) &&
!init_sensor_lambda(new OX03C10) &&
!init_sensor_lambda(new OS04C10)) { !init_sensor_lambda(new OS04C10)) {
LOGE("** sensor %d FAILED bringup, disabling", cc.camera_num); LOGE("** sensor %d FAILED bringup, disabling", cc.camera_num);
enabled = false; enabled = false;

@ -1,136 +0,0 @@
#include <cassert>
#include <cmath>
#include "system/camerad/sensors/sensor.h"
namespace {
const size_t AR0231_REGISTERS_HEIGHT = 2;
// TODO: this extra height is universal and doesn't apply per camera
const size_t AR0231_STATS_HEIGHT = 2 + 8;
const float sensor_analog_gains_AR0231[] = {
1.0 / 8.0, 2.0 / 8.0, 2.0 / 7.0, 3.0 / 7.0, // 0, 1, 2, 3
3.0 / 6.0, 4.0 / 6.0, 4.0 / 5.0, 5.0 / 5.0, // 4, 5, 6, 7
5.0 / 4.0, 6.0 / 4.0, 6.0 / 3.0, 7.0 / 3.0, // 8, 9, 10, 11
7.0 / 2.0, 8.0 / 2.0, 8.0 / 1.0}; // 12, 13, 14, 15 = bypass
} // namespace
AR0231::AR0231() {
image_sensor = cereal::FrameData::ImageSensor::AR0231;
bayer_pattern = CAM_ISP_PATTERN_BAYER_GRGRGR;
pixel_size_mm = 0.003;
data_word = true;
frame_width = 1928;
frame_height = 1208;
frame_stride = (frame_width * 12 / 8) + 4;
extra_height = AR0231_REGISTERS_HEIGHT + AR0231_STATS_HEIGHT;
registers_offset = 0;
frame_offset = AR0231_REGISTERS_HEIGHT;
stats_offset = AR0231_REGISTERS_HEIGHT + frame_height;
start_reg_array.assign(std::begin(start_reg_array_ar0231), std::end(start_reg_array_ar0231));
init_reg_array.assign(std::begin(init_array_ar0231), std::end(init_array_ar0231));
probe_reg_addr = 0x3000;
probe_expected_data = 0x354;
bits_per_pixel = 12;
mipi_format = CAM_FORMAT_MIPI_RAW_12;
frame_data_type = 0x12; // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead
mclk_frequency = 19200000; //Hz
readout_time_ns = 22850000;
dc_gain_factor = 2.5;
dc_gain_min_weight = 0;
dc_gain_max_weight = 1;
dc_gain_on_grey = 0.2;
dc_gain_off_grey = 0.3;
exposure_time_min = 2; // with HDR, fastest ss
exposure_time_max = 0x0855; // with HDR, slowest ss, 40ms
analog_gain_min_idx = 0x1; // 0.25x
analog_gain_rec_idx = 0x6; // 0.8x
analog_gain_max_idx = 0xD; // 4.0x
analog_gain_cost_delta = 0;
analog_gain_cost_low = 0.1;
analog_gain_cost_high = 5.0;
for (int i = 0; i <= analog_gain_max_idx; i++) {
sensor_analog_gains[i] = sensor_analog_gains_AR0231[i];
}
min_ev = exposure_time_min * sensor_analog_gains[analog_gain_min_idx];
max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx];
target_grey_factor = 1.0;
black_level = 168;
color_correct_matrix = {
0x000000af, 0x00000ff9, 0x00000fd8,
0x00000fbc, 0x000000bb, 0x00000009,
0x00000fb6, 0x00000fe0, 0x000000ea,
};
for (int i = 0; i < 65; i++) {
float fx = i / 64.0;
const float gamma_k = 0.75;
const float gamma_b = 0.125;
const float mp = 0.01; // ideally midpoint should be adaptive
const float rk = 9 - 100*mp;
// poly approximation for s curve
fx = (fx > mp) ?
((rk * (fx-mp) * (1-(gamma_k*mp+gamma_b)) * (1+1/(rk*(1-mp))) / (1+rk*(fx-mp))) + gamma_k*mp + gamma_b) :
((rk * (fx-mp) * (gamma_k*mp+gamma_b) * (1+1/(rk*mp)) / (1-rk*(fx-mp))) + gamma_k*mp + gamma_b);
gamma_lut_rgb.push_back((uint32_t)(fx*1023.0 + 0.5));
}
prepare_gamma_lut();
linearization_lut = {
0x02000000, 0x02000000, 0x02000000, 0x02000000,
0x020007ff, 0x020007ff, 0x020007ff, 0x020007ff,
0x02000bff, 0x02000bff, 0x02000bff, 0x02000bff,
0x020017ff, 0x020017ff, 0x020017ff, 0x020017ff,
0x02001bff, 0x02001bff, 0x02001bff, 0x02001bff,
0x020023ff, 0x020023ff, 0x020023ff, 0x020023ff,
0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff,
0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff,
0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff,
};
linearization_pts = {0x07ff0bff, 0x17ff1bff, 0x23ff3fff, 0x3fff3fff};
vignetting_lut = {
0x00eaa755, 0x00cf2679, 0x00bc05e0, 0x00acc566, 0x00a1450a, 0x009984cc, 0x0095a4ad, 0x009584ac, 0x009944ca, 0x00a0c506, 0x00ac0560, 0x00bb25d9, 0x00ce2671, 0x00e90748, 0x01112889, 0x014a2a51, 0x01984cc2,
0x00db06d8, 0x00c30618, 0x00afe57f, 0x00a0a505, 0x009524a9, 0x008d646b, 0x0089844c, 0x0089644b, 0x008d2469, 0x0094a4a5, 0x009fe4ff, 0x00af0578, 0x00c20610, 0x00d986cc, 0x00fda7ed, 0x01320990, 0x017aebd7,
0x00d1868c, 0x00baa5d5, 0x00a7853c, 0x009844c2, 0x008cc466, 0x0085a42d, 0x0083641b, 0x0083641b, 0x0085842c, 0x008c4462, 0x0097a4bd, 0x00a6c536, 0x00b9a5cd, 0x00d06683, 0x00f1678b, 0x01226913, 0x0167ab3d,
0x00cd0668, 0x00b625b1, 0x00a30518, 0x0093c49e, 0x00884442, 0x00830418, 0x0080e407, 0x0080c406, 0x0082e417, 0x0087c43e, 0x00932499, 0x00a22511, 0x00b525a9, 0x00cbe65f, 0x00eb0758, 0x011a68d3, 0x015daaed,
0x00cc4662, 0x00b565ab, 0x00a24512, 0x00930498, 0x0087843c, 0x0082a415, 0x00806403, 0x00806403, 0x00828414, 0x00870438, 0x00926493, 0x00a1850c, 0x00b465a3, 0x00cb2659, 0x00ea2751, 0x011928c9, 0x015c2ae1,
0x00cf667b, 0x00b885c4, 0x00a5652b, 0x009624b1, 0x008aa455, 0x00846423, 0x00822411, 0x00822411, 0x00844422, 0x008a2451, 0x009564ab, 0x00a48524, 0x00b785bc, 0x00ce4672, 0x00ee6773, 0x011e88f4, 0x0162eb17,
0x00d6c6b6, 0x00bf65fb, 0x00ac4562, 0x009d04e8, 0x0091848c, 0x0089c44e, 0x00862431, 0x00860430, 0x0089844c, 0x00910488, 0x009c64e3, 0x00ab655b, 0x00be65f3, 0x00d566ab, 0x00f847c2, 0x012b2959, 0x01726b93,
0x00e3e71f, 0x00ca0650, 0x00b705b8, 0x00a7a53d, 0x009c24e1, 0x009484a4, 0x00908484, 0x00908484, 0x009424a1, 0x009bc4de, 0x00a70538, 0x00b625b1, 0x00c90648, 0x00e26713, 0x0108e847, 0x013fe9ff, 0x018bcc5e,
0x00f807c0, 0x00d966cb, 0x00c5862c, 0x00b625b1, 0x00aaa555, 0x00a30518, 0x009f04f8, 0x009f04f8, 0x00a2a515, 0x00aa2551, 0x00b585ac, 0x00c4a625, 0x00d846c2, 0x00f647b2, 0x0121a90d, 0x015e4af2, 0x01b8cdc6,
0x011548aa, 0x00f1678b, 0x00d886c4, 0x00c86643, 0x00bce5e7, 0x00b545aa, 0x00b1658b, 0x00b1458a, 0x00b505a8, 0x00bc85e4, 0x00c7c63e, 0x00d786bc, 0x00efe77f, 0x0113489a, 0x0144ea27, 0x01888c44, 0x01fdcfee,
0x013e49f2, 0x0113e89f, 0x00f5a7ad, 0x00e0c706, 0x00d30698, 0x00cb665b, 0x00c7663b, 0x00c7663b, 0x00cb0658, 0x00d2a695, 0x00dfe6ff, 0x00f467a3, 0x01122891, 0x013be9df, 0x01750ba8, 0x01cfae7d, 0x025912c8,
0x01766bb3, 0x01446a23, 0x011fc8fe, 0x0105e82f, 0x00f467a3, 0x00e9874c, 0x00e46723, 0x00e44722, 0x00e92749, 0x00f3a79d, 0x0104c826, 0x011e48f2, 0x01424a12, 0x01738b9c, 0x01bf6dfb, 0x023611b0, 0x02ced676,
0x01cf8e7c, 0x01866c33, 0x015aaad5, 0x013ae9d7, 0x01250928, 0x011768bb, 0x0110a885, 0x01108884, 0x0116e8b7, 0x01242921, 0x0139a9cd, 0x0158eac7, 0x01840c20, 0x01cb0e58, 0x0233719b, 0x02b9d5ce, 0x03645b22,
};
}
std::vector<i2c_random_wr_payload> AR0231::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const {
uint16_t analog_gain_reg = 0xFF00 | (new_exp_g << 4) | new_exp_g;
return {
{0x3366, analog_gain_reg},
{0x3362, (uint16_t)(dc_gain_enabled ? 0x1 : 0x0)},
{0x3012, (uint16_t)exposure_time},
};
}
int AR0231::getSlaveAddress(int port) const {
assert(port >= 0 && port <= 2);
return (int[]){0x20, 0x30, 0x20}[port];
}
float AR0231::getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const {
// Cost of ev diff
float score = std::abs(desired_ev - (exp_t * exp_gain)) * 10;
// Cost of absolute gain
float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low;
score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m;
// Cost of changing gain
score += std::abs(exp_g_idx - gain_idx) * (score + 1.0) / 10.0;
return score;
}

@ -1,34 +0,0 @@
#if SENSOR_ID == 1
#define VIGNETTE_PROFILE_8DT0MM
#define BIT_DEPTH 12
#define PV_MAX 4096
#define BLACK_LVL 168
float4 normalize_pv(int4 parsed, float vignette_factor) {
float4 pv = (convert_float4(parsed) - BLACK_LVL) / (PV_MAX - BLACK_LVL);
return clamp(pv*vignette_factor, 0.0, 1.0);
}
float3 color_correct(float3 rgb) {
float3 corrected = rgb.x * (float3)(1.82717181, -0.31231438, 0.07307673);
corrected += rgb.y * (float3)(-0.5743977, 1.36858544, -0.53183455);
corrected += rgb.z * (float3)(-0.25277411, -0.05627105, 1.45875782);
return corrected;
}
float3 apply_gamma(float3 rgb, int expo_time) {
// tone mapping params
const float gamma_k = 0.75;
const float gamma_b = 0.125;
const float mp = 0.01; // ideally midpoint should be adaptive
const float rk = 9 - 100*mp;
// poly approximation for s curve
return (rgb > mp) ?
((rk * (rgb-mp) * (1-(gamma_k*mp+gamma_b)) * (1+1/(rk*(1-mp))) / (1+rk*(rgb-mp))) + gamma_k*mp + gamma_b) :
((rk * (rgb-mp) * (gamma_k*mp+gamma_b) * (1+1/(rk*mp)) / (1-rk*(rgb-mp))) + gamma_k*mp + gamma_b);
}
#endif

@ -1,121 +0,0 @@
#pragma once
const struct i2c_random_wr_payload start_reg_array_ar0231[] = {{0x301A, 0x91C}};
const struct i2c_random_wr_payload stop_reg_array_ar0231[] = {{0x301A, 0x918}};
const struct i2c_random_wr_payload init_array_ar0231[] = {
{0x301A, 0x0018}, // RESET_REGISTER
// **NOTE**: if this is changed, readout_time_ns must be updated in the Sensor config
// CLOCK Settings
// input clock is 19.2 / 2 * 0x37 = 528 MHz
// pixclk is 528 / 6 = 88 MHz
// full roll time is 1000/(PIXCLK/(LINE_LENGTH_PCK*FRAME_LENGTH_LINES)) = 39.99 ms
// img roll time is 1000/(PIXCLK/(LINE_LENGTH_PCK*Y_OUTPUT_CONTROL)) = 22.85 ms
{0x302A, 0x0006}, // VT_PIX_CLK_DIV
{0x302C, 0x0001}, // VT_SYS_CLK_DIV
{0x302E, 0x0002}, // PRE_PLL_CLK_DIV
{0x3030, 0x0037}, // PLL_MULTIPLIER
{0x3036, 0x000C}, // OP_PIX_CLK_DIV
{0x3038, 0x0001}, // OP_SYS_CLK_DIV
// FORMAT
{0x3040, 0xC000}, // READ_MODE
{0x3004, 0x0000}, // X_ADDR_START_
{0x3008, 0x0787}, // X_ADDR_END_
{0x3002, 0x0000}, // Y_ADDR_START_
{0x3006, 0x04B7}, // Y_ADDR_END_
{0x3032, 0x0000}, // SCALING_MODE
{0x30A2, 0x0001}, // X_ODD_INC_
{0x30A6, 0x0001}, // Y_ODD_INC_
{0x3402, 0x0788}, // X_OUTPUT_CONTROL
{0x3404, 0x04B8}, // Y_OUTPUT_CONTROL
{0x3064, 0x1982}, // SMIA_TEST
{0x30BA, 0x11F2}, // DIGITAL_CTRL
// Enable external trigger and disable GPIO outputs
{0x30CE, 0x0120}, // SLAVE_SH_SYNC_MODE | FRAME_START_MODE
{0x340A, 0xE0}, // GPIO3_INPUT_DISABLE | GPIO2_INPUT_DISABLE | GPIO1_INPUT_DISABLE
{0x340C, 0x802}, // GPIO_HIDRV_EN | GPIO0_ISEL=2
// Readout timing
{0x300C, 0x0672}, // LINE_LENGTH_PCK (valid for 3-exposure HDR)
{0x300A, 0x0855}, // FRAME_LENGTH_LINES
{0x3042, 0x0000}, // EXTRA_DELAY
// Readout Settings
{0x31AE, 0x0204}, // SERIAL_FORMAT, 4-lane MIPI
{0x31AC, 0x0C0C}, // DATA_FORMAT_BITS, 12 -> 12
{0x3342, 0x1212}, // MIPI_F1_PDT_EDT
{0x3346, 0x1212}, // MIPI_F2_PDT_EDT
{0x334A, 0x1212}, // MIPI_F3_PDT_EDT
{0x334E, 0x1212}, // MIPI_F4_PDT_EDT
{0x3344, 0x0011}, // MIPI_F1_VDT_VC
{0x3348, 0x0111}, // MIPI_F2_VDT_VC
{0x334C, 0x0211}, // MIPI_F3_VDT_VC
{0x3350, 0x0311}, // MIPI_F4_VDT_VC
{0x31B0, 0x0053}, // FRAME_PREAMBLE
{0x31B2, 0x003B}, // LINE_PREAMBLE
{0x301A, 0x001C}, // RESET_REGISTER
// Noise Corrections
{0x3092, 0x0C24}, // ROW_NOISE_CONTROL
{0x337A, 0x0C80}, // DBLC_SCALE0
{0x3370, 0x03B1}, // DBLC
{0x3044, 0x0400}, // DARK_CONTROL
// Enable temperature sensor
{0x30B4, 0x0007}, // TEMPSENS0_CTRL_REG
{0x30B8, 0x0007}, // TEMPSENS1_CTRL_REG
// Enable dead pixel correction using
// the 1D line correction scheme
{0x31E0, 0x0003},
// HDR Settings
{0x3082, 0x0004}, // OPERATION_MODE_CTRL
{0x3238, 0x0444}, // EXPOSURE_RATIO
{0x1008, 0x0361}, // FINE_INTEGRATION_TIME_MIN
{0x100C, 0x0589}, // FINE_INTEGRATION_TIME2_MIN
{0x100E, 0x07B1}, // FINE_INTEGRATION_TIME3_MIN
{0x1010, 0x0139}, // FINE_INTEGRATION_TIME4_MIN
// TODO: do these have to be lower than LINE_LENGTH_PCK?
{0x3014, 0x08CB}, // FINE_INTEGRATION_TIME_
{0x321E, 0x0894}, // FINE_INTEGRATION_TIME2
{0x31D0, 0x0000}, // COMPANDING, no good in 10 bit?
{0x33DA, 0x0000}, // COMPANDING
{0x318E, 0x0200}, // PRE_HDR_GAIN_EN
// DLO Settings
{0x3100, 0x4000}, // DLO_CONTROL0
{0x3280, 0x0CCC}, // T1 G1
{0x3282, 0x0CCC}, // T1 R
{0x3284, 0x0CCC}, // T1 B
{0x3286, 0x0CCC}, // T1 G2
{0x3288, 0x0FA0}, // T2 G1
{0x328A, 0x0FA0}, // T2 R
{0x328C, 0x0FA0}, // T2 B
{0x328E, 0x0FA0}, // T2 G2
// Initial Gains
{0x3022, 0x0001}, // GROUPED_PARAMETER_HOLD_
{0x3366, 0xFF77}, // ANALOG_GAIN (1x)
{0x3060, 0x3333}, // ANALOG_COLOR_GAIN
{0x3362, 0x0000}, // DC GAIN
{0x305A, 0x00F8}, // red gain
{0x3058, 0x0122}, // blue gain
{0x3056, 0x009A}, // g1 gain
{0x305C, 0x009A}, // g2 gain
{0x3022, 0x0000}, // GROUPED_PARAMETER_HOLD_
// Initial Integration Time
{0x3012, 0x0005},
};

@ -1,58 +0,0 @@
#if SENSOR_ID == 3
#define BGGR
#define VIGNETTE_PROFILE_4DT6MM
#define BIT_DEPTH 12
#define PV_MAX10 1023
#define PV_MAX12 4095
#define PV_MAX16 65536 // gamma curve is calibrated to 16bit
#define BLACK_LVL 48
float combine_dual_pvs(float lv, float sv, int expo_time) {
float svc = fmax(sv * expo_time, (float)(64 * (PV_MAX10 - BLACK_LVL)));
float svd = sv * fmin(expo_time, 8.0) / 8;
if (expo_time > 64) {
if (lv < PV_MAX10 - BLACK_LVL) {
return lv / (PV_MAX16 - BLACK_LVL);
} else {
return (svc / 64) / (PV_MAX16 - BLACK_LVL);
}
} else {
if (lv > 32) {
return (lv * 64 / fmax(expo_time, 8.0)) / (PV_MAX16 - BLACK_LVL);
} else {
return svd / (PV_MAX16 - BLACK_LVL);
}
}
}
float4 normalize_pv_hdr(int4 parsed, int4 short_parsed, float vignette_factor, int expo_time) {
float4 pl = convert_float4(parsed - BLACK_LVL);
float4 ps = convert_float4(short_parsed - BLACK_LVL);
float4 pv;
pv.s0 = combine_dual_pvs(pl.s0, ps.s0, expo_time);
pv.s1 = combine_dual_pvs(pl.s1, ps.s1, expo_time);
pv.s2 = combine_dual_pvs(pl.s2, ps.s2, expo_time);
pv.s3 = combine_dual_pvs(pl.s3, ps.s3, expo_time);
return clamp(pv*vignette_factor, 0.0, 1.0);
}
float4 normalize_pv(int4 parsed, float vignette_factor) {
float4 pv = (convert_float4(parsed) - BLACK_LVL) / (PV_MAX12 - BLACK_LVL);
return clamp(pv*vignette_factor, 0.0, 1.0);
}
float3 color_correct(float3 rgb) {
float3 corrected = rgb.x * (float3)(1.55361989, -0.268894615, -0.000593219);
corrected += rgb.y * (float3)(-0.421217301, 1.51883144, -0.69760146);
corrected += rgb.z * (float3)(-0.132402589, -0.249936825, 1.69819468);
return corrected;
}
float3 apply_gamma(float3 rgb, int expo_time) {
return (10 * rgb) / (1 + 9 * rgb);
}
#endif

@ -1,47 +0,0 @@
#if SENSOR_ID == 2
#define VIGNETTE_PROFILE_8DT0MM
#define BIT_DEPTH 12
#define BLACK_LVL 64
float ox_lut_func(int x) {
if (x < 512) {
return x * 5.94873e-8;
} else if (512 <= x && x < 768) {
return 3.0458e-05 + (x-512) * 1.19913e-7;
} else if (768 <= x && x < 1536) {
return 6.1154e-05 + (x-768) * 2.38493e-7;
} else if (1536 <= x && x < 1792) {
return 0.0002448 + (x-1536) * 9.56930e-7;
} else if (1792 <= x && x < 2048) {
return 0.00048977 + (x-1792) * 1.91441e-6;
} else if (2048 <= x && x < 2304) {
return 0.00097984 + (x-2048) * 3.82937e-6;
} else if (2304 <= x && x < 2560) {
return 0.0019601 + (x-2304) * 7.659055e-6;
} else if (2560 <= x && x < 2816) {
return 0.0039207 + (x-2560) * 1.525e-5;
} else {
return 0.0078421 + (exp((x-2816)/273.0) - 1) * 0.0092421;
}
}
float4 normalize_pv(int4 parsed, float vignette_factor) {
// PWL
float4 pv = {ox_lut_func(parsed.s0), ox_lut_func(parsed.s1), ox_lut_func(parsed.s2), ox_lut_func(parsed.s3)};
return clamp(pv*vignette_factor*256.0, 0.0, 1.0);
}
float3 color_correct(float3 rgb) {
float3 corrected = rgb.x * (float3)(1.5664815, -0.29808738, -0.03973474);
corrected += rgb.y * (float3)(-0.48672447, 1.41914433, -0.40295248);
corrected += rgb.z * (float3)(-0.07975703, -0.12105695, 1.44268722);
return corrected;
}
float3 apply_gamma(float3 rgb, int expo_time) {
return -0.507089*exp(-12.54124638*rgb) + 0.9655*powr(rgb, 0.5) - 0.472597*rgb + 0.507089;
}
#endif

@ -10,7 +10,6 @@
#include "media/cam_sensor.h" #include "media/cam_sensor.h"
#include "cereal/gen/cpp/log.capnp.h" #include "cereal/gen/cpp/log.capnp.h"
#include "system/camerad/sensors/ar0231_registers.h"
#include "system/camerad/sensors/ox03c10_registers.h" #include "system/camerad/sensors/ox03c10_registers.h"
#include "system/camerad/sensors/os04c10_registers.h" #include "system/camerad/sensors/os04c10_registers.h"
@ -88,17 +87,6 @@ public:
}; };
}; };
class AR0231 : public SensorInfo {
public:
AR0231();
std::vector<i2c_random_wr_payload> getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const override;
float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const override;
int getSlaveAddress(int port) const override;
private:
mutable std::map<uint16_t, std::pair<int, int>> ar0231_register_lut;
};
class OX03C10 : public SensorInfo { class OX03C10 : public SensorInfo {
public: public:
OX03C10(); OX03C10();

@ -65,6 +65,10 @@ class ThermalConfig:
return ret return ret
class LPABase(ABC): class LPABase(ABC):
@abstractmethod
def bootstrap(self) -> None:
pass
@abstractmethod @abstractmethod
def list_profiles(self) -> list[Profile]: def list_profiles(self) -> list[Profile]:
pass pass
@ -89,6 +93,9 @@ class LPABase(ABC):
def switch_profile(self, iccid: str) -> None: def switch_profile(self, iccid: str) -> None:
pass pass
def is_comma_profile(self, iccid: str) -> bool:
return any(iccid.startswith(prefix) for prefix in ('8985235',))
class HardwareBase(ABC): class HardwareBase(ABC):
@staticmethod @staticmethod
def get_cmdline() -> dict[str, str]: def get_cmdline() -> dict[str, str]:

@ -3,10 +3,32 @@
import argparse import argparse
import time import time
from openpilot.system.hardware import HARDWARE from openpilot.system.hardware import HARDWARE
from openpilot.system.hardware.base import LPABase
def bootstrap(lpa: LPABase) -> None:
print('┌──────────────────────────────────────────────────────────────────────────────┐')
print('│ WARNING, PLEASE READ BEFORE PROCEEDING │')
print('│ │')
print('│ this is an irreversible operation that will remove the comma-provisioned │')
print('│ profile. │')
print('│ │')
print('│ after this operation, you must purchase a new eSIM from comma in order to │')
print('│ use the comma prime subscription again. │')
print('└──────────────────────────────────────────────────────────────────────────────┘')
print()
for severity in ('sure', '100% sure'):
print(f'are you {severity} you want to proceed? (y/N) ', end='')
confirm = input()
if confirm != 'y':
print('aborting')
exit(0)
lpa.bootstrap()
if __name__ == '__main__': if __name__ == '__main__':
parser = argparse.ArgumentParser(prog='esim.py', description='manage eSIM profiles on your comma device', epilog='comma.ai') parser = argparse.ArgumentParser(prog='esim.py', description='manage eSIM profiles on your comma device', epilog='comma.ai')
parser.add_argument('--bootstrap', action='store_true', help='bootstrap the eUICC (required before downloading profiles)')
parser.add_argument('--backend', choices=['qmi', 'at'], default='qmi', help='use the specified backend, defaults to qmi') parser.add_argument('--backend', choices=['qmi', 'at'], default='qmi', help='use the specified backend, defaults to qmi')
parser.add_argument('--switch', metavar='iccid', help='switch to profile') parser.add_argument('--switch', metavar='iccid', help='switch to profile')
parser.add_argument('--delete', metavar='iccid', help='delete profile (warning: this cannot be undone)') parser.add_argument('--delete', metavar='iccid', help='delete profile (warning: this cannot be undone)')
@ -16,7 +38,10 @@ if __name__ == '__main__':
mutated = False mutated = False
lpa = HARDWARE.get_sim_lpa() lpa = HARDWARE.get_sim_lpa()
if args.switch: if args.bootstrap:
bootstrap(lpa)
mutated = True
elif args.switch:
lpa.switch_profile(args.switch) lpa.switch_profile(args.switch)
mutated = True mutated = True
elif args.delete: elif args.delete:

@ -6,7 +6,6 @@ import struct
import threading import threading
import time import time
from collections import OrderedDict, namedtuple from collections import OrderedDict, namedtuple
from pathlib import Path
import psutil import psutil
@ -334,12 +333,6 @@ def hardware_thread(end_event, hw_queue) -> None:
# to make a different decision in your software # to make a different decision in your software
startup_conditions["registered_device"] = PC or (params.get("DongleId") != UNREGISTERED_DONGLE_ID) startup_conditions["registered_device"] = PC or (params.get("DongleId") != UNREGISTERED_DONGLE_ID)
# TODO: this should move to TICI.initialize_hardware, but we currently can't import params there
if TICI and HARDWARE.get_device_type() == "tici":
if not os.path.isfile("/persist/comma/living-in-the-moment"):
if not Path("/data/media").is_mount():
set_offroad_alert_if_changed("Offroad_StorageMissing", True)
# Handle offroad/onroad transition # Handle offroad/onroad transition
should_start = all(onroad_conditions.values()) should_start = all(onroad_conditions.values())
if started_ts is None: if started_ts is None:

@ -23,14 +23,14 @@
}, },
{ {
"name": "abl", "name": "abl",
"url": "https://commadist.azureedge.net/agnosupdate/abl-32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/abl-556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee.img.xz",
"hash": "32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6", "hash": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee",
"hash_raw": "32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6", "hash_raw": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee",
"size": 274432, "size": 274432,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6" "ondevice_hash": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee"
}, },
{ {
"name": "aop", "name": "aop",
@ -56,28 +56,28 @@
}, },
{ {
"name": "boot", "name": "boot",
"url": "https://commadist.azureedge.net/agnosupdate/boot-0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/boot-3e26a0d330a1be1614a5c25cae238ca5d01c1be90802ad296c805c3bcbad0e7a.img.xz",
"hash": "0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4", "hash": "3e26a0d330a1be1614a5c25cae238ca5d01c1be90802ad296c805c3bcbad0e7a",
"hash_raw": "0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4", "hash_raw": "3e26a0d330a1be1614a5c25cae238ca5d01c1be90802ad296c805c3bcbad0e7a",
"size": 18515968, "size": 18515968,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "492ae27f569e8db457c79d0e358a7a6297d1a1c685c2b1ae6deba7315d3a6cb0" "ondevice_hash": "41d693d7e752c04210b4f8d68015d2367ee83e1cd54cc7b0aca3b79b4855e6b1"
}, },
{ {
"name": "system", "name": "system",
"url": "https://commadist.azureedge.net/agnosupdate/system-e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/system-4d0c7005e242fc757adbefd43b44ab2e78be53ca5145fceb160cc32ecf8d6cc3.img.xz",
"hash": "1468d50b7ad0fda0f04074755d21e786e3b1b6ca5dd5b17eb2608202025e6126", "hash": "3596cd5d8a51dabcdd75c29f9317ca3dad9036b1083630ad719eaf584fdb1ce9",
"hash_raw": "e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087", "hash_raw": "4d0c7005e242fc757adbefd43b44ab2e78be53ca5145fceb160cc32ecf8d6cc3",
"size": 5368709120, "size": 5368709120,
"sparse": true, "sparse": true,
"full_check": false, "full_check": false,
"has_ab": true, "has_ab": true,
"ondevice_hash": "242aa5adad1c04e1398e00e2440d1babf962022eb12b89adf2e60ee3068946e7", "ondevice_hash": "32cdbc0ce176e0ea92944e53be875c12374512fa09b6041e42e683519d36591e",
"alt": { "alt": {
"hash": "e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087", "hash": "4d0c7005e242fc757adbefd43b44ab2e78be53ca5145fceb160cc32ecf8d6cc3",
"url": "https://commadist.azureedge.net/agnosupdate/system-e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087.img", "url": "https://commadist.azureedge.net/agnosupdate/system-4d0c7005e242fc757adbefd43b44ab2e78be53ca5145fceb160cc32ecf8d6cc3.img",
"size": 5368709120 "size": 5368709120
} }
} }

@ -152,14 +152,14 @@
}, },
{ {
"name": "abl", "name": "abl",
"url": "https://commadist.azureedge.net/agnosupdate/abl-32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/abl-556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee.img.xz",
"hash": "32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6", "hash": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee",
"hash_raw": "32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6", "hash_raw": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee",
"size": 274432, "size": 274432,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6" "ondevice_hash": "556bbb4ed1c671402b217bd2f3c07edce4f88b0bbd64e92241b82e396aa9ebee"
}, },
{ {
"name": "aop", "name": "aop",
@ -339,62 +339,62 @@
}, },
{ {
"name": "boot", "name": "boot",
"url": "https://commadist.azureedge.net/agnosupdate/boot-0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/boot-3e26a0d330a1be1614a5c25cae238ca5d01c1be90802ad296c805c3bcbad0e7a.img.xz",
"hash": "0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4", "hash": "3e26a0d330a1be1614a5c25cae238ca5d01c1be90802ad296c805c3bcbad0e7a",
"hash_raw": "0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4", "hash_raw": "3e26a0d330a1be1614a5c25cae238ca5d01c1be90802ad296c805c3bcbad0e7a",
"size": 18515968, "size": 18515968,
"sparse": false, "sparse": false,
"full_check": true, "full_check": true,
"has_ab": true, "has_ab": true,
"ondevice_hash": "492ae27f569e8db457c79d0e358a7a6297d1a1c685c2b1ae6deba7315d3a6cb0" "ondevice_hash": "41d693d7e752c04210b4f8d68015d2367ee83e1cd54cc7b0aca3b79b4855e6b1"
}, },
{ {
"name": "system", "name": "system",
"url": "https://commadist.azureedge.net/agnosupdate/system-e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/system-4d0c7005e242fc757adbefd43b44ab2e78be53ca5145fceb160cc32ecf8d6cc3.img.xz",
"hash": "1468d50b7ad0fda0f04074755d21e786e3b1b6ca5dd5b17eb2608202025e6126", "hash": "3596cd5d8a51dabcdd75c29f9317ca3dad9036b1083630ad719eaf584fdb1ce9",
"hash_raw": "e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087", "hash_raw": "4d0c7005e242fc757adbefd43b44ab2e78be53ca5145fceb160cc32ecf8d6cc3",
"size": 5368709120, "size": 5368709120,
"sparse": true, "sparse": true,
"full_check": false, "full_check": false,
"has_ab": true, "has_ab": true,
"ondevice_hash": "242aa5adad1c04e1398e00e2440d1babf962022eb12b89adf2e60ee3068946e7", "ondevice_hash": "32cdbc0ce176e0ea92944e53be875c12374512fa09b6041e42e683519d36591e",
"alt": { "alt": {
"hash": "e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087", "hash": "4d0c7005e242fc757adbefd43b44ab2e78be53ca5145fceb160cc32ecf8d6cc3",
"url": "https://commadist.azureedge.net/agnosupdate/system-e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087.img", "url": "https://commadist.azureedge.net/agnosupdate/system-4d0c7005e242fc757adbefd43b44ab2e78be53ca5145fceb160cc32ecf8d6cc3.img",
"size": 5368709120 "size": 5368709120
} }
}, },
{ {
"name": "userdata_90", "name": "userdata_90",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_90-602d5103cba97e1b07f76508d5febb47cfc4463a7e31bd20e461b55c801feb0a.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/userdata_90-a3695e6b4bade3dd9c2711cd92e93e9ac7744207c2af03b78f0b9a17e89d357f.img.xz",
"hash": "6a11d448bac50467791809339051eed2894aae971c37bf6284b3b972a99ba3ac", "hash": "eeb50afb13973d7e54013fdb3ce0f4f396b8608c8325442966cad6b67e39a8d9",
"hash_raw": "602d5103cba97e1b07f76508d5febb47cfc4463a7e31bd20e461b55c801feb0a", "hash_raw": "a3695e6b4bade3dd9c2711cd92e93e9ac7744207c2af03b78f0b9a17e89d357f",
"size": 96636764160, "size": 96636764160,
"sparse": true, "sparse": true,
"full_check": true, "full_check": true,
"has_ab": false, "has_ab": false,
"ondevice_hash": "e014d92940a696bf8582807259820ab73948b950656ed83a45da738f26083705" "ondevice_hash": "537088b516805b32b1b4ad176e7f3fc6bc828e296398ce65cbf5f6150fb1a26f"
}, },
{ {
"name": "userdata_89", "name": "userdata_89",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_89-4d7f6d12a5557eb6e3cbff9a4cd595677456fdfddcc879eddcea96a43a9d8b48.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/userdata_89-cbe9979b42b265c9e25a50e876faf5b592fe175aeb5936f2a97b345a6d4e53f5.img.xz",
"hash": "748e31a5fc01fc256c012e359c3382d1f98cce98feafe8ecc0fca3e47caef116", "hash": "9456a8b117736e6f8eb35cc97fc62ddc8255f38a1be5959a6911498d6aaee08d",
"hash_raw": "4d7f6d12a5557eb6e3cbff9a4cd595677456fdfddcc879eddcea96a43a9d8b48", "hash_raw": "cbe9979b42b265c9e25a50e876faf5b592fe175aeb5936f2a97b345a6d4e53f5",
"size": 95563022336, "size": 95563022336,
"sparse": true, "sparse": true,
"full_check": true, "full_check": true,
"has_ab": false, "has_ab": false,
"ondevice_hash": "c181b93050787adcfef730c086bcb780f28508d84e6376d9b80d37e5dc02b55e" "ondevice_hash": "9e7293cf9a377cb2f3477698e7143e6085a42f7355d7eace5bf9e590992941a8"
}, },
{ {
"name": "userdata_30", "name": "userdata_30",
"url": "https://commadist.azureedge.net/agnosupdate/userdata_30-80a76c8e56bbd7536fd5e87e8daa12984e2960db4edeb1f83229b2baeecc4668.img.xz", "url": "https://commadist.azureedge.net/agnosupdate/userdata_30-0b25bb660f1c0c4475fc22a32a51cd32bb980f55b95069e6ab56dd8e47f00c31.img.xz",
"hash": "09ff390e639e4373d772e1688d05a5ac77a573463ed1deeff86390686fa686f9", "hash": "6c5c98c0fec64355ead5dfc9c1902653b4ea9a071e7b968d1ccd36565082f6b7",
"hash_raw": "80a76c8e56bbd7536fd5e87e8daa12984e2960db4edeb1f83229b2baeecc4668", "hash_raw": "0b25bb660f1c0c4475fc22a32a51cd32bb980f55b95069e6ab56dd8e47f00c31",
"size": 32212254720, "size": 32212254720,
"sparse": true, "sparse": true,
"full_check": true, "full_check": true,
"has_ab": false, "has_ab": false,
"ondevice_hash": "2c01ab470c02121c721ff6afc25582437e821686207f3afef659387afb69c507" "ondevice_hash": "42b5c09a36866d9a52e78b038901669d5bebb02176c498ce11618f200bdfe6b5"
} }
] ]

@ -61,18 +61,6 @@ BASE_CONFIG = [
] ]
CONFIGS = { CONFIGS = {
"tici": [
AmpConfig("Right speaker output from right DAC", 0b1, 0x2C, 0, 0b11111111),
AmpConfig("Right Speaker Mixer Gain", 0b00, 0x2D, 2, 0b00001100),
AmpConfig("Right speaker output volume", 0x1c, 0x3E, 0, 0b00011111),
AmpConfig("DAI2 EQ enable", 0b1, 0x49, 1, 0b00000010),
*configs_from_eq_params(0x84, EQParams(0x274F, 0xC0FF, 0x3BF9, 0x0B3C, 0x1656)),
*configs_from_eq_params(0x8E, EQParams(0x1009, 0xC6BF, 0x2952, 0x1C97, 0x30DF)),
*configs_from_eq_params(0x98, EQParams(0x0F75, 0xCBE5, 0x0ED2, 0x2528, 0x3E42)),
*configs_from_eq_params(0xA2, EQParams(0x091F, 0x3D4C, 0xCE11, 0x1266, 0x2807)),
*configs_from_eq_params(0xAC, EQParams(0x0A9E, 0x3F20, 0xE573, 0x0A8B, 0x3A3B)),
],
"tizi": [ "tizi": [
AmpConfig("Left speaker output from left DAC", 0b1, 0x2B, 0, 0b11111111), AmpConfig("Left speaker output from left DAC", 0b1, 0x2B, 0, 0b11111111),
AmpConfig("Right speaker output from right DAC", 0b1, 0x2C, 0, 0b11111111), AmpConfig("Right speaker output from right DAC", 0b1, 0x2C, 0, 0b11111111),

@ -40,6 +40,7 @@ class TiciLPA(LPABase):
self._process_notifications() self._process_notifications()
def download_profile(self, qr: str, nickname: str | None = None) -> None: def download_profile(self, qr: str, nickname: str | None = None) -> None:
self._check_bootstrapped()
msgs = self._invoke('profile', 'download', '-a', qr) msgs = self._invoke('profile', 'download', '-a', qr)
self._validate_successful(msgs) self._validate_successful(msgs)
new_profile = next((m for m in msgs if m['payload']['message'] == 'es8p_meatadata_parse'), None) new_profile = next((m for m in msgs if m['payload']['message'] == 'es8p_meatadata_parse'), None)
@ -54,6 +55,7 @@ class TiciLPA(LPABase):
self._validate_successful(self._invoke('profile', 'nickname', iccid, nickname)) self._validate_successful(self._invoke('profile', 'nickname', iccid, nickname))
def switch_profile(self, iccid: str) -> None: def switch_profile(self, iccid: str) -> None:
self._check_bootstrapped()
self._validate_profile_exists(iccid) self._validate_profile_exists(iccid)
latest = self.get_active_profile() latest = self.get_active_profile()
if latest and latest.iccid == iccid: if latest and latest.iccid == iccid:
@ -61,6 +63,33 @@ class TiciLPA(LPABase):
self._validate_successful(self._invoke('profile', 'enable', iccid)) self._validate_successful(self._invoke('profile', 'enable', iccid))
self._process_notifications() self._process_notifications()
def bootstrap(self) -> None:
"""
find all comma-provisioned profiles and delete them. they conflict with user-provisioned profiles
and must be deleted.
**note**: this is a **very** destructive operation. you **must** purchase a new comma SIM in order
to use comma prime again.
"""
if self._is_bootstrapped():
return
for p in self.list_profiles():
if self.is_comma_profile(p.iccid):
self._disable_profile(p.iccid)
self.delete_profile(p.iccid)
def _disable_profile(self, iccid: str) -> None:
self._validate_successful(self._invoke('profile', 'disable', iccid))
self._process_notifications()
def _check_bootstrapped(self) -> None:
assert self._is_bootstrapped(), 'eUICC is not bootstrapped, please bootstrap before performing this operation'
def _is_bootstrapped(self) -> bool:
""" check if any comma provisioned profiles are on the eUICC """
return not any(self.is_comma_profile(iccid) for iccid in (p.iccid for p in self.list_profiles()))
def _invoke(self, *cmd: str): def _invoke(self, *cmd: str):
proc = subprocess.Popen(['sudo', '-E', 'lpac'] + list(cmd), stdout=subprocess.PIPE, stderr=subprocess.PIPE, env=self.env) proc = subprocess.Popen(['sudo', '-E', 'lpac'] + list(cmd), stdout=subprocess.PIPE, stderr=subprocess.PIPE, env=self.env)
try: try:

@ -425,9 +425,6 @@ class Tici(HardwareBase):
# pandad core # pandad core
affine_irq(3, "spi_geni") # SPI affine_irq(3, "spi_geni") # SPI
if "tici" in self.get_device_type():
affine_irq(3, "xhci-hcd:usb3") # aux panda USB (or potentially anything else on USB)
affine_irq(3, "xhci-hcd:usb1") # internal panda USB (also modem)
try: try:
pid = subprocess.check_output(["pgrep", "-f", "spi0"], encoding='utf8').strip() pid = subprocess.check_output(["pgrep", "-f", "spi0"], encoding='utf8').strip()
subprocess.call(["sudo", "chrt", "-f", "-p", "1", pid]) subprocess.call(["sudo", "chrt", "-f", "-p", "1", pid])
@ -446,22 +443,20 @@ class Tici(HardwareBase):
cmds = [] cmds = []
if self.get_device_type() in ("tici", "tizi"): if self.get_device_type() in ("tizi", ):
# clear out old blue prime initial APN # clear out old blue prime initial APN
os.system('mmcli -m any --3gpp-set-initial-eps-bearer-settings="apn="') os.system('mmcli -m any --3gpp-set-initial-eps-bearer-settings="apn="')
cmds += [ cmds += [
# SIM hot swap
'AT+QSIMDET=1,0',
'AT+QSIMSTAT=1',
# configure modem as data-centric # configure modem as data-centric
'AT+QNVW=5280,0,"0102000000000000"', 'AT+QNVW=5280,0,"0102000000000000"',
'AT+QNVFW="/nv/item_files/ims/IMS_enable",00', 'AT+QNVFW="/nv/item_files/ims/IMS_enable",00',
'AT+QNVFW="/nv/item_files/modem/mmode/ue_usage_setting",01', 'AT+QNVFW="/nv/item_files/modem/mmode/ue_usage_setting",01',
] ]
if self.get_device_type() == "tizi":
# SIM hot swap, not routed on tici
cmds += [
'AT+QSIMDET=1,0',
'AT+QSIMSTAT=1',
]
elif manufacturer == 'Cavli Inc.': elif manufacturer == 'Cavli Inc.':
cmds += [ cmds += [
'AT^SIMSWAP=1', # use SIM slot, instead of internal eSIM 'AT^SIMSWAP=1', # use SIM slot, instead of internal eSIM
@ -492,7 +487,7 @@ class Tici(HardwareBase):
# eSIM prime # eSIM prime
dest = "/etc/NetworkManager/system-connections/esim.nmconnection" dest = "/etc/NetworkManager/system-connections/esim.nmconnection"
if sim_id.startswith('8985235') and not os.path.exists(dest): if self.get_sim_lpa().is_comma_profile(sim_id) and not os.path.exists(dest):
with open(Path(__file__).parent/'esim.nmconnection') as f, tempfile.NamedTemporaryFile(mode='w') as tf: with open(Path(__file__).parent/'esim.nmconnection') as f, tempfile.NamedTemporaryFile(mode='w') as tf:
dat = f.read() dat = f.read()
dat = dat.replace("sim-id=", f"sim-id={sim_id}") dat = dat.replace("sim-id=", f"sim-id={sim_id}")
@ -503,6 +498,14 @@ class Tici(HardwareBase):
os.system(f"sudo cp {tf.name} {dest}") os.system(f"sudo cp {tf.name} {dest}")
os.system(f"sudo nmcli con load {dest}") os.system(f"sudo nmcli con load {dest}")
def reboot_modem(self):
modem = self.get_modem()
for state in (0, 1):
try:
modem.Command(f'AT+CFUN={state}', math.ceil(TIMEOUT), dbus_interface=MM_MODEM, timeout=TIMEOUT)
except Exception:
pass
def get_networks(self): def get_networks(self):
r = {} r = {}

@ -1,5 +1,3 @@
# TODO: these are also defined in a header
# GPIO pin definitions # GPIO pin definitions
class GPIO: class GPIO:
# both GPIO_STM_RST_N and GPIO_LTE_RST_N are misnamed, they are high to reset # both GPIO_STM_RST_N and GPIO_LTE_RST_N are misnamed, they are high to reset
@ -26,7 +24,4 @@ class GPIO:
CAM2_RSTN = 12 CAM2_RSTN = 12
# Sensor interrupts # Sensor interrupts
BMX055_ACCEL_INT = 21
BMX055_GYRO_INT = 23
BMX055_MAGN_INT = 87
LSM_INT = 84 LSM_INT = 84

@ -32,8 +32,8 @@ class Proc:
PROCS = [ PROCS = [
Proc(['camerad'], 1.75, msgs=['roadCameraState', 'wideRoadCameraState', 'driverCameraState']), Proc(['camerad'], 1.75, msgs=['roadCameraState', 'wideRoadCameraState', 'driverCameraState']),
Proc(['modeld'], 1.12, atol=0.2, msgs=['modelV2']), Proc(['modeld'], 1.24, atol=0.2, msgs=['modelV2']),
Proc(['dmonitoringmodeld'], 0.6, msgs=['driverStateV2']), Proc(['dmonitoringmodeld'], 0.7, msgs=['driverStateV2']),
Proc(['encoderd'], 0.23, msgs=[]), Proc(['encoderd'], 0.23, msgs=[]),
] ]

@ -0,0 +1,13 @@
#!/usr/bin/env bash
set -e
cd /sys/kernel/debug/tracing
echo "" > trace
echo 1 > tracing_on
echo 1 > /sys/kernel/debug/tracing/events/msm_vidc/enable
echo 0xff > /sys/module/videobuf2_core/parameters/debug
echo 0x7fffffff > /sys/kernel/debug/msm_vidc/debug_level
echo 0xff > /sys/devices/platform/soc/aa00000.qcom,vidc/video4linux/video33/dev_debug
cat /sys/kernel/debug/tracing/trace_pipe

@ -0,0 +1,44 @@
from enum import IntEnum
# NetworkManager device states
class NMDeviceState(IntEnum):
UNKNOWN = 0
DISCONNECTED = 30
PREPARE = 40
STATE_CONFIG = 50
NEED_AUTH = 60
IP_CONFIG = 70
ACTIVATED = 100
DEACTIVATING = 110
# NetworkManager constants
NM = "org.freedesktop.NetworkManager"
NM_PATH = '/org/freedesktop/NetworkManager'
NM_IFACE = 'org.freedesktop.NetworkManager'
NM_ACCESS_POINT_IFACE = 'org.freedesktop.NetworkManager.AccessPoint'
NM_SETTINGS_PATH = '/org/freedesktop/NetworkManager/Settings'
NM_SETTINGS_IFACE = 'org.freedesktop.NetworkManager.Settings'
NM_CONNECTION_IFACE = 'org.freedesktop.NetworkManager.Settings.Connection'
NM_WIRELESS_IFACE = 'org.freedesktop.NetworkManager.Device.Wireless'
NM_PROPERTIES_IFACE = 'org.freedesktop.DBus.Properties'
NM_DEVICE_IFACE = "org.freedesktop.NetworkManager.Device"
NM_DEVICE_TYPE_WIFI = 2
NM_DEVICE_TYPE_MODEM = 8
NM_DEVICE_STATE_REASON_SUPPLICANT_DISCONNECT = 8
NM_DEVICE_STATE_REASON_NEW_ACTIVATION = 60
# https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NM80211ApFlags
NM_802_11_AP_FLAGS_NONE = 0x0
NM_802_11_AP_FLAGS_PRIVACY = 0x1
NM_802_11_AP_FLAGS_WPS = 0x2
# https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NM80211ApSecurityFlags
NM_802_11_AP_SEC_PAIR_WEP40 = 0x00000001
NM_802_11_AP_SEC_PAIR_WEP104 = 0x00000002
NM_802_11_AP_SEC_GROUP_WEP40 = 0x00000010
NM_802_11_AP_SEC_GROUP_WEP104 = 0x00000020
NM_802_11_AP_SEC_KEY_MGMT_PSK = 0x00000100
NM_802_11_AP_SEC_KEY_MGMT_802_1X = 0x00000200

File diff suppressed because it is too large Load Diff

@ -13,7 +13,6 @@ from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.button import Button, ButtonStyle from openpilot.system.ui.widgets.button import Button, ButtonStyle
from openpilot.system.ui.widgets.label import gui_label, gui_text_box from openpilot.system.ui.widgets.label import gui_label, gui_text_box
NVME = "/dev/nvme0n1"
USERDATA = "/dev/disk/by-partlabel/userdata" USERDATA = "/dev/disk/by-partlabel/userdata"
TIMEOUT = 3*60 TIMEOUT = 3*60
@ -49,10 +48,6 @@ class Reset(Widget):
if PC: if PC:
return return
# Best effort to wipe NVME
os.system(f"sudo umount {NVME}")
os.system(f"yes | sudo mkfs.ext4 {NVME}")
# Removing data and formatting # Removing data and formatting
rm = os.system("sudo rm -rf /data/*") rm = os.system("sudo rm -rf /data/*")
os.system(f"sudo umount {USERDATA}") os.system(f"sudo umount {USERDATA}")

@ -19,7 +19,7 @@ from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.button import Button, ButtonStyle, ButtonRadio from openpilot.system.ui.widgets.button import Button, ButtonStyle, ButtonRadio
from openpilot.system.ui.widgets.keyboard import Keyboard from openpilot.system.ui.widgets.keyboard import Keyboard
from openpilot.system.ui.widgets.label import Label, TextAlignment from openpilot.system.ui.widgets.label import Label, TextAlignment
from openpilot.system.ui.widgets.network import WifiManagerUI, WifiManagerWrapper from openpilot.system.ui.widgets.network import WifiManagerUI, WifiManager
NetworkType = log.DeviceState.NetworkType NetworkType = log.DeviceState.NetworkType
@ -72,8 +72,7 @@ class Setup(Widget):
self.download_url = "" self.download_url = ""
self.download_progress = 0 self.download_progress = 0
self.download_thread = None self.download_thread = None
self.wifi_manager = WifiManagerWrapper() self.wifi_ui = WifiManagerUI(WifiManager())
self.wifi_ui = WifiManagerUI(self.wifi_manager)
self.keyboard = Keyboard() self.keyboard = Keyboard()
self.selected_radio = None self.selected_radio = None
self.warning = gui_app.texture("icons/warning.png", 150, 150) self.warning = gui_app.texture("icons/warning.png", 150, 150)

@ -7,7 +7,7 @@ from enum import IntEnum
from openpilot.system.hardware import HARDWARE from openpilot.system.hardware import HARDWARE
from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.lib.application import gui_app, FontWeight
from openpilot.system.ui.lib.wifi_manager import WifiManagerWrapper from openpilot.system.ui.lib.wifi_manager import WifiManager
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.button import gui_button, ButtonStyle from openpilot.system.ui.widgets.button import gui_button, ButtonStyle
from openpilot.system.ui.widgets.label import gui_text_box, gui_label from openpilot.system.ui.widgets.label import gui_text_box, gui_label
@ -43,8 +43,7 @@ class Updater(Widget):
self.show_reboot_button = False self.show_reboot_button = False
self.process = None self.process = None
self.update_thread = None self.update_thread = None
self.wifi_manager = WifiManagerWrapper() self.wifi_manager_ui = WifiManagerUI(WifiManager())
self.wifi_manager_ui = WifiManagerUI(self.wifi_manager)
def install_update(self): def install_update(self):
self.current_screen = Screen.PROGRESS self.current_screen = Screen.PROGRESS

@ -129,3 +129,10 @@ class Widget(abc.ABC):
def _handle_mouse_release(self, mouse_pos: MousePos) -> bool: def _handle_mouse_release(self, mouse_pos: MousePos) -> bool:
"""Optionally handle mouse release events.""" """Optionally handle mouse release events."""
return False return False
def show_event(self):
"""Optionally handle show event. Parent must manually call this"""
def hide_event(self):
"""Optionally handle hide event. Parent must manually call this"""

@ -213,6 +213,7 @@ class ListItem(Widget):
self.set_rect(rl.Rectangle(0, 0, ITEM_BASE_WIDTH, ITEM_BASE_HEIGHT)) self.set_rect(rl.Rectangle(0, 0, ITEM_BASE_WIDTH, ITEM_BASE_HEIGHT))
self._font = gui_app.font(FontWeight.NORMAL) self._font = gui_app.font(FontWeight.NORMAL)
self._icon_texture = gui_app.texture(os.path.join("icons", self.icon), ICON_SIZE, ICON_SIZE) if self.icon else None
# Cached properties for performance # Cached properties for performance
self._prev_max_width: int = 0 self._prev_max_width: int = 0
@ -261,8 +262,7 @@ class ListItem(Widget):
if self.title: if self.title:
# Draw icon if present # Draw icon if present
if self.icon: if self.icon:
icon_texture = gui_app.texture(os.path.join("icons", self.icon), ICON_SIZE, ICON_SIZE) rl.draw_texture(self._icon_texture, int(content_x), int(self._rect.y + (ITEM_BASE_HEIGHT - self._icon_texture.width) // 2), rl.WHITE)
rl.draw_texture(icon_texture, int(content_x), int(self._rect.y + (ITEM_BASE_HEIGHT - icon_texture.width) // 2), rl.WHITE)
text_x += ICON_SIZE + ITEM_PADDING text_x += ICON_SIZE + ITEM_PADDING
# Draw main text # Draw main text

@ -1,17 +1,16 @@
from dataclasses import dataclass from enum import IntEnum
from functools import partial from functools import partial
from threading import Lock from typing import cast
from typing import Literal
import pyray as rl import pyray as rl
from openpilot.system.ui.lib.application import gui_app from openpilot.system.ui.lib.application import gui_app
from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel
from openpilot.system.ui.lib.wifi_manager import NetworkInfo, WifiManagerCallbacks, WifiManagerWrapper, SecurityType from openpilot.system.ui.lib.wifi_manager import WifiManager, SecurityType, Network
from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets import Widget
from openpilot.system.ui.widgets.button import ButtonStyle, Button, TextAlignment from openpilot.system.ui.widgets.button import ButtonStyle, Button
from openpilot.system.ui.widgets.confirm_dialog import ConfirmDialog from openpilot.system.ui.widgets.confirm_dialog import ConfirmDialog
from openpilot.system.ui.widgets.keyboard import Keyboard from openpilot.system.ui.widgets.keyboard import Keyboard
from openpilot.system.ui.widgets.label import gui_label from openpilot.system.ui.widgets.label import TextAlignment, gui_label
NM_DEVICE_STATE_NEED_AUTH = 60 NM_DEVICE_STATE_NEED_AUTH = 60
MIN_PASSWORD_LENGTH = 8 MIN_PASSWORD_LENGTH = 8
@ -27,85 +26,67 @@ STRENGTH_ICONS = [
] ]
@dataclass class UIState(IntEnum):
class StateIdle: IDLE = 0
action: Literal["idle"] = "idle" CONNECTING = 1
NEEDS_AUTH = 2
SHOW_FORGET_CONFIRM = 3
@dataclass FORGETTING = 4
class StateConnecting:
network: NetworkInfo
action: Literal["connecting"] = "connecting"
@dataclass
class StateNeedsAuth:
network: NetworkInfo
retry: bool
action: Literal["needs_auth"] = "needs_auth"
@dataclass
class StateShowForgetConfirm:
network: NetworkInfo
action: Literal["show_forget_confirm"] = "show_forget_confirm"
@dataclass
class StateForgetting:
network: NetworkInfo
action: Literal["forgetting"] = "forgetting"
UIState = StateIdle | StateConnecting | StateNeedsAuth | StateShowForgetConfirm | StateForgetting
class WifiManagerUI(Widget): class WifiManagerUI(Widget):
def __init__(self, wifi_manager: WifiManagerWrapper): def __init__(self, wifi_manager: WifiManager):
super().__init__() super().__init__()
self.state: UIState = StateIdle() self.wifi_manager = wifi_manager
self.state: UIState = UIState.IDLE
self._state_network: Network | None = None # for CONNECTING / NEEDS_AUTH / SHOW_FORGET_CONFIRM / FORGETTING
self._password_retry: bool = False # for NEEDS_AUTH
self.btn_width: int = 200 self.btn_width: int = 200
self.scroll_panel = GuiScrollPanel() self.scroll_panel = GuiScrollPanel()
self.keyboard = Keyboard(max_text_size=MAX_PASSWORD_LENGTH, min_text_size=MIN_PASSWORD_LENGTH, show_password_toggle=True) self.keyboard = Keyboard(max_text_size=MAX_PASSWORD_LENGTH, min_text_size=MIN_PASSWORD_LENGTH, show_password_toggle=True)
self._load_icons()
self._networks: list[NetworkInfo] = [] self._networks: list[Network] = []
self._networks_buttons: dict[str, Button] = {} self._networks_buttons: dict[str, Button] = {}
self._forget_networks_buttons: dict[str, Button] = {} self._forget_networks_buttons: dict[str, Button] = {}
self._lock = Lock()
self.wifi_manager = wifi_manager
self._confirm_dialog = ConfirmDialog("", "Forget", "Cancel") self._confirm_dialog = ConfirmDialog("", "Forget", "Cancel")
self.wifi_manager.set_callbacks( self.wifi_manager.set_callbacks(need_auth=self._on_need_auth,
WifiManagerCallbacks( activated=self._on_activated,
need_auth=self._on_need_auth, forgotten=self._on_forgotten,
activated=self._on_activated, networks_updated=self._on_network_updated,
forgotten=self._on_forgotten, disconnected=self._on_disconnected)
networks_updated=self._on_network_updated,
connection_failed=self._on_connection_failed def show_event(self):
) # start/stop scanning when widget is visible
) self.wifi_manager.set_active(True)
self.wifi_manager.start()
self.wifi_manager.connect() def hide_event(self):
self.wifi_manager.set_active(False)
def _load_icons(self):
for icon in STRENGTH_ICONS + ["icons/checkmark.png", "icons/circled_slash.png", "icons/lock_closed.png"]:
gui_app.texture(icon, ICON_SIZE, ICON_SIZE)
def _render(self, rect: rl.Rectangle): def _render(self, rect: rl.Rectangle):
with self._lock: self.wifi_manager.process_callbacks()
if not self._networks:
gui_label(rect, "Scanning Wi-Fi networks...", 72, alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER) if not self._networks:
return gui_label(rect, "Scanning Wi-Fi networks...", 72, alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER)
return
match self.state:
case StateNeedsAuth(network, retry): if self.state == UIState.NEEDS_AUTH and self._state_network:
self.keyboard.set_title("Wrong password" if retry else "Enter password", f"for {network.ssid}") self.keyboard.set_title("Wrong password" if self._password_retry else "Enter password", f"for {self._state_network.ssid}")
self.keyboard.reset() self.keyboard.reset()
gui_app.set_modal_overlay(self.keyboard, lambda result: self._on_password_entered(network, result)) gui_app.set_modal_overlay(self.keyboard, lambda result: self._on_password_entered(cast(Network, self._state_network), result))
case StateShowForgetConfirm(network): elif self.state == UIState.SHOW_FORGET_CONFIRM and self._state_network:
self._confirm_dialog.set_text(f'Forget Wi-Fi Network "{network.ssid}"?') self._confirm_dialog.set_text(f'Forget Wi-Fi Network "{self._state_network.ssid}"?')
self._confirm_dialog.reset() self._confirm_dialog.reset()
gui_app.set_modal_overlay(self._confirm_dialog, callback=lambda result: self.on_forgot_confirm_finished(network, result)) gui_app.set_modal_overlay(self._confirm_dialog, callback=lambda result: self.on_forgot_confirm_finished(self._state_network, result))
case _: else:
self._draw_network_list(rect) self._draw_network_list(rect)
def _on_password_entered(self, network: NetworkInfo, result: int): def _on_password_entered(self, network: Network, result: int):
if result == 1: if result == 1:
password = self.keyboard.text password = self.keyboard.text
self.keyboard.clear() self.keyboard.clear()
@ -113,13 +94,13 @@ class WifiManagerUI(Widget):
if len(password) >= MIN_PASSWORD_LENGTH: if len(password) >= MIN_PASSWORD_LENGTH:
self.connect_to_network(network, password) self.connect_to_network(network, password)
elif result == 0: elif result == 0:
self.state = StateIdle() self.state = UIState.IDLE
def on_forgot_confirm_finished(self, network, result: int): def on_forgot_confirm_finished(self, network, result: int):
if result == 1: if result == 1:
self.forget_network(network) self.forget_network(network)
elif result == 0: elif result == 0:
self.state = StateIdle() self.state = UIState.IDLE
def _draw_network_list(self, rect: rl.Rectangle): def _draw_network_list(self, rect: rl.Rectangle):
content_rect = rl.Rectangle(rect.x, rect.y, rect.width, len(self._networks) * ITEM_HEIGHT) content_rect = rl.Rectangle(rect.x, rect.y, rect.width, len(self._networks) * ITEM_HEIGHT)
@ -140,24 +121,25 @@ class WifiManagerUI(Widget):
rl.end_scissor_mode() rl.end_scissor_mode()
def _draw_network_item(self, rect, network: NetworkInfo, clicked: bool): def _draw_network_item(self, rect, network: Network, clicked: bool):
spacing = 50 spacing = 50
ssid_rect = rl.Rectangle(rect.x, rect.y, rect.width - self.btn_width * 2, ITEM_HEIGHT) ssid_rect = rl.Rectangle(rect.x, rect.y, rect.width - self.btn_width * 2, ITEM_HEIGHT)
signal_icon_rect = rl.Rectangle(rect.x + rect.width - ICON_SIZE, rect.y + (ITEM_HEIGHT - ICON_SIZE) / 2, ICON_SIZE, ICON_SIZE) signal_icon_rect = rl.Rectangle(rect.x + rect.width - ICON_SIZE, rect.y + (ITEM_HEIGHT - ICON_SIZE) / 2, ICON_SIZE, ICON_SIZE)
security_icon_rect = rl.Rectangle(signal_icon_rect.x - spacing - ICON_SIZE, rect.y + (ITEM_HEIGHT - ICON_SIZE) / 2, ICON_SIZE, ICON_SIZE) security_icon_rect = rl.Rectangle(signal_icon_rect.x - spacing - ICON_SIZE, rect.y + (ITEM_HEIGHT - ICON_SIZE) / 2, ICON_SIZE, ICON_SIZE)
status_text = "" status_text = ""
match self.state: if self.state == UIState.CONNECTING and self._state_network:
case StateConnecting(network=connecting): if self._state_network.ssid == network.ssid:
if connecting.ssid == network.ssid: self._networks_buttons[network.ssid].set_enabled(False)
self._networks_buttons[network.ssid].set_enabled(False) status_text = "CONNECTING..."
status_text = "CONNECTING..." elif self.state == UIState.FORGETTING and self._state_network:
case StateForgetting(network=forgetting): if self._state_network.ssid == network.ssid:
if forgetting.ssid == network.ssid: self._networks_buttons[network.ssid].set_enabled(False)
self._networks_buttons[network.ssid].set_enabled(False) status_text = "FORGETTING..."
status_text = "FORGETTING..." elif network.security_type == SecurityType.UNSUPPORTED:
case _: self._networks_buttons[network.ssid].set_enabled(False)
self._networks_buttons[network.ssid].set_enabled(True) else:
self._networks_buttons[network.ssid].set_enabled(True)
self._networks_buttons[network.ssid].render(ssid_rect) self._networks_buttons[network.ssid].render(ssid_rect)
@ -181,18 +163,21 @@ class WifiManagerUI(Widget):
def _networks_buttons_callback(self, network): def _networks_buttons_callback(self, network):
if self.scroll_panel.is_touch_valid(): if self.scroll_panel.is_touch_valid():
if not network.is_saved and network.security_type != SecurityType.OPEN: if not network.is_saved and network.security_type != SecurityType.OPEN:
self.state = StateNeedsAuth(network, False) self.state = UIState.NEEDS_AUTH
self._state_network = network
self._password_retry = False
elif not network.is_connected: elif not network.is_connected:
self.connect_to_network(network) self.connect_to_network(network)
def _forget_networks_buttons_callback(self, network): def _forget_networks_buttons_callback(self, network):
if self.scroll_panel.is_touch_valid(): if self.scroll_panel.is_touch_valid():
self.state = StateShowForgetConfirm(network) self.state = UIState.SHOW_FORGET_CONFIRM
self._state_network = network
def _draw_status_icon(self, rect, network: NetworkInfo): def _draw_status_icon(self, rect, network: Network):
"""Draw the status icon based on network's connection state""" """Draw the status icon based on network's connection state"""
icon_file = None icon_file = None
if network.is_connected: if network.is_connected and self.state != UIState.CONNECTING:
icon_file = "icons/checkmark.png" icon_file = "icons/checkmark.png"
elif network.security_type == SecurityType.UNSUPPORTED: elif network.security_type == SecurityType.UNSUPPORTED:
icon_file = "icons/circled_slash.png" icon_file = "icons/circled_slash.png"
@ -206,63 +191,59 @@ class WifiManagerUI(Widget):
icon_rect = rl.Vector2(rect.x, rect.y + (ICON_SIZE - texture.height) / 2) icon_rect = rl.Vector2(rect.x, rect.y + (ICON_SIZE - texture.height) / 2)
rl.draw_texture_v(texture, icon_rect, rl.WHITE) rl.draw_texture_v(texture, icon_rect, rl.WHITE)
def _draw_signal_strength_icon(self, rect: rl.Rectangle, network: NetworkInfo): def _draw_signal_strength_icon(self, rect: rl.Rectangle, network: Network):
"""Draw the Wi-Fi signal strength icon based on network's signal strength""" """Draw the Wi-Fi signal strength icon based on network's signal strength"""
strength_level = max(0, min(3, round(network.strength / 33.0))) strength_level = max(0, min(3, round(network.strength / 33.0)))
rl.draw_texture_v(gui_app.texture(STRENGTH_ICONS[strength_level], ICON_SIZE, ICON_SIZE), rl.Vector2(rect.x, rect.y), rl.WHITE) rl.draw_texture_v(gui_app.texture(STRENGTH_ICONS[strength_level], ICON_SIZE, ICON_SIZE), rl.Vector2(rect.x, rect.y), rl.WHITE)
def connect_to_network(self, network: NetworkInfo, password=''): def connect_to_network(self, network: Network, password=''):
self.state = StateConnecting(network) self.state = UIState.CONNECTING
self._state_network = network
if network.is_saved and not password: if network.is_saved and not password:
self.wifi_manager.activate_connection(network.ssid) self.wifi_manager.activate_connection(network.ssid)
else: else:
self.wifi_manager.connect_to_network(network.ssid, password) self.wifi_manager.connect_to_network(network.ssid, password)
def forget_network(self, network: NetworkInfo): def forget_network(self, network: Network):
self.state = StateForgetting(network) self.state = UIState.FORGETTING
network.is_saved = False self._state_network = network
self.wifi_manager.forget_connection(network.ssid) self.wifi_manager.forget_connection(network.ssid)
def _on_network_updated(self, networks: list[NetworkInfo]): def _on_network_updated(self, networks: list[Network]):
with self._lock: self._networks = networks
self._networks = networks for n in self._networks:
for n in self._networks: self._networks_buttons[n.ssid] = Button(n.ssid, partial(self._networks_buttons_callback, n), font_size=55, text_alignment=TextAlignment.LEFT,
self._networks_buttons[n.ssid] = Button(n.ssid, partial(self._networks_buttons_callback, n), font_size=55, text_alignment=TextAlignment.LEFT, button_style=ButtonStyle.NO_EFFECT)
button_style=ButtonStyle.NO_EFFECT) self._forget_networks_buttons[n.ssid] = Button("Forget", partial(self._forget_networks_buttons_callback, n), button_style=ButtonStyle.FORGET_WIFI,
self._forget_networks_buttons[n.ssid] = Button("Forget", partial(self._forget_networks_buttons_callback, n), button_style=ButtonStyle.FORGET_WIFI, font_size=45)
font_size=45)
def _on_need_auth(self, ssid): def _on_need_auth(self, ssid):
with self._lock: network = next((n for n in self._networks if n.ssid == ssid), None)
network = next((n for n in self._networks if n.ssid == ssid), None) if network:
if network: self.state = UIState.NEEDS_AUTH
self.state = StateNeedsAuth(network, True) self._state_network = network
self._password_retry = True
def _on_activated(self): def _on_activated(self):
with self._lock: if self.state == UIState.CONNECTING:
if isinstance(self.state, StateConnecting): self.state = UIState.IDLE
self.state = StateIdle()
def _on_forgotten(self, ssid): def _on_forgotten(self):
with self._lock: if self.state == UIState.FORGETTING:
if isinstance(self.state, StateForgetting): self.state = UIState.IDLE
self.state = StateIdle()
def _on_connection_failed(self, ssid: str, error: str): def _on_disconnected(self):
with self._lock: if self.state == UIState.CONNECTING:
if isinstance(self.state, StateConnecting): self.state = UIState.IDLE
self.state = StateIdle()
def main(): def main():
gui_app.init_window("Wi-Fi Manager") gui_app.init_window("Wi-Fi Manager")
wifi_manager = WifiManagerWrapper() wifi_ui = WifiManagerUI(WifiManager())
wifi_ui = WifiManagerUI(wifi_manager)
for _ in gui_app.render(): for _ in gui_app.render():
wifi_ui.render(rl.Rectangle(50, 50, gui_app.width - 100, gui_app.height - 100)) wifi_ui.render(rl.Rectangle(50, 50, gui_app.width - 100, gui_app.height - 100))
wifi_manager.shutdown()
gui_app.close() gui_app.close()

@ -243,7 +243,7 @@ class Updater:
if b is None: if b is None:
b = self.get_branch(BASEDIR) b = self.get_branch(BASEDIR)
b = { b = {
("tici", "release3"): "release-tici" ("tizi", "release3"): "release-tizi",
}.get((HARDWARE.get_device_type(), b), b) }.get((HARDWARE.get_device_type(), b), b)
return b return b

@ -1 +1 @@
Subproject commit c30a113b2a876cabaea1049601fea3a0b758c5b1 Subproject commit 965ea59b16679793b8f48368ac24c4a0ef587e71

@ -1,6 +1,6 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
import sys import sys
from openpilot.tools.lib.logreader import LogReader from openpilot.tools.lib.logreader import LogReader, ReadMode
def main(): def main():
@ -9,7 +9,7 @@ def main():
sys.exit(1) sys.exit(1)
log_path = sys.argv[1] log_path = sys.argv[1]
lr = LogReader(log_path, sort_by_time=True) lr = LogReader(log_path, default_mode=ReadMode.AUTO, sort_by_time=True)
print("\n".join(lr.logreader_identifiers)) print("\n".join(lr.logreader_identifiers))

@ -365,6 +365,7 @@ function op_switch() {
fi fi
BRANCH="$1" BRANCH="$1"
git config --replace-all remote.origin.fetch "+refs/heads/*:refs/remotes/origin/*"
git fetch "$REMOTE" "$BRANCH" git fetch "$REMOTE" "$BRANCH"
git checkout -f FETCH_HEAD git checkout -f FETCH_HEAD
git checkout -B "$BRANCH" --track "$REMOTE"/"$BRANCH" git checkout -B "$BRANCH" --track "$REMOTE"/"$BRANCH"

@ -510,27 +510,27 @@ wheels = [
[[package]] [[package]]
name = "fonttools" name = "fonttools"
version = "4.59.1" version = "4.59.2"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/11/7f/29c9c3fe4246f6ad96fee52b88d0dc3a863c7563b0afc959e36d78b965dc/fonttools-4.59.1.tar.gz", hash = "sha256:74995b402ad09822a4c8002438e54940d9f1ecda898d2bb057729d7da983e4cb", size = 3534394, upload-time = "2025-08-14T16:28:14.266Z" } sdist = { url = "https://files.pythonhosted.org/packages/0d/a5/fba25f9fbdab96e26dedcaeeba125e5f05a09043bf888e0305326e55685b/fonttools-4.59.2.tar.gz", hash = "sha256:e72c0749b06113f50bcb80332364c6be83a9582d6e3db3fe0b280f996dc2ef22", size = 3540889, upload-time = "2025-08-27T16:40:30.97Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/34/62/9667599561f623d4a523cc9eb4f66f3b94b6155464110fa9aebbf90bbec7/fonttools-4.59.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4909cce2e35706f3d18c54d3dcce0414ba5e0fb436a454dffec459c61653b513", size = 2778815, upload-time = "2025-08-14T16:26:28.484Z" }, { url = "https://files.pythonhosted.org/packages/f8/53/742fcd750ae0bdc74de4c0ff923111199cc2f90a4ee87aaddad505b6f477/fonttools-4.59.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:511946e8d7ea5c0d6c7a53c4cb3ee48eda9ab9797cd9bf5d95829a398400354f", size = 2774961, upload-time = "2025-08-27T16:38:47.536Z" },
{ url = "https://files.pythonhosted.org/packages/8f/78/cc25bcb2ce86033a9df243418d175e58f1956a35047c685ef553acae67d6/fonttools-4.59.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:efbec204fa9f877641747f2d9612b2b656071390d7a7ef07a9dbf0ecf9c7195c", size = 2341631, upload-time = "2025-08-14T16:26:30.396Z" }, { url = "https://files.pythonhosted.org/packages/57/2a/976f5f9fa3b4dd911dc58d07358467bec20e813d933bc5d3db1a955dd456/fonttools-4.59.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:8e5e2682cf7be766d84f462ba8828d01e00c8751a8e8e7ce12d7784ccb69a30d", size = 2344690, upload-time = "2025-08-27T16:38:49.723Z" },
{ url = "https://files.pythonhosted.org/packages/a4/cc/fcbb606dd6871f457ac32f281c20bcd6cc77d9fce77b5a4e2b2afab1f500/fonttools-4.59.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:39dfd42cc2dc647b2c5469bc7a5b234d9a49e72565b96dd14ae6f11c2c59ef15", size = 5022222, upload-time = "2025-08-14T16:26:32.447Z" }, { url = "https://files.pythonhosted.org/packages/c1/8f/b7eefc274fcf370911e292e95565c8253b0b87c82a53919ab3c795a4f50e/fonttools-4.59.2-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5729e12a982dba3eeae650de48b06f3b9ddb51e9aee2fcaf195b7d09a96250e2", size = 5026910, upload-time = "2025-08-27T16:38:51.904Z" },
{ url = "https://files.pythonhosted.org/packages/61/96/c0b1cf2b74d08eb616a80dbf5564351fe4686147291a25f7dce8ace51eb3/fonttools-4.59.1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:b11bc177a0d428b37890825d7d025040d591aa833f85f8d8878ed183354f47df", size = 4966512, upload-time = "2025-08-14T16:26:34.621Z" }, { url = "https://files.pythonhosted.org/packages/69/95/864726eaa8f9d4e053d0c462e64d5830ec7c599cbdf1db9e40f25ca3972e/fonttools-4.59.2-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:c52694eae5d652361d59ecdb5a2246bff7cff13b6367a12da8499e9df56d148d", size = 4971031, upload-time = "2025-08-27T16:38:53.676Z" },
{ url = "https://files.pythonhosted.org/packages/a4/26/51ce2e3e0835ffc2562b1b11d1fb9dafd0aca89c9041b64a9e903790a761/fonttools-4.59.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:5b9b4c35b3be45e5bc774d3fc9608bbf4f9a8d371103b858c80edbeed31dd5aa", size = 5001645, upload-time = "2025-08-14T16:26:36.876Z" }, { url = "https://files.pythonhosted.org/packages/24/4c/b8c4735ebdea20696277c70c79e0de615dbe477834e5a7c2569aa1db4033/fonttools-4.59.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:f1f1bbc23ba1312bd8959896f46f667753b90216852d2a8cfa2d07e0cb234144", size = 5006112, upload-time = "2025-08-27T16:38:55.69Z" },
{ url = "https://files.pythonhosted.org/packages/36/11/ef0b23f4266349b6d5ccbd1a07b7adc998d5bce925792aa5d1ec33f593e3/fonttools-4.59.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:01158376b8a418a0bae9625c476cebfcfcb5e6761e9d243b219cd58341e7afbb", size = 5113777, upload-time = "2025-08-14T16:26:39.002Z" }, { url = "https://files.pythonhosted.org/packages/3b/23/f9ea29c292aa2fc1ea381b2e5621ac436d5e3e0a5dee24ffe5404e58eae8/fonttools-4.59.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1a1bfe5378962825dabe741720885e8b9ae9745ec7ecc4a5ec1f1ce59a6062bf", size = 5117671, upload-time = "2025-08-27T16:38:58.984Z" },
{ url = "https://files.pythonhosted.org/packages/d0/da/b398fe61ef433da0a0472cdb5d4399124f7581ffe1a31b6242c91477d802/fonttools-4.59.1-cp311-cp311-win32.whl", hash = "sha256:cf7c5089d37787387123f1cb8f1793a47c5e1e3d1e4e7bfbc1cc96e0f925eabe", size = 2215076, upload-time = "2025-08-14T16:26:41.196Z" }, { url = "https://files.pythonhosted.org/packages/ba/07/cfea304c555bf06e86071ff2a3916bc90f7c07ec85b23bab758d4908c33d/fonttools-4.59.2-cp311-cp311-win32.whl", hash = "sha256:e937790f3c2c18a1cbc7da101550a84319eb48023a715914477d2e7faeaba570", size = 2218157, upload-time = "2025-08-27T16:39:00.75Z" },
{ url = "https://files.pythonhosted.org/packages/94/bd/e2624d06ab94e41c7c77727b2941f1baed7edb647e63503953e6888020c9/fonttools-4.59.1-cp311-cp311-win_amd64.whl", hash = "sha256:c866eef7a0ba320486ade6c32bfc12813d1a5db8567e6904fb56d3d40acc5116", size = 2262779, upload-time = "2025-08-14T16:26:43.483Z" }, { url = "https://files.pythonhosted.org/packages/d7/de/35d839aa69db737a3f9f3a45000ca24721834d40118652a5775d5eca8ebb/fonttools-4.59.2-cp311-cp311-win_amd64.whl", hash = "sha256:9836394e2f4ce5f9c0a7690ee93bd90aa1adc6b054f1a57b562c5d242c903104", size = 2265846, upload-time = "2025-08-27T16:39:02.453Z" },
{ url = "https://files.pythonhosted.org/packages/ac/fe/6e069cc4cb8881d164a9bd956e9df555bc62d3eb36f6282e43440200009c/fonttools-4.59.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:43ab814bbba5f02a93a152ee61a04182bb5809bd2bc3609f7822e12c53ae2c91", size = 2769172, upload-time = "2025-08-14T16:26:45.729Z" }, { url = "https://files.pythonhosted.org/packages/ba/3d/1f45db2df51e7bfa55492e8f23f383d372200be3a0ded4bf56a92753dd1f/fonttools-4.59.2-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:82906d002c349cad647a7634b004825a7335f8159d0d035ae89253b4abf6f3ea", size = 2769711, upload-time = "2025-08-27T16:39:04.423Z" },
{ url = "https://files.pythonhosted.org/packages/b9/98/ec4e03f748fefa0dd72d9d95235aff6fef16601267f4a2340f0e16b9330f/fonttools-4.59.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:4f04c3ffbfa0baafcbc550657cf83657034eb63304d27b05cff1653b448ccff6", size = 2337281, upload-time = "2025-08-14T16:26:47.921Z" }, { url = "https://files.pythonhosted.org/packages/29/df/cd236ab32a8abfd11558f296e064424258db5edefd1279ffdbcfd4fd8b76/fonttools-4.59.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:a10c1bd7644dc58f8862d8ba0cf9fb7fef0af01ea184ba6ce3f50ab7dfe74d5a", size = 2340225, upload-time = "2025-08-27T16:39:06.143Z" },
{ url = "https://files.pythonhosted.org/packages/8b/b1/890360a7e3d04a30ba50b267aca2783f4c1364363797e892e78a4f036076/fonttools-4.59.1-cp312-cp312-manylinux1_x86_64.manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:d601b153e51a5a6221f0d4ec077b6bfc6ac35bfe6c19aeaa233d8990b2b71726", size = 4909215, upload-time = "2025-08-14T16:26:49.682Z" }, { url = "https://files.pythonhosted.org/packages/98/12/b6f9f964fe6d4b4dd4406bcbd3328821c3de1f909ffc3ffa558fe72af48c/fonttools-4.59.2-cp312-cp312-manylinux1_x86_64.manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:738f31f23e0339785fd67652a94bc69ea49e413dfdb14dcb8c8ff383d249464e", size = 4912766, upload-time = "2025-08-27T16:39:08.138Z" },
{ url = "https://files.pythonhosted.org/packages/8a/ec/2490599550d6c9c97a44c1e36ef4de52d6acf742359eaa385735e30c05c4/fonttools-4.59.1-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c735e385e30278c54f43a0d056736942023c9043f84ee1021eff9fd616d17693", size = 4951958, upload-time = "2025-08-14T16:26:51.616Z" }, { url = "https://files.pythonhosted.org/packages/73/78/82bde2f2d2c306ef3909b927363170b83df96171f74e0ccb47ad344563cd/fonttools-4.59.2-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0ec99f9bdfee9cdb4a9172f9e8fd578cce5feb231f598909e0aecf5418da4f25", size = 4955178, upload-time = "2025-08-27T16:39:10.094Z" },
{ url = "https://files.pythonhosted.org/packages/d1/40/bd053f6f7634234a9b9805ff8ae4f32df4f2168bee23cafd1271ba9915a9/fonttools-4.59.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1017413cdc8555dce7ee23720da490282ab7ec1cf022af90a241f33f9a49afc4", size = 4894738, upload-time = "2025-08-14T16:26:53.836Z" }, { url = "https://files.pythonhosted.org/packages/92/77/7de766afe2d31dda8ee46d7e479f35c7d48747e558961489a2d6e3a02bd4/fonttools-4.59.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:0476ea74161322e08c7a982f83558a2b81b491509984523a1a540baf8611cc31", size = 4897898, upload-time = "2025-08-27T16:39:12.087Z" },
{ url = "https://files.pythonhosted.org/packages/ac/a1/3cd12a010d288325a7cfcf298a84825f0f9c29b01dee1baba64edfe89257/fonttools-4.59.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:5c6d8d773470a5107052874341ed3c487c16ecd179976d81afed89dea5cd7406", size = 5045983, upload-time = "2025-08-14T16:26:56.153Z" }, { url = "https://files.pythonhosted.org/packages/c5/77/ce0e0b905d62a06415fda9f2b2e109a24a5db54a59502b769e9e297d2242/fonttools-4.59.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:95922a922daa1f77cc72611747c156cfb38030ead72436a2c551d30ecef519b9", size = 5049144, upload-time = "2025-08-27T16:39:13.84Z" },
{ url = "https://files.pythonhosted.org/packages/a2/af/8a2c3f6619cc43cf87951405337cc8460d08a4e717bb05eaa94b335d11dc/fonttools-4.59.1-cp312-cp312-win32.whl", hash = "sha256:2a2d0d33307f6ad3a2086a95dd607c202ea8852fa9fb52af9b48811154d1428a", size = 2203407, upload-time = "2025-08-14T16:26:58.165Z" }, { url = "https://files.pythonhosted.org/packages/d9/ea/870d93aefd23fff2e07cbeebdc332527868422a433c64062c09d4d5e7fe6/fonttools-4.59.2-cp312-cp312-win32.whl", hash = "sha256:39ad9612c6a622726a6a130e8ab15794558591f999673f1ee7d2f3d30f6a3e1c", size = 2206473, upload-time = "2025-08-27T16:39:15.854Z" },
{ url = "https://files.pythonhosted.org/packages/8e/f2/a19b874ddbd3ebcf11d7e25188ef9ac3f68b9219c62263acb34aca8cde05/fonttools-4.59.1-cp312-cp312-win_amd64.whl", hash = "sha256:0b9e4fa7eaf046ed6ac470f6033d52c052481ff7a6e0a92373d14f556f298dc0", size = 2251561, upload-time = "2025-08-14T16:27:00.646Z" }, { url = "https://files.pythonhosted.org/packages/61/c4/e44bad000c4a4bb2e9ca11491d266e857df98ab6d7428441b173f0fe2517/fonttools-4.59.2-cp312-cp312-win_amd64.whl", hash = "sha256:980fd7388e461b19a881d35013fec32c713ffea1fc37aef2f77d11f332dfd7da", size = 2254706, upload-time = "2025-08-27T16:39:17.893Z" },
{ url = "https://files.pythonhosted.org/packages/0f/64/9d606e66d498917cd7a2ff24f558010d42d6fd4576d9dd57f0bd98333f5a/fonttools-4.59.1-py3-none-any.whl", hash = "sha256:647db657073672a8330608970a984d51573557f328030566521bc03415535042", size = 1130094, upload-time = "2025-08-14T16:28:12.048Z" }, { url = "https://files.pythonhosted.org/packages/65/a4/d2f7be3c86708912c02571db0b550121caab8cd88a3c0aacb9cfa15ea66e/fonttools-4.59.2-py3-none-any.whl", hash = "sha256:8bd0f759020e87bb5d323e6283914d9bf4ae35a7307dafb2cbd1e379e720ad37", size = 1132315, upload-time = "2025-08-27T16:40:28.984Z" },
] ]
[[package]] [[package]]
@ -690,6 +690,15 @@ wheels = [
{ url = "https://files.pythonhosted.org/packages/15/aa/0aca39a37d3c7eb941ba736ede56d689e7be91cab5d9ca846bde3999eba6/isodate-0.7.2-py3-none-any.whl", hash = "sha256:28009937d8031054830160fce6d409ed342816b543597cece116d966c6d99e15", size = 22320, upload-time = "2024-10-08T23:04:09.501Z" }, { url = "https://files.pythonhosted.org/packages/15/aa/0aca39a37d3c7eb941ba736ede56d689e7be91cab5d9ca846bde3999eba6/isodate-0.7.2-py3-none-any.whl", hash = "sha256:28009937d8031054830160fce6d409ed342816b543597cece116d966c6d99e15", size = 22320, upload-time = "2024-10-08T23:04:09.501Z" },
] ]
[[package]]
name = "jeepney"
version = "0.9.0"
source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/7b/6f/357efd7602486741aa73ffc0617fb310a29b588ed0fd69c2399acbb85b0c/jeepney-0.9.0.tar.gz", hash = "sha256:cf0e9e845622b81e4a28df94c40345400256ec608d0e55bb8a3feaa9163f5732", size = 106758, upload-time = "2025-02-27T18:51:01.684Z" }
wheels = [
{ url = "https://files.pythonhosted.org/packages/b2/a3/e137168c9c44d18eff0376253da9f1e9234d0239e0ee230d2fee6cea8e55/jeepney-0.9.0-py3-none-any.whl", hash = "sha256:97e5714520c16fc0a45695e5365a2e11b81ea79bba796e26f9f1d178cb182683", size = 49010, upload-time = "2025-02-27T18:51:00.104Z" },
]
[[package]] [[package]]
name = "jinja2" name = "jinja2"
version = "3.1.6" version = "3.1.6"
@ -763,40 +772,48 @@ wheels = [
[[package]] [[package]]
name = "lxml" name = "lxml"
version = "6.0.0" version = "6.0.1"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/c5/ed/60eb6fa2923602fba988d9ca7c5cdbd7cf25faa795162ed538b527a35411/lxml-6.0.0.tar.gz", hash = "sha256:032e65120339d44cdc3efc326c9f660f5f7205f3a535c1fdbf898b29ea01fb72", size = 4096938, upload-time = "2025-06-26T16:28:19.373Z" } sdist = { url = "https://files.pythonhosted.org/packages/8f/bd/f9d01fd4132d81c6f43ab01983caea69ec9614b913c290a26738431a015d/lxml-6.0.1.tar.gz", hash = "sha256:2b3a882ebf27dd026df3801a87cf49ff791336e0f94b0fad195db77e01240690", size = 4070214, upload-time = "2025-08-22T10:37:53.525Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/7c/23/828d4cc7da96c611ec0ce6147bbcea2fdbde023dc995a165afa512399bbf/lxml-6.0.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4ee56288d0df919e4aac43b539dd0e34bb55d6a12a6562038e8d6f3ed07f9e36", size = 8438217, upload-time = "2025-06-26T16:25:34.349Z" }, { url = "https://files.pythonhosted.org/packages/29/c8/262c1d19339ef644cdc9eb5aad2e85bd2d1fa2d7c71cdef3ede1a3eed84d/lxml-6.0.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c6acde83f7a3d6399e6d83c1892a06ac9b14ea48332a5fbd55d60b9897b9570a", size = 8422719, upload-time = "2025-08-22T10:32:24.848Z" },
{ url = "https://files.pythonhosted.org/packages/f1/33/5ac521212c5bcb097d573145d54b2b4a3c9766cda88af5a0e91f66037c6e/lxml-6.0.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:b8dd6dd0e9c1992613ccda2bcb74fc9d49159dbe0f0ca4753f37527749885c25", size = 4590317, upload-time = "2025-06-26T16:25:38.103Z" }, { url = "https://files.pythonhosted.org/packages/e5/d4/1b0afbeb801468a310642c3a6f6704e53c38a4a6eb1ca6faea013333e02f/lxml-6.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:0d21c9cacb6a889cbb8eeb46c77ef2c1dd529cde10443fdeb1de847b3193c541", size = 4575763, upload-time = "2025-08-22T10:32:27.057Z" },
{ url = "https://files.pythonhosted.org/packages/2b/2e/45b7ca8bee304c07f54933c37afe7dd4d39ff61ba2757f519dcc71bc5d44/lxml-6.0.0-cp311-cp311-manylinux2010_i686.manylinux2014_i686.manylinux_2_12_i686.manylinux_2_17_i686.whl", hash = "sha256:d7ae472f74afcc47320238b5dbfd363aba111a525943c8a34a1b657c6be934c3", size = 5221628, upload-time = "2025-06-26T16:25:40.878Z" }, { url = "https://files.pythonhosted.org/packages/5b/c1/8db9b5402bf52ceb758618313f7423cd54aea85679fcf607013707d854a8/lxml-6.0.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:847458b7cd0d04004895f1fb2cca8e7c0f8ec923c49c06b7a72ec2d48ea6aca2", size = 4943244, upload-time = "2025-08-22T10:32:28.847Z" },
{ url = "https://files.pythonhosted.org/packages/32/23/526d19f7eb2b85da1f62cffb2556f647b049ebe2a5aa8d4d41b1fb2c7d36/lxml-6.0.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:5592401cdf3dc682194727c1ddaa8aa0f3ddc57ca64fd03226a430b955eab6f6", size = 4949429, upload-time = "2025-06-28T18:47:20.046Z" }, { url = "https://files.pythonhosted.org/packages/e7/78/838e115358dd2369c1c5186080dd874a50a691fb5cd80db6afe5e816e2c6/lxml-6.0.1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1dc13405bf315d008fe02b1472d2a9d65ee1c73c0a06de5f5a45e6e404d9a1c0", size = 5081725, upload-time = "2025-08-22T10:32:30.666Z" },
{ url = "https://files.pythonhosted.org/packages/ac/cc/f6be27a5c656a43a5344e064d9ae004d4dcb1d3c9d4f323c8189ddfe4d13/lxml-6.0.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:58ffd35bd5425c3c3b9692d078bf7ab851441434531a7e517c4984d5634cd65b", size = 5087909, upload-time = "2025-06-28T18:47:22.834Z" }, { url = "https://files.pythonhosted.org/packages/c7/b6/bdcb3a3ddd2438c5b1a1915161f34e8c85c96dc574b0ef3be3924f36315c/lxml-6.0.1-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:70f540c229a8c0a770dcaf6d5af56a5295e0fc314fc7ef4399d543328054bcea", size = 5021238, upload-time = "2025-08-22T10:32:32.49Z" },
{ url = "https://files.pythonhosted.org/packages/3b/e6/8ec91b5bfbe6972458bc105aeb42088e50e4b23777170404aab5dfb0c62d/lxml-6.0.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f720a14aa102a38907c6d5030e3d66b3b680c3e6f6bc95473931ea3c00c59967", size = 5031713, upload-time = "2025-06-26T16:25:43.226Z" }, { url = "https://files.pythonhosted.org/packages/73/e5/1bfb96185dc1a64c7c6fbb7369192bda4461952daa2025207715f9968205/lxml-6.0.1-cp311-cp311-manylinux_2_26_i686.manylinux_2_28_i686.whl", hash = "sha256:d2f73aef768c70e8deb8c4742fca4fd729b132fda68458518851c7735b55297e", size = 5343744, upload-time = "2025-08-22T10:32:34.385Z" },
{ url = "https://files.pythonhosted.org/packages/33/cf/05e78e613840a40e5be3e40d892c48ad3e475804db23d4bad751b8cadb9b/lxml-6.0.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:c2a5e8d207311a0170aca0eb6b160af91adc29ec121832e4ac151a57743a1e1e", size = 5232417, upload-time = "2025-06-26T16:25:46.111Z" }, { url = "https://files.pythonhosted.org/packages/a2/ae/df3ea9ebc3c493b9c6bdc6bd8c554ac4e147f8d7839993388aab57ec606d/lxml-6.0.1-cp311-cp311-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:e7f4066b85a4fa25ad31b75444bd578c3ebe6b8ed47237896341308e2ce923c3", size = 5223477, upload-time = "2025-08-22T10:32:36.256Z" },
{ url = "https://files.pythonhosted.org/packages/ac/8c/6b306b3e35c59d5f0b32e3b9b6b3b0739b32c0dc42a295415ba111e76495/lxml-6.0.0-cp311-cp311-manylinux_2_31_armv7l.whl", hash = "sha256:2dd1cc3ea7e60bfb31ff32cafe07e24839df573a5e7c2d33304082a5019bcd58", size = 4681443, upload-time = "2025-06-26T16:25:48.837Z" }, { url = "https://files.pythonhosted.org/packages/37/b3/65e1e33600542c08bc03a4c5c9c306c34696b0966a424a3be6ffec8038ed/lxml-6.0.1-cp311-cp311-manylinux_2_31_armv7l.whl", hash = "sha256:0cce65db0cd8c750a378639900d56f89f7d6af11cd5eda72fde054d27c54b8ce", size = 4676626, upload-time = "2025-08-22T10:32:38.793Z" },
{ url = "https://files.pythonhosted.org/packages/59/43/0bd96bece5f7eea14b7220476835a60d2b27f8e9ca99c175f37c085cb154/lxml-6.0.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:2cfcf84f1defed7e5798ef4f88aa25fcc52d279be731ce904789aa7ccfb7e8d2", size = 5074542, upload-time = "2025-06-26T16:25:51.65Z" }, { url = "https://files.pythonhosted.org/packages/7a/46/ee3ed8f3a60e9457d7aea46542d419917d81dbfd5700fe64b2a36fb5ef61/lxml-6.0.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:c372d42f3eee5844b69dcab7b8d18b2f449efd54b46ac76970d6e06b8e8d9a66", size = 5066042, upload-time = "2025-08-22T10:32:41.134Z" },
{ url = "https://files.pythonhosted.org/packages/e2/3d/32103036287a8ca012d8518071f8852c68f2b3bfe048cef2a0202eb05910/lxml-6.0.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:a52a4704811e2623b0324a18d41ad4b9fabf43ce5ff99b14e40a520e2190c851", size = 4729471, upload-time = "2025-06-26T16:25:54.571Z" }, { url = "https://files.pythonhosted.org/packages/9c/b9/8394538e7cdbeb3bfa36bc74924be1a4383e0bb5af75f32713c2c4aa0479/lxml-6.0.1-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:2e2b0e042e1408bbb1c5f3cfcb0f571ff4ac98d8e73f4bf37c5dd179276beedd", size = 4724714, upload-time = "2025-08-22T10:32:43.94Z" },
{ url = "https://files.pythonhosted.org/packages/ca/a8/7be5d17df12d637d81854bd8648cd329f29640a61e9a72a3f77add4a311b/lxml-6.0.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:c16304bba98f48a28ae10e32a8e75c349dd742c45156f297e16eeb1ba9287a1f", size = 5256285, upload-time = "2025-06-26T16:25:56.997Z" }, { url = "https://files.pythonhosted.org/packages/b3/21/3ef7da1ea2a73976c1a5a311d7cde5d379234eec0968ee609517714940b4/lxml-6.0.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:cc73bb8640eadd66d25c5a03175de6801f63c535f0f3cf50cac2f06a8211f420", size = 5247376, upload-time = "2025-08-22T10:32:46.263Z" },
{ url = "https://files.pythonhosted.org/packages/cd/d0/6cb96174c25e0d749932557c8d51d60c6e292c877b46fae616afa23ed31a/lxml-6.0.0-cp311-cp311-win32.whl", hash = "sha256:f8d19565ae3eb956d84da3ef367aa7def14a2735d05bd275cd54c0301f0d0d6c", size = 3612004, upload-time = "2025-06-26T16:25:59.11Z" }, { url = "https://files.pythonhosted.org/packages/26/7d/0980016f124f00c572cba6f4243e13a8e80650843c66271ee692cddf25f3/lxml-6.0.1-cp311-cp311-win32.whl", hash = "sha256:7c23fd8c839708d368e406282d7953cee5134f4592ef4900026d84566d2b4c88", size = 3609499, upload-time = "2025-08-22T10:32:48.156Z" },
{ url = "https://files.pythonhosted.org/packages/ca/77/6ad43b165dfc6dead001410adeb45e88597b25185f4479b7ca3b16a5808f/lxml-6.0.0-cp311-cp311-win_amd64.whl", hash = "sha256:b2d71cdefda9424adff9a3607ba5bbfc60ee972d73c21c7e3c19e71037574816", size = 4003470, upload-time = "2025-06-26T16:26:01.655Z" }, { url = "https://files.pythonhosted.org/packages/b1/08/28440437521f265eff4413eb2a65efac269c4c7db5fd8449b586e75d8de2/lxml-6.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:2516acc6947ecd3c41a4a4564242a87c6786376989307284ddb115f6a99d927f", size = 4036003, upload-time = "2025-08-22T10:32:50.662Z" },
{ url = "https://files.pythonhosted.org/packages/a0/bc/4c50ec0eb14f932a18efc34fc86ee936a66c0eb5f2fe065744a2da8a68b2/lxml-6.0.0-cp311-cp311-win_arm64.whl", hash = "sha256:8a2e76efbf8772add72d002d67a4c3d0958638696f541734304c7f28217a9cab", size = 3682477, upload-time = "2025-06-26T16:26:03.808Z" }, { url = "https://files.pythonhosted.org/packages/7b/dc/617e67296d98099213a505d781f04804e7b12923ecd15a781a4ab9181992/lxml-6.0.1-cp311-cp311-win_arm64.whl", hash = "sha256:cb46f8cfa1b0334b074f40c0ff94ce4d9a6755d492e6c116adb5f4a57fb6ad96", size = 3679662, upload-time = "2025-08-22T10:32:52.739Z" },
{ url = "https://files.pythonhosted.org/packages/89/c3/d01d735c298d7e0ddcedf6f028bf556577e5ab4f4da45175ecd909c79378/lxml-6.0.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:78718d8454a6e928470d511bf8ac93f469283a45c354995f7d19e77292f26108", size = 8429515, upload-time = "2025-06-26T16:26:06.776Z" }, { url = "https://files.pythonhosted.org/packages/b0/a9/82b244c8198fcdf709532e39a1751943a36b3e800b420adc739d751e0299/lxml-6.0.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c03ac546adaabbe0b8e4a15d9ad815a281afc8d36249c246aecf1aaad7d6f200", size = 8422788, upload-time = "2025-08-22T10:32:56.612Z" },
{ url = "https://files.pythonhosted.org/packages/06/37/0e3eae3043d366b73da55a86274a590bae76dc45aa004b7042e6f97803b1/lxml-6.0.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:84ef591495ffd3f9dcabffd6391db7bb70d7230b5c35ef5148354a134f56f2be", size = 4601387, upload-time = "2025-06-26T16:26:09.511Z" }, { url = "https://files.pythonhosted.org/packages/c9/8d/1ed2bc20281b0e7ed3e6c12b0a16e64ae2065d99be075be119ba88486e6d/lxml-6.0.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:33b862c7e3bbeb4ba2c96f3a039f925c640eeba9087a4dc7a572ec0f19d89392", size = 4593547, upload-time = "2025-08-22T10:32:59.016Z" },
{ url = "https://files.pythonhosted.org/packages/a3/28/e1a9a881e6d6e29dda13d633885d13acb0058f65e95da67841c8dd02b4a8/lxml-6.0.0-cp312-cp312-manylinux2010_i686.manylinux2014_i686.manylinux_2_12_i686.manylinux_2_17_i686.whl", hash = "sha256:2930aa001a3776c3e2601cb8e0a15d21b8270528d89cc308be4843ade546b9ab", size = 5228928, upload-time = "2025-06-26T16:26:12.337Z" }, { url = "https://files.pythonhosted.org/packages/76/53/d7fd3af95b72a3493bf7fbe842a01e339d8f41567805cecfecd5c71aa5ee/lxml-6.0.1-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:7a3ec1373f7d3f519de595032d4dcafae396c29407cfd5073f42d267ba32440d", size = 4948101, upload-time = "2025-08-22T10:33:00.765Z" },
{ url = "https://files.pythonhosted.org/packages/9a/55/2cb24ea48aa30c99f805921c1c7860c1f45c0e811e44ee4e6a155668de06/lxml-6.0.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:219e0431ea8006e15005767f0351e3f7f9143e793e58519dc97fe9e07fae5563", size = 4952289, upload-time = "2025-06-28T18:47:25.602Z" }, { url = "https://files.pythonhosted.org/packages/9d/51/4e57cba4d55273c400fb63aefa2f0d08d15eac021432571a7eeefee67bed/lxml-6.0.1-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:03b12214fb1608f4cffa181ec3d046c72f7e77c345d06222144744c122ded870", size = 5108090, upload-time = "2025-08-22T10:33:03.108Z" },
{ url = "https://files.pythonhosted.org/packages/31/c0/b25d9528df296b9a3306ba21ff982fc5b698c45ab78b94d18c2d6ae71fd9/lxml-6.0.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:bd5913b4972681ffc9718bc2d4c53cde39ef81415e1671ff93e9aa30b46595e7", size = 5111310, upload-time = "2025-06-28T18:47:28.136Z" }, { url = "https://files.pythonhosted.org/packages/f6/6e/5f290bc26fcc642bc32942e903e833472271614e24d64ad28aaec09d5dae/lxml-6.0.1-cp312-cp312-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:207ae0d5f0f03b30f95e649a6fa22aa73f5825667fee9c7ec6854d30e19f2ed8", size = 5021791, upload-time = "2025-08-22T10:33:06.972Z" },
{ url = "https://files.pythonhosted.org/packages/e9/af/681a8b3e4f668bea6e6514cbcb297beb6de2b641e70f09d3d78655f4f44c/lxml-6.0.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:390240baeb9f415a82eefc2e13285016f9c8b5ad71ec80574ae8fa9605093cd7", size = 5025457, upload-time = "2025-06-26T16:26:15.068Z" }, { url = "https://files.pythonhosted.org/packages/13/d4/2e7551a86992ece4f9a0f6eebd4fb7e312d30f1e372760e2109e721d4ce6/lxml-6.0.1-cp312-cp312-manylinux_2_26_i686.manylinux_2_28_i686.whl", hash = "sha256:32297b09ed4b17f7b3f448de87a92fb31bb8747496623483788e9f27c98c0f00", size = 5358861, upload-time = "2025-08-22T10:33:08.967Z" },
{ url = "https://files.pythonhosted.org/packages/99/b6/3a7971aa05b7be7dfebc7ab57262ec527775c2c3c5b2f43675cac0458cad/lxml-6.0.0-cp312-cp312-manylinux_2_27_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:d6e200909a119626744dd81bae409fc44134389e03fbf1d68ed2a55a2fb10991", size = 5657016, upload-time = "2025-07-03T19:19:06.008Z" }, { url = "https://files.pythonhosted.org/packages/8a/5f/cb49d727fc388bf5fd37247209bab0da11697ddc5e976ccac4826599939e/lxml-6.0.1-cp312-cp312-manylinux_2_26_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:7e18224ea241b657a157c85e9cac82c2b113ec90876e01e1f127312006233756", size = 5652569, upload-time = "2025-08-22T10:33:10.815Z" },
{ url = "https://files.pythonhosted.org/packages/69/f8/693b1a10a891197143c0673fcce5b75fc69132afa81a36e4568c12c8faba/lxml-6.0.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ca50bd612438258a91b5b3788c6621c1f05c8c478e7951899f492be42defc0da", size = 5257565, upload-time = "2025-06-26T16:26:17.906Z" }, { url = "https://files.pythonhosted.org/packages/ca/b8/66c1ef8c87ad0f958b0a23998851e610607c74849e75e83955d5641272e6/lxml-6.0.1-cp312-cp312-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a07a994d3c46cd4020c1ea566345cf6815af205b1e948213a4f0f1d392182072", size = 5252262, upload-time = "2025-08-22T10:33:12.673Z" },
{ url = "https://files.pythonhosted.org/packages/a8/96/e08ff98f2c6426c98c8964513c5dab8d6eb81dadcd0af6f0c538ada78d33/lxml-6.0.0-cp312-cp312-manylinux_2_31_armv7l.whl", hash = "sha256:c24b8efd9c0f62bad0439283c2c795ef916c5a6b75f03c17799775c7ae3c0c9e", size = 4713390, upload-time = "2025-06-26T16:26:20.292Z" }, { url = "https://files.pythonhosted.org/packages/1a/ef/131d3d6b9590e64fdbb932fbc576b81fcc686289da19c7cb796257310e82/lxml-6.0.1-cp312-cp312-manylinux_2_31_armv7l.whl", hash = "sha256:2287fadaa12418a813b05095485c286c47ea58155930cfbd98c590d25770e225", size = 4710309, upload-time = "2025-08-22T10:33:14.952Z" },
{ url = "https://files.pythonhosted.org/packages/a8/83/6184aba6cc94d7413959f6f8f54807dc318fdcd4985c347fe3ea6937f772/lxml-6.0.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:afd27d8629ae94c5d863e32ab0e1d5590371d296b87dae0a751fb22bf3685741", size = 5066103, upload-time = "2025-06-26T16:26:22.765Z" }, { url = "https://files.pythonhosted.org/packages/bc/3f/07f48ae422dce44902309aa7ed386c35310929dc592439c403ec16ef9137/lxml-6.0.1-cp312-cp312-manylinux_2_38_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:b4e597efca032ed99f418bd21314745522ab9fa95af33370dcee5533f7f70136", size = 5265786, upload-time = "2025-08-22T10:33:16.721Z" },
{ url = "https://files.pythonhosted.org/packages/ee/01/8bf1f4035852d0ff2e36a4d9aacdbcc57e93a6cd35a54e05fa984cdf73ab/lxml-6.0.0-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:54c4855eabd9fc29707d30141be99e5cd1102e7d2258d2892314cf4c110726c3", size = 4791428, upload-time = "2025-06-26T16:26:26.461Z" }, { url = "https://files.pythonhosted.org/packages/11/c7/125315d7b14ab20d9155e8316f7d287a4956098f787c22d47560b74886c4/lxml-6.0.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:9696d491f156226decdd95d9651c6786d43701e49f32bf23715c975539aa2b3b", size = 5062272, upload-time = "2025-08-22T10:33:18.478Z" },
{ url = "https://files.pythonhosted.org/packages/29/31/c0267d03b16954a85ed6b065116b621d37f559553d9339c7dcc4943a76f1/lxml-6.0.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:c907516d49f77f6cd8ead1322198bdfd902003c3c330c77a1c5f3cc32a0e4d16", size = 5678523, upload-time = "2025-07-03T19:19:09.837Z" }, { url = "https://files.pythonhosted.org/packages/8b/c3/51143c3a5fc5168a7c3ee626418468ff20d30f5a59597e7b156c1e61fba8/lxml-6.0.1-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:e4e3cd3585f3c6f87cdea44cda68e692cc42a012f0131d25957ba4ce755241a7", size = 4786955, upload-time = "2025-08-22T10:33:20.34Z" },
{ url = "https://files.pythonhosted.org/packages/5c/f7/5495829a864bc5f8b0798d2b52a807c89966523140f3d6fa3a58ab6720ea/lxml-6.0.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:36531f81c8214e293097cd2b7873f178997dae33d3667caaae8bdfb9666b76c0", size = 5281290, upload-time = "2025-06-26T16:26:29.406Z" }, { url = "https://files.pythonhosted.org/packages/11/86/73102370a420ec4529647b31c4a8ce8c740c77af3a5fae7a7643212d6f6e/lxml-6.0.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:45cbc92f9d22c28cd3b97f8d07fcefa42e569fbd587dfdac76852b16a4924277", size = 5673557, upload-time = "2025-08-22T10:33:22.282Z" },
{ url = "https://files.pythonhosted.org/packages/79/56/6b8edb79d9ed294ccc4e881f4db1023af56ba451909b9ce79f2a2cd7c532/lxml-6.0.0-cp312-cp312-win32.whl", hash = "sha256:690b20e3388a7ec98e899fd54c924e50ba6693874aa65ef9cb53de7f7de9d64a", size = 3613495, upload-time = "2025-06-26T16:26:31.588Z" }, { url = "https://files.pythonhosted.org/packages/d7/2d/aad90afaec51029aef26ef773b8fd74a9e8706e5e2f46a57acd11a421c02/lxml-6.0.1-cp312-cp312-musllinux_1_2_riscv64.whl", hash = "sha256:f8c9bcfd2e12299a442fba94459adf0b0d001dbc68f1594439bfa10ad1ecb74b", size = 5254211, upload-time = "2025-08-22T10:33:24.15Z" },
{ url = "https://files.pythonhosted.org/packages/0b/1e/cc32034b40ad6af80b6fd9b66301fc0f180f300002e5c3eb5a6110a93317/lxml-6.0.0-cp312-cp312-win_amd64.whl", hash = "sha256:310b719b695b3dd442cdfbbe64936b2f2e231bb91d998e99e6f0daf991a3eba3", size = 4014711, upload-time = "2025-06-26T16:26:33.723Z" }, { url = "https://files.pythonhosted.org/packages/63/01/c9e42c8c2d8b41f4bdefa42ab05448852e439045f112903dd901b8fbea4d/lxml-6.0.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:1e9dc2b9f1586e7cd77753eae81f8d76220eed9b768f337dc83a3f675f2f0cf9", size = 5275817, upload-time = "2025-08-22T10:33:26.007Z" },
{ url = "https://files.pythonhosted.org/packages/55/10/dc8e5290ae4c94bdc1a4c55865be7e1f31dfd857a88b21cbba68b5fea61b/lxml-6.0.0-cp312-cp312-win_arm64.whl", hash = "sha256:8cb26f51c82d77483cdcd2b4a53cda55bbee29b3c2f3ddeb47182a2a9064e4eb", size = 3674431, upload-time = "2025-06-26T16:26:35.959Z" }, { url = "https://files.pythonhosted.org/packages/bc/1f/962ea2696759abe331c3b0e838bb17e92224f39c638c2068bf0d8345e913/lxml-6.0.1-cp312-cp312-win32.whl", hash = "sha256:987ad5c3941c64031f59c226167f55a04d1272e76b241bfafc968bdb778e07fb", size = 3610889, upload-time = "2025-08-22T10:33:28.169Z" },
{ url = "https://files.pythonhosted.org/packages/41/e2/22c86a990b51b44442b75c43ecb2f77b8daba8c4ba63696921966eac7022/lxml-6.0.1-cp312-cp312-win_amd64.whl", hash = "sha256:abb05a45394fd76bf4a60c1b7bec0e6d4e8dfc569fc0e0b1f634cd983a006ddc", size = 4010925, upload-time = "2025-08-22T10:33:29.874Z" },
{ url = "https://files.pythonhosted.org/packages/b2/21/dc0c73325e5eb94ef9c9d60dbb5dcdcb2e7114901ea9509735614a74e75a/lxml-6.0.1-cp312-cp312-win_arm64.whl", hash = "sha256:c4be29bce35020d8579d60aa0a4e95effd66fcfce31c46ffddf7e5422f73a299", size = 3671922, upload-time = "2025-08-22T10:33:31.535Z" },
{ url = "https://files.pythonhosted.org/packages/41/37/41961f53f83ded57b37e65e4f47d1c6c6ef5fd02cb1d6ffe028ba0efa7d4/lxml-6.0.1-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:b556aaa6ef393e989dac694b9c95761e32e058d5c4c11ddeef33f790518f7a5e", size = 3903412, upload-time = "2025-08-22T10:37:40.758Z" },
{ url = "https://files.pythonhosted.org/packages/3d/47/8631ea73f3dc776fb6517ccde4d5bd5072f35f9eacbba8c657caa4037a69/lxml-6.0.1-pp311-pypy311_pp73-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:64fac7a05ebb3737b79fd89fe5a5b6c5546aac35cfcfd9208eb6e5d13215771c", size = 4224810, upload-time = "2025-08-22T10:37:42.839Z" },
{ url = "https://files.pythonhosted.org/packages/3d/b8/39ae30ca3b1516729faeef941ed84bf8f12321625f2644492ed8320cb254/lxml-6.0.1-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:038d3c08babcfce9dc89aaf498e6da205efad5b7106c3b11830a488d4eadf56b", size = 4329221, upload-time = "2025-08-22T10:37:45.223Z" },
{ url = "https://files.pythonhosted.org/packages/9c/ea/048dea6cdfc7a72d40ae8ed7e7d23cf4a6b6a6547b51b492a3be50af0e80/lxml-6.0.1-pp311-pypy311_pp73-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:445f2cee71c404ab4259bc21e20339a859f75383ba2d7fb97dfe7c163994287b", size = 4270228, upload-time = "2025-08-22T10:37:47.276Z" },
{ url = "https://files.pythonhosted.org/packages/6b/d4/c2b46e432377c45d611ae2f669aa47971df1586c1a5240675801d0f02bac/lxml-6.0.1-pp311-pypy311_pp73-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:e352d8578e83822d70bea88f3d08b9912528e4c338f04ab707207ab12f4b7aac", size = 4416077, upload-time = "2025-08-22T10:37:49.822Z" },
{ url = "https://files.pythonhosted.org/packages/b6/db/8f620f1ac62cf32554821b00b768dd5957ac8e3fd051593532be5b40b438/lxml-6.0.1-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:51bd5d1a9796ca253db6045ab45ca882c09c071deafffc22e06975b7ace36300", size = 3518127, upload-time = "2025-08-22T10:37:51.66Z" },
] ]
[[package]] [[package]]
@ -838,7 +855,7 @@ wheels = [
[[package]] [[package]]
name = "matplotlib" name = "matplotlib"
version = "3.10.5" version = "3.10.6"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
dependencies = [ dependencies = [
{ name = "contourpy" }, { name = "contourpy" },
@ -851,25 +868,25 @@ dependencies = [
{ name = "pyparsing" }, { name = "pyparsing" },
{ name = "python-dateutil" }, { name = "python-dateutil" },
] ]
sdist = { url = "https://files.pythonhosted.org/packages/43/91/f2939bb60b7ebf12478b030e0d7f340247390f402b3b189616aad790c366/matplotlib-3.10.5.tar.gz", hash = "sha256:352ed6ccfb7998a00881692f38b4ca083c691d3e275b4145423704c34c909076", size = 34804044, upload-time = "2025-07-31T18:09:33.805Z" } sdist = { url = "https://files.pythonhosted.org/packages/a0/59/c3e6453a9676ffba145309a73c462bb407f4400de7de3f2b41af70720a3c/matplotlib-3.10.6.tar.gz", hash = "sha256:ec01b645840dd1996df21ee37f208cd8ba57644779fa20464010638013d3203c", size = 34804264, upload-time = "2025-08-30T00:14:25.137Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/aa/c7/1f2db90a1d43710478bb1e9b57b162852f79234d28e4f48a28cc415aa583/matplotlib-3.10.5-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:dcfc39c452c6a9f9028d3e44d2d721484f665304857188124b505b2c95e1eecf", size = 8239216, upload-time = "2025-07-31T18:07:51.947Z" }, { url = "https://files.pythonhosted.org/packages/80/d6/5d3665aa44c49005aaacaa68ddea6fcb27345961cd538a98bb0177934ede/matplotlib-3.10.6-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:905b60d1cb0ee604ce65b297b61cf8be9f4e6cfecf95a3fe1c388b5266bc8f4f", size = 8257527, upload-time = "2025-08-30T00:12:45.31Z" },
{ url = "https://files.pythonhosted.org/packages/82/6d/ca6844c77a4f89b1c9e4d481c412e1d1dbabf2aae2cbc5aa2da4a1d6683e/matplotlib-3.10.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:903352681b59f3efbf4546985142a9686ea1d616bb054b09a537a06e4b892ccf", size = 8102130, upload-time = "2025-07-31T18:07:53.65Z" }, { url = "https://files.pythonhosted.org/packages/8c/af/30ddefe19ca67eebd70047dabf50f899eaff6f3c5e6a1a7edaecaf63f794/matplotlib-3.10.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:7bac38d816637343e53d7185d0c66677ff30ffb131044a81898b5792c956ba76", size = 8119583, upload-time = "2025-08-30T00:12:47.236Z" },
{ url = "https://files.pythonhosted.org/packages/1d/1e/5e187a30cc673a3e384f3723e5f3c416033c1d8d5da414f82e4e731128ea/matplotlib-3.10.5-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:080c3676a56b8ee1c762bcf8fca3fe709daa1ee23e6ef06ad9f3fc17332f2d2a", size = 8666471, upload-time = "2025-07-31T18:07:55.304Z" }, { url = "https://files.pythonhosted.org/packages/d3/29/4a8650a3dcae97fa4f375d46efcb25920d67b512186f8a6788b896062a81/matplotlib-3.10.6-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:942a8de2b5bfff1de31d95722f702e2966b8a7e31f4e68f7cd963c7cd8861cf6", size = 8692682, upload-time = "2025-08-30T00:12:48.781Z" },
{ url = "https://files.pythonhosted.org/packages/03/c0/95540d584d7d645324db99a845ac194e915ef75011a0d5e19e1b5cee7e69/matplotlib-3.10.5-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:4b4984d5064a35b6f66d2c11d668565f4389b1119cc64db7a4c1725bc11adffc", size = 9500518, upload-time = "2025-07-31T18:07:57.199Z" }, { url = "https://files.pythonhosted.org/packages/aa/d3/b793b9cb061cfd5d42ff0f69d1822f8d5dbc94e004618e48a97a8373179a/matplotlib-3.10.6-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a3276c85370bc0dfca051ec65c5817d1e0f8f5ce1b7787528ec8ed2d524bbc2f", size = 9521065, upload-time = "2025-08-30T00:12:50.602Z" },
{ url = "https://files.pythonhosted.org/packages/ba/2e/e019352099ea58b4169adb9c6e1a2ad0c568c6377c2b677ee1f06de2adc7/matplotlib-3.10.5-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:3967424121d3a46705c9fa9bdb0931de3228f13f73d7bb03c999c88343a89d89", size = 9552372, upload-time = "2025-07-31T18:07:59.41Z" }, { url = "https://files.pythonhosted.org/packages/f7/c5/53de5629f223c1c66668d46ac2621961970d21916a4bc3862b174eb2a88f/matplotlib-3.10.6-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:9df5851b219225731f564e4b9e7f2ac1e13c9e6481f941b5631a0f8e2d9387ce", size = 9576888, upload-time = "2025-08-30T00:12:52.92Z" },
{ url = "https://files.pythonhosted.org/packages/b7/81/3200b792a5e8b354f31f4101ad7834743ad07b6d620259f2059317b25e4d/matplotlib-3.10.5-cp311-cp311-win_amd64.whl", hash = "sha256:33775bbeb75528555a15ac29396940128ef5613cf9a2d31fb1bfd18b3c0c0903", size = 8100634, upload-time = "2025-07-31T18:08:01.801Z" }, { url = "https://files.pythonhosted.org/packages/fc/8e/0a18d6d7d2d0a2e66585032a760d13662e5250c784d53ad50434e9560991/matplotlib-3.10.6-cp311-cp311-win_amd64.whl", hash = "sha256:abb5d9478625dd9c9eb51a06d39aae71eda749ae9b3138afb23eb38824026c7e", size = 8115158, upload-time = "2025-08-30T00:12:54.863Z" },
{ url = "https://files.pythonhosted.org/packages/52/46/a944f6f0c1f5476a0adfa501969d229ce5ae60cf9a663be0e70361381f89/matplotlib-3.10.5-cp311-cp311-win_arm64.whl", hash = "sha256:c61333a8e5e6240e73769d5826b9a31d8b22df76c0778f8480baf1b4b01c9420", size = 7978880, upload-time = "2025-07-31T18:08:03.407Z" }, { url = "https://files.pythonhosted.org/packages/07/b3/1a5107bb66c261e23b9338070702597a2d374e5aa7004b7adfc754fbed02/matplotlib-3.10.6-cp311-cp311-win_arm64.whl", hash = "sha256:886f989ccfae63659183173bb3fced7fd65e9eb793c3cc21c273add368536951", size = 7992444, upload-time = "2025-08-30T00:12:57.067Z" },
{ url = "https://files.pythonhosted.org/packages/66/1e/c6f6bcd882d589410b475ca1fc22e34e34c82adff519caf18f3e6dd9d682/matplotlib-3.10.5-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:00b6feadc28a08bd3c65b2894f56cf3c94fc8f7adcbc6ab4516ae1e8ed8f62e2", size = 8253056, upload-time = "2025-07-31T18:08:05.385Z" }, { url = "https://files.pythonhosted.org/packages/ea/1a/7042f7430055d567cc3257ac409fcf608599ab27459457f13772c2d9778b/matplotlib-3.10.6-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:31ca662df6a80bd426f871105fdd69db7543e28e73a9f2afe80de7e531eb2347", size = 8272404, upload-time = "2025-08-30T00:12:59.112Z" },
{ url = "https://files.pythonhosted.org/packages/53/e6/d6f7d1b59413f233793dda14419776f5f443bcccb2dfc84b09f09fe05dbe/matplotlib-3.10.5-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ee98a5c5344dc7f48dc261b6ba5d9900c008fc12beb3fa6ebda81273602cc389", size = 8110131, upload-time = "2025-07-31T18:08:07.293Z" }, { url = "https://files.pythonhosted.org/packages/a9/5d/1d5f33f5b43f4f9e69e6a5fe1fb9090936ae7bc8e2ff6158e7a76542633b/matplotlib-3.10.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:1678bb61d897bb4ac4757b5ecfb02bfb3fddf7f808000fb81e09c510712fda75", size = 8128262, upload-time = "2025-08-30T00:13:01.141Z" },
{ url = "https://files.pythonhosted.org/packages/66/2b/bed8a45e74957549197a2ac2e1259671cd80b55ed9e1fe2b5c94d88a9202/matplotlib-3.10.5-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:a17e57e33de901d221a07af32c08870ed4528db0b6059dce7d7e65c1122d4bea", size = 8669603, upload-time = "2025-07-31T18:08:09.064Z" }, { url = "https://files.pythonhosted.org/packages/67/c3/135fdbbbf84e0979712df58e5e22b4f257b3f5e52a3c4aacf1b8abec0d09/matplotlib-3.10.6-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:56cd2d20842f58c03d2d6e6c1f1cf5548ad6f66b91e1e48f814e4fb5abd1cb95", size = 8697008, upload-time = "2025-08-30T00:13:03.24Z" },
{ url = "https://files.pythonhosted.org/packages/7e/a7/315e9435b10d057f5e52dfc603cd353167ae28bb1a4e033d41540c0067a4/matplotlib-3.10.5-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:97b9d6443419085950ee4a5b1ee08c363e5c43d7176e55513479e53669e88468", size = 9508127, upload-time = "2025-07-31T18:08:10.845Z" }, { url = "https://files.pythonhosted.org/packages/9c/be/c443ea428fb2488a3ea7608714b1bd85a82738c45da21b447dc49e2f8e5d/matplotlib-3.10.6-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:662df55604a2f9a45435566d6e2660e41efe83cd94f4288dfbf1e6d1eae4b0bb", size = 9530166, upload-time = "2025-08-30T00:13:05.951Z" },
{ url = "https://files.pythonhosted.org/packages/7f/d9/edcbb1f02ca99165365d2768d517898c22c6040187e2ae2ce7294437c413/matplotlib-3.10.5-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ceefe5d40807d29a66ae916c6a3915d60ef9f028ce1927b84e727be91d884369", size = 9566926, upload-time = "2025-07-31T18:08:13.186Z" }, { url = "https://files.pythonhosted.org/packages/a9/35/48441422b044d74034aea2a3e0d1a49023f12150ebc58f16600132b9bbaf/matplotlib-3.10.6-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:08f141d55148cd1fc870c3387d70ca4df16dee10e909b3b038782bd4bda6ea07", size = 9593105, upload-time = "2025-08-30T00:13:08.356Z" },
{ url = "https://files.pythonhosted.org/packages/3b/d9/6dd924ad5616c97b7308e6320cf392c466237a82a2040381163b7500510a/matplotlib-3.10.5-cp312-cp312-win_amd64.whl", hash = "sha256:c04cba0f93d40e45b3c187c6c52c17f24535b27d545f757a2fffebc06c12b98b", size = 8107599, upload-time = "2025-07-31T18:08:15.116Z" }, { url = "https://files.pythonhosted.org/packages/45/c3/994ef20eb4154ab84cc08d033834555319e4af970165e6c8894050af0b3c/matplotlib-3.10.6-cp312-cp312-win_amd64.whl", hash = "sha256:590f5925c2d650b5c9d813c5b3b5fc53f2929c3f8ef463e4ecfa7e052044fb2b", size = 8122784, upload-time = "2025-08-30T00:13:10.367Z" },
{ url = "https://files.pythonhosted.org/packages/0e/f3/522dc319a50f7b0279fbe74f86f7a3506ce414bc23172098e8d2bdf21894/matplotlib-3.10.5-cp312-cp312-win_arm64.whl", hash = "sha256:a41bcb6e2c8e79dc99c5511ae6f7787d2fb52efd3d805fff06d5d4f667db16b2", size = 7978173, upload-time = "2025-07-31T18:08:21.518Z" }, { url = "https://files.pythonhosted.org/packages/57/b8/5c85d9ae0e40f04e71bedb053aada5d6bab1f9b5399a0937afb5d6b02d98/matplotlib-3.10.6-cp312-cp312-win_arm64.whl", hash = "sha256:f44c8d264a71609c79a78d50349e724f5d5fc3684ead7c2a473665ee63d868aa", size = 7992823, upload-time = "2025-08-30T00:13:12.24Z" },
{ url = "https://files.pythonhosted.org/packages/dc/d6/e921be4e1a5f7aca5194e1f016cb67ec294548e530013251f630713e456d/matplotlib-3.10.5-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:160e125da27a749481eaddc0627962990f6029811dbeae23881833a011a0907f", size = 8233224, upload-time = "2025-07-31T18:09:27.512Z" }, { url = "https://files.pythonhosted.org/packages/12/bb/02c35a51484aae5f49bd29f091286e7af5f3f677a9736c58a92b3c78baeb/matplotlib-3.10.6-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:f2d684c3204fa62421bbf770ddfebc6b50130f9cad65531eeba19236d73bb488", size = 8252296, upload-time = "2025-08-30T00:14:19.49Z" },
{ url = "https://files.pythonhosted.org/packages/ec/74/a2b9b04824b9c349c8f1b2d21d5af43fa7010039427f2b133a034cb09e59/matplotlib-3.10.5-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:ac3d50760394d78a3c9be6b28318fe22b494c4fcf6407e8fd4794b538251899b", size = 8098539, upload-time = "2025-07-31T18:09:29.629Z" }, { url = "https://files.pythonhosted.org/packages/7d/85/41701e3092005aee9a2445f5ee3904d9dbd4a7df7a45905ffef29b7ef098/matplotlib-3.10.6-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:6f4a69196e663a41d12a728fab8751177215357906436804217d6d9cf0d4d6cf", size = 8116749, upload-time = "2025-08-30T00:14:21.344Z" },
{ url = "https://files.pythonhosted.org/packages/fc/66/cd29ebc7f6c0d2a15d216fb572573e8fc38bd5d6dec3bd9d7d904c0949f7/matplotlib-3.10.5-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:6c49465bf689c4d59d174d0c7795fb42a21d4244d11d70e52b8011987367ac61", size = 8672192, upload-time = "2025-07-31T18:09:31.407Z" }, { url = "https://files.pythonhosted.org/packages/16/53/8d8fa0ea32a8c8239e04d022f6c059ee5e1b77517769feccd50f1df43d6d/matplotlib-3.10.6-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:4d6ca6ef03dfd269f4ead566ec6f3fb9becf8dab146fb999022ed85ee9f6b3eb", size = 8693933, upload-time = "2025-08-30T00:14:22.942Z" },
] ]
[[package]] [[package]]
@ -973,6 +990,27 @@ wheels = [
{ url = "https://files.pythonhosted.org/packages/9f/d4/029f984e8d3f3b6b726bd33cafc473b75e9e44c0f7e80a5b29abc466bdea/mkdocs_get_deps-0.2.0-py3-none-any.whl", hash = "sha256:2bf11d0b133e77a0dd036abeeb06dec8775e46efa526dc70667d8863eefc6134", size = 9521, upload-time = "2023-11-20T17:51:08.587Z" }, { url = "https://files.pythonhosted.org/packages/9f/d4/029f984e8d3f3b6b726bd33cafc473b75e9e44c0f7e80a5b29abc466bdea/mkdocs_get_deps-0.2.0-py3-none-any.whl", hash = "sha256:2bf11d0b133e77a0dd036abeeb06dec8775e46efa526dc70667d8863eefc6134", size = 9521, upload-time = "2023-11-20T17:51:08.587Z" },
] ]
[[package]]
name = "ml-dtypes"
version = "0.5.3"
source = { registry = "https://pypi.org/simple" }
dependencies = [
{ name = "numpy" },
]
sdist = { url = "https://files.pythonhosted.org/packages/78/a7/aad060393123cfb383956dca68402aff3db1e1caffd5764887ed5153f41b/ml_dtypes-0.5.3.tar.gz", hash = "sha256:95ce33057ba4d05df50b1f3cfefab22e351868a843b3b15a46c65836283670c9", size = 692316, upload-time = "2025-07-29T18:39:19.454Z" }
wheels = [
{ url = "https://files.pythonhosted.org/packages/af/f1/720cb1409b5d0c05cff9040c0e9fba73fa4c67897d33babf905d5d46a070/ml_dtypes-0.5.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4a177b882667c69422402df6ed5c3428ce07ac2c1f844d8a1314944651439458", size = 667412, upload-time = "2025-07-29T18:38:25.275Z" },
{ url = "https://files.pythonhosted.org/packages/6a/d5/05861ede5d299f6599f86e6bc1291714e2116d96df003cfe23cc54bcc568/ml_dtypes-0.5.3-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:9849ce7267444c0a717c80c6900997de4f36e2815ce34ac560a3edb2d9a64cd2", size = 4964606, upload-time = "2025-07-29T18:38:27.045Z" },
{ url = "https://files.pythonhosted.org/packages/db/dc/72992b68de367741bfab8df3b3fe7c29f982b7279d341aa5bf3e7ef737ea/ml_dtypes-0.5.3-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:c3f5ae0309d9f888fd825c2e9d0241102fadaca81d888f26f845bc8c13c1e4ee", size = 4938435, upload-time = "2025-07-29T18:38:29.193Z" },
{ url = "https://files.pythonhosted.org/packages/81/1c/d27a930bca31fb07d975a2d7eaf3404f9388114463b9f15032813c98f893/ml_dtypes-0.5.3-cp311-cp311-win_amd64.whl", hash = "sha256:58e39349d820b5702bb6f94ea0cb2dc8ec62ee81c0267d9622067d8333596a46", size = 206334, upload-time = "2025-07-29T18:38:30.687Z" },
{ url = "https://files.pythonhosted.org/packages/1a/d8/6922499effa616012cb8dc445280f66d100a7ff39b35c864cfca019b3f89/ml_dtypes-0.5.3-cp311-cp311-win_arm64.whl", hash = "sha256:66c2756ae6cfd7f5224e355c893cfd617fa2f747b8bbd8996152cbdebad9a184", size = 157584, upload-time = "2025-07-29T18:38:32.187Z" },
{ url = "https://files.pythonhosted.org/packages/0d/eb/bc07c88a6ab002b4635e44585d80fa0b350603f11a2097c9d1bfacc03357/ml_dtypes-0.5.3-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:156418abeeda48ea4797db6776db3c5bdab9ac7be197c1233771e0880c304057", size = 663864, upload-time = "2025-07-29T18:38:33.777Z" },
{ url = "https://files.pythonhosted.org/packages/cf/89/11af9b0f21b99e6386b6581ab40fb38d03225f9de5f55cf52097047e2826/ml_dtypes-0.5.3-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1db60c154989af253f6c4a34e8a540c2c9dce4d770784d426945e09908fbb177", size = 4951313, upload-time = "2025-07-29T18:38:36.45Z" },
{ url = "https://files.pythonhosted.org/packages/d8/a9/b98b86426c24900b0c754aad006dce2863df7ce0bb2bcc2c02f9cc7e8489/ml_dtypes-0.5.3-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1b255acada256d1fa8c35ed07b5f6d18bc21d1556f842fbc2d5718aea2cd9e55", size = 4928805, upload-time = "2025-07-29T18:38:38.29Z" },
{ url = "https://files.pythonhosted.org/packages/50/c1/85e6be4fc09c6175f36fb05a45917837f30af9a5146a5151cb3a3f0f9e09/ml_dtypes-0.5.3-cp312-cp312-win_amd64.whl", hash = "sha256:da65e5fd3eea434ccb8984c3624bc234ddcc0d9f4c81864af611aaebcc08a50e", size = 208182, upload-time = "2025-07-29T18:38:39.72Z" },
{ url = "https://files.pythonhosted.org/packages/9e/17/cf5326d6867be057f232d0610de1458f70a8ce7b6290e4b4a277ea62b4cd/ml_dtypes-0.5.3-cp312-cp312-win_arm64.whl", hash = "sha256:8bb9cd1ce63096567f5f42851f5843b5a0ea11511e50039a7649619abfb4ba6d", size = 161560, upload-time = "2025-07-29T18:38:41.072Z" },
]
[[package]] [[package]]
name = "mouseinfo" name = "mouseinfo"
version = "0.1.3" version = "0.1.3"
@ -1147,27 +1185,28 @@ wheels = [
[[package]] [[package]]
name = "onnx" name = "onnx"
version = "1.18.0" version = "1.19.0"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
dependencies = [ dependencies = [
{ name = "ml-dtypes" },
{ name = "numpy" }, { name = "numpy" },
{ name = "protobuf" }, { name = "protobuf" },
{ name = "typing-extensions" }, { name = "typing-extensions" },
] ]
sdist = { url = "https://files.pythonhosted.org/packages/3d/60/e56e8ec44ed34006e6d4a73c92a04d9eea6163cc12440e35045aec069175/onnx-1.18.0.tar.gz", hash = "sha256:3d8dbf9e996629131ba3aa1afd1d8239b660d1f830c6688dd7e03157cccd6b9c", size = 12563009, upload-time = "2025-05-12T22:03:09.626Z" } sdist = { url = "https://files.pythonhosted.org/packages/5b/bf/b0a63ee9f3759dcd177b28c6f2cb22f2aecc6d9b3efecaabc298883caa5f/onnx-1.19.0.tar.gz", hash = "sha256:aa3f70b60f54a29015e41639298ace06adf1dd6b023b9b30f1bca91bb0db9473", size = 11949859, upload-time = "2025-08-27T02:34:27.107Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/ed/3a/a336dac4db1eddba2bf577191e5b7d3e4c26fcee5ec518a5a5b11d13540d/onnx-1.18.0-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:735e06d8d0cf250dc498f54038831401063c655a8d6e5975b2527a4e7d24be3e", size = 18281831, upload-time = "2025-05-12T22:02:06.429Z" }, { url = "https://files.pythonhosted.org/packages/db/5c/b959b17608cfb6ccf6359b39fe56a5b0b7d965b3d6e6a3c0add90812c36e/onnx-1.19.0-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:206f00c47b85b5c7af79671e3307147407991a17994c26974565aadc9e96e4e4", size = 18312580, upload-time = "2025-08-27T02:33:03.081Z" },
{ url = "https://files.pythonhosted.org/packages/02/3a/56475a111120d1e5d11939acbcbb17c92198c8e64a205cd68e00bdfd8a1f/onnx-1.18.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:73160799472e1a86083f786fecdf864cf43d55325492a9b5a1cfa64d8a523ecc", size = 17424359, upload-time = "2025-05-12T22:02:09.866Z" }, { url = "https://files.pythonhosted.org/packages/2c/ee/ac052bbbc832abe0debb784c2c57f9582444fb5f51d63c2967fd04432444/onnx-1.19.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:4d7bee94abaac28988b50da675ae99ef8dd3ce16210d591fbd0b214a5930beb3", size = 18029165, upload-time = "2025-08-27T02:33:05.771Z" },
{ url = "https://files.pythonhosted.org/packages/cf/03/5eb5e9ef446ed9e78c4627faf3c1bc25e0f707116dd00e9811de232a8df5/onnx-1.18.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6acafb3823238bbe8f4340c7ac32fb218689442e074d797bee1c5c9a02fdae75", size = 17586006, upload-time = "2025-05-12T22:02:13.217Z" }, { url = "https://files.pythonhosted.org/packages/5c/c9/8687ba0948d46fd61b04e3952af9237883bbf8f16d716e7ed27e688d73b8/onnx-1.19.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:7730b96b68c0c354bbc7857961bb4909b9aaa171360a8e3708d0a4c749aaadeb", size = 18202125, upload-time = "2025-08-27T02:33:09.325Z" },
{ url = "https://files.pythonhosted.org/packages/b0/4e/70943125729ce453271a6e46bb847b4a612496f64db6cbc6cb1f49f41ce1/onnx-1.18.0-cp311-cp311-win32.whl", hash = "sha256:4c8c4bbda760c654e65eaffddb1a7de71ec02e60092d33f9000521f897c99be9", size = 15734988, upload-time = "2025-05-12T22:02:16.561Z" }, { url = "https://files.pythonhosted.org/packages/e2/16/6249c013e81bd689f46f96c7236d7677f1af5dd9ef22746716b48f10e506/onnx-1.19.0-cp311-cp311-win32.whl", hash = "sha256:7cb7a3ad8059d1a0dfdc5e0a98f71837d82002e441f112825403b137227c2c97", size = 16332738, upload-time = "2025-08-27T02:33:12.448Z" },
{ url = "https://files.pythonhosted.org/packages/44/b0/435fd764011911e8f599e3361f0f33425b1004662c1ea33a0ad22e43db2d/onnx-1.18.0-cp311-cp311-win_amd64.whl", hash = "sha256:a5810194f0f6be2e58c8d6dedc6119510df7a14280dd07ed5f0f0a85bd74816a", size = 15849576, upload-time = "2025-05-12T22:02:19.569Z" }, { url = "https://files.pythonhosted.org/packages/6a/28/34a1e2166e418c6a78e5c82e66f409d9da9317832f11c647f7d4e23846a6/onnx-1.19.0-cp311-cp311-win_amd64.whl", hash = "sha256:d75452a9be868bd30c3ef6aa5991df89bbfe53d0d90b2325c5e730fbd91fff85", size = 16452303, upload-time = "2025-08-27T02:33:15.176Z" },
{ url = "https://files.pythonhosted.org/packages/6c/f0/9e31f4b4626d60f1c034f71b411810bc9fafe31f4e7dd3598effd1b50e05/onnx-1.18.0-cp311-cp311-win_arm64.whl", hash = "sha256:aa1b7483fac6cdec26922174fc4433f8f5c2f239b1133c5625063bb3b35957d0", size = 15822961, upload-time = "2025-05-12T22:02:22.735Z" }, { url = "https://files.pythonhosted.org/packages/e6/b7/639664626e5ba8027860c4d2a639ee02b37e9c322215c921e9222513c3aa/onnx-1.19.0-cp311-cp311-win_arm64.whl", hash = "sha256:23c7959370d7b3236f821e609b0af7763cff7672a758e6c1fc877bac099e786b", size = 16425340, upload-time = "2025-08-27T02:33:17.78Z" },
{ url = "https://files.pythonhosted.org/packages/a7/fe/16228aca685392a7114625b89aae98b2dc4058a47f0f467a376745efe8d0/onnx-1.18.0-cp312-cp312-macosx_12_0_universal2.whl", hash = "sha256:521bac578448667cbb37c50bf05b53c301243ede8233029555239930996a625b", size = 18285770, upload-time = "2025-05-12T22:02:26.116Z" }, { url = "https://files.pythonhosted.org/packages/0d/94/f56f6ca5e2f921b28c0f0476705eab56486b279f04e1d568ed64c14e7764/onnx-1.19.0-cp312-cp312-macosx_12_0_universal2.whl", hash = "sha256:61d94e6498ca636756f8f4ee2135708434601b2892b7c09536befb19bc8ca007", size = 18322331, upload-time = "2025-08-27T02:33:20.373Z" },
{ url = "https://files.pythonhosted.org/packages/1e/77/ba50a903a9b5e6f9be0fa50f59eb2fca4a26ee653375408fbc72c3acbf9f/onnx-1.18.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e4da451bf1c5ae381f32d430004a89f0405bc57a8471b0bddb6325a5b334aa40", size = 17421291, upload-time = "2025-05-12T22:02:29.645Z" }, { url = "https://files.pythonhosted.org/packages/c8/00/8cc3f3c40b54b28f96923380f57c9176872e475face726f7d7a78bd74098/onnx-1.19.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:224473354462f005bae985c72028aaa5c85ab11de1b71d55b06fdadd64a667dd", size = 18027513, upload-time = "2025-08-27T02:33:23.44Z" },
{ url = "https://files.pythonhosted.org/packages/11/23/25ec2ba723ac62b99e8fed6d7b59094dadb15e38d4c007331cc9ae3dfa5f/onnx-1.18.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:99afac90b4cdb1471432203c3c1f74e16549c526df27056d39f41a9a47cfb4af", size = 17584084, upload-time = "2025-05-12T22:02:32.789Z" }, { url = "https://files.pythonhosted.org/packages/61/90/17c4d2566fd0117a5e412688c9525f8950d467f477fbd574e6b32bc9cb8d/onnx-1.19.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1ae475c85c89bc4d1f16571006fd21a3e7c0e258dd2c091f6e8aafb083d1ed9b", size = 18202278, upload-time = "2025-08-27T02:33:26.103Z" },
{ url = "https://files.pythonhosted.org/packages/6a/4d/2c253a36070fb43f340ff1d2c450df6a9ef50b938adcd105693fee43c4ee/onnx-1.18.0-cp312-cp312-win32.whl", hash = "sha256:ee159b41a3ae58d9c7341cf432fc74b96aaf50bd7bb1160029f657b40dc69715", size = 15734892, upload-time = "2025-05-12T22:02:35.527Z" }, { url = "https://files.pythonhosted.org/packages/bc/6e/a9383d9cf6db4ac761a129b081e9fa5d0cd89aad43cf1e3fc6285b915c7d/onnx-1.19.0-cp312-cp312-win32.whl", hash = "sha256:323f6a96383a9cdb3960396cffea0a922593d221f3929b17312781e9f9b7fb9f", size = 16333080, upload-time = "2025-08-27T02:33:28.559Z" },
{ url = "https://files.pythonhosted.org/packages/e8/92/048ba8fafe6b2b9a268ec2fb80def7e66c0b32ab2cae74de886981f05a27/onnx-1.18.0-cp312-cp312-win_amd64.whl", hash = "sha256:102c04edc76b16e9dfeda5a64c1fccd7d3d2913b1544750c01d38f1ac3c04e05", size = 15850336, upload-time = "2025-05-12T22:02:38.545Z" }, { url = "https://files.pythonhosted.org/packages/a7/2e/3ff480a8c1fa7939662bdc973e41914add2d4a1f2b8572a3c39c2e4982e5/onnx-1.19.0-cp312-cp312-win_amd64.whl", hash = "sha256:50220f3499a499b1a15e19451a678a58e22ad21b34edf2c844c6ef1d9febddc2", size = 16453927, upload-time = "2025-08-27T02:33:31.177Z" },
{ url = "https://files.pythonhosted.org/packages/a1/66/bbc4ffedd44165dcc407a51ea4c592802a5391ce3dc94aa5045350f64635/onnx-1.18.0-cp312-cp312-win_arm64.whl", hash = "sha256:911b37d724a5d97396f3c2ef9ea25361c55cbc9aa18d75b12a52b620b67145af", size = 15823802, upload-time = "2025-05-12T22:02:42.037Z" }, { url = "https://files.pythonhosted.org/packages/57/37/ad500945b1b5c154fe9d7b826b30816ebd629d10211ea82071b5bcc30aa4/onnx-1.19.0-cp312-cp312-win_arm64.whl", hash = "sha256:efb768299580b786e21abe504e1652ae6189f0beed02ab087cd841cb4bb37e43", size = 16426022, upload-time = "2025-08-27T02:33:33.515Z" },
] ]
[[package]] [[package]]
@ -1235,6 +1274,7 @@ dev = [
{ name = "azure-storage-blob" }, { name = "azure-storage-blob" },
{ name = "dbus-next" }, { name = "dbus-next" },
{ name = "dictdiffer" }, { name = "dictdiffer" },
{ name = "jeepney" },
{ name = "matplotlib" }, { name = "matplotlib" },
{ name = "opencv-python-headless" }, { name = "opencv-python-headless" },
{ name = "parameterized" }, { name = "parameterized" },
@ -1291,6 +1331,7 @@ requires-dist = [
{ name = "future-fstrings" }, { name = "future-fstrings" },
{ name = "hypothesis", marker = "extra == 'testing'", specifier = "==6.47.*" }, { name = "hypothesis", marker = "extra == 'testing'", specifier = "==6.47.*" },
{ name = "inputs" }, { name = "inputs" },
{ name = "jeepney", marker = "extra == 'dev'" },
{ name = "jinja2", marker = "extra == 'docs'" }, { name = "jinja2", marker = "extra == 'docs'" },
{ name = "json-rpc" }, { name = "json-rpc" },
{ name = "libusb1" }, { name = "libusb1" },
@ -1459,11 +1500,11 @@ wheels = [
[[package]] [[package]]
name = "platformdirs" name = "platformdirs"
version = "4.3.8" version = "4.4.0"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/fe/8b/3c73abc9c759ecd3f1f7ceff6685840859e8070c4d947c93fae71f6a0bf2/platformdirs-4.3.8.tar.gz", hash = "sha256:3d512d96e16bcb959a814c9f348431070822a6496326a4be0911c40b5a74c2bc", size = 21362, upload-time = "2025-05-07T22:47:42.121Z" } sdist = { url = "https://files.pythonhosted.org/packages/23/e8/21db9c9987b0e728855bd57bff6984f67952bea55d6f75e055c46b5383e8/platformdirs-4.4.0.tar.gz", hash = "sha256:ca753cf4d81dc309bc67b0ea38fd15dc97bc30ce419a7f58d13eb3bf14c4febf", size = 21634, upload-time = "2025-08-26T14:32:04.268Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/fe/39/979e8e21520d4e47a0bbe349e2713c0aac6f3d853d0e5b34d76206c439aa/platformdirs-4.3.8-py3-none-any.whl", hash = "sha256:ff7059bb7eb1179e2685604f4aaf157cfd9535242bd23742eadc3c13542139b4", size = 18567, upload-time = "2025-05-07T22:47:40.376Z" }, { url = "https://files.pythonhosted.org/packages/40/4b/2028861e724d3bd36227adfa20d3fd24c3fc6d52032f4a93c133be5d17ce/platformdirs-4.4.0-py3-none-any.whl", hash = "sha256:abd01743f24e5287cd7a5db3752faf1a2d65353f38ec26d98e25a6db65958c85", size = 18654, upload-time = "2025-08-26T14:32:02.735Z" },
] ]
[[package]] [[package]]
@ -4452,38 +4493,38 @@ wheels = [
[[package]] [[package]]
name = "pyzmq" name = "pyzmq"
version = "27.0.1" version = "27.0.2"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
dependencies = [ dependencies = [
{ name = "cffi", marker = "implementation_name == 'pypy'" }, { name = "cffi", marker = "implementation_name == 'pypy'" },
] ]
sdist = { url = "https://files.pythonhosted.org/packages/30/5f/557d2032a2f471edbcc227da724c24a1c05887b5cda1e3ae53af98b9e0a5/pyzmq-27.0.1.tar.gz", hash = "sha256:45c549204bc20e7484ffd2555f6cf02e572440ecf2f3bdd60d4404b20fddf64b", size = 281158, upload-time = "2025-08-03T05:05:40.352Z" } sdist = { url = "https://files.pythonhosted.org/packages/f8/66/159f38d184f08b5f971b467f87b1ab142ab1320d5200825c824b32b84b66/pyzmq-27.0.2.tar.gz", hash = "sha256:b398dd713b18de89730447347e96a0240225e154db56e35b6bb8447ffdb07798", size = 281440, upload-time = "2025-08-21T04:23:26.334Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/ae/18/a8e0da6ababbe9326116fb1c890bf1920eea880e8da621afb6bc0f39a262/pyzmq-27.0.1-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:9729190bd770314f5fbba42476abf6abe79a746eeda11d1d68fd56dd70e5c296", size = 1332721, upload-time = "2025-08-03T05:03:15.237Z" }, { url = "https://files.pythonhosted.org/packages/42/73/034429ab0f4316bf433eb6c20c3f49d1dc13b2ed4e4d951b283d300a0f35/pyzmq-27.0.2-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:063845960df76599ad4fad69fa4d884b3ba38304272104fdcd7e3af33faeeb1d", size = 1333169, upload-time = "2025-08-21T04:21:12.483Z" },
{ url = "https://files.pythonhosted.org/packages/75/a4/9431ba598651d60ebd50dc25755402b770322cf8432adcc07d2906e53a54/pyzmq-27.0.1-cp311-cp311-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:696900ef6bc20bef6a242973943574f96c3f97d2183c1bd3da5eea4f559631b1", size = 908249, upload-time = "2025-08-03T05:03:16.933Z" }, { url = "https://files.pythonhosted.org/packages/35/02/c42b3b526eb03a570c889eea85a5602797f800a50ba8b09ddbf7db568b78/pyzmq-27.0.2-cp311-cp311-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:845a35fb21b88786aeb38af8b271d41ab0967985410f35411a27eebdc578a076", size = 909176, upload-time = "2025-08-21T04:21:13.835Z" },
{ url = "https://files.pythonhosted.org/packages/f0/7a/e624e1793689e4e685d2ee21c40277dd4024d9d730af20446d88f69be838/pyzmq-27.0.1-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f96a63aecec22d3f7fdea3c6c98df9e42973f5856bb6812c3d8d78c262fee808", size = 668649, upload-time = "2025-08-03T05:03:18.49Z" }, { url = "https://files.pythonhosted.org/packages/1b/35/a1c0b988fabbdf2dc5fe94b7c2bcfd61e3533e5109297b8e0daf1d7a8d2d/pyzmq-27.0.2-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:515d20b5c3c86db95503faa989853a8ab692aab1e5336db011cd6d35626c4cb1", size = 668972, upload-time = "2025-08-21T04:21:15.315Z" },
{ url = "https://files.pythonhosted.org/packages/6c/29/0652a39d4e876e0d61379047ecf7752685414ad2e253434348246f7a2a39/pyzmq-27.0.1-cp311-cp311-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:c512824360ea7490390566ce00bee880e19b526b312b25cc0bc30a0fe95cb67f", size = 856601, upload-time = "2025-08-03T05:03:20.194Z" }, { url = "https://files.pythonhosted.org/packages/a0/63/908ac865da32ceaeecea72adceadad28ca25b23a2ca5ff018e5bff30116f/pyzmq-27.0.2-cp311-cp311-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:862aedec0b0684a5050cdb5ec13c2da96d2f8dffda48657ed35e312a4e31553b", size = 856962, upload-time = "2025-08-21T04:21:16.652Z" },
{ url = "https://files.pythonhosted.org/packages/36/2d/8d5355d7fc55bb6e9c581dd74f58b64fa78c994079e3a0ea09b1b5627cde/pyzmq-27.0.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:dfb2bb5e0f7198eaacfb6796fb0330afd28f36d985a770745fba554a5903595a", size = 1657750, upload-time = "2025-08-03T05:03:22.055Z" }, { url = "https://files.pythonhosted.org/packages/2f/5a/90b3cc20b65cdf9391896fcfc15d8db21182eab810b7ea05a2986912fbe2/pyzmq-27.0.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:2cb5bcfc51c7a4fce335d3bc974fd1d6a916abbcdd2b25f6e89d37b8def25f57", size = 1657712, upload-time = "2025-08-21T04:21:18.666Z" },
{ url = "https://files.pythonhosted.org/packages/ab/f4/cd032352d5d252dc6f5ee272a34b59718ba3af1639a8a4ef4654f9535cf5/pyzmq-27.0.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:4f6886c59ba93ffde09b957d3e857e7950c8fe818bd5494d9b4287bc6d5bc7f1", size = 2034312, upload-time = "2025-08-03T05:03:23.578Z" }, { url = "https://files.pythonhosted.org/packages/c4/3c/32a5a80f9be4759325b8d7b22ce674bb87e586b4c80c6a9d77598b60d6f0/pyzmq-27.0.2-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:38ff75b2a36e3a032e9fef29a5871e3e1301a37464e09ba364e3c3193f62982a", size = 2035054, upload-time = "2025-08-21T04:21:20.073Z" },
{ url = "https://files.pythonhosted.org/packages/e4/1a/c050d8b6597200e97a4bd29b93c769d002fa0b03083858227e0376ad59bc/pyzmq-27.0.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b99ea9d330e86ce1ff7f2456b33f1bf81c43862a5590faf4ef4ed3a63504bdab", size = 1893632, upload-time = "2025-08-03T05:03:25.167Z" }, { url = "https://files.pythonhosted.org/packages/13/61/71084fe2ff2d7dc5713f8740d735336e87544845dae1207a8e2e16d9af90/pyzmq-27.0.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:7a5709abe8d23ca158a9d0a18c037f4193f5b6afeb53be37173a41e9fb885792", size = 1894010, upload-time = "2025-08-21T04:21:21.96Z" },
{ url = "https://files.pythonhosted.org/packages/6a/29/173ce21d5097e7fcf284a090e8beb64fc683c6582b1f00fa52b1b7e867ce/pyzmq-27.0.1-cp311-cp311-win32.whl", hash = "sha256:571f762aed89025ba8cdcbe355fea56889715ec06d0264fd8b6a3f3fa38154ed", size = 566587, upload-time = "2025-08-03T05:03:26.769Z" }, { url = "https://files.pythonhosted.org/packages/cb/6b/77169cfb13b696e50112ca496b2ed23c4b7d8860a1ec0ff3e4b9f9926221/pyzmq-27.0.2-cp311-cp311-win32.whl", hash = "sha256:47c5dda2018c35d87be9b83de0890cb92ac0791fd59498847fc4eca6ff56671d", size = 566819, upload-time = "2025-08-21T04:21:23.31Z" },
{ url = "https://files.pythonhosted.org/packages/53/ab/22bd33e7086f0a2cc03a5adabff4bde414288bb62a21a7820951ef86ec20/pyzmq-27.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:ee16906c8025fa464bea1e48128c048d02359fb40bebe5333103228528506530", size = 632873, upload-time = "2025-08-03T05:03:28.685Z" }, { url = "https://files.pythonhosted.org/packages/37/cd/86c4083e0f811f48f11bc0ddf1e7d13ef37adfd2fd4f78f2445f1cc5dec0/pyzmq-27.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:f54ca3e98f8f4d23e989c7d0edcf9da7a514ff261edaf64d1d8653dd5feb0a8b", size = 633264, upload-time = "2025-08-21T04:21:24.761Z" },
{ url = "https://files.pythonhosted.org/packages/90/14/3e59b4a28194285ceeff725eba9aa5ba8568d1cb78aed381dec1537c705a/pyzmq-27.0.1-cp311-cp311-win_arm64.whl", hash = "sha256:ba068f28028849da725ff9185c24f832ccf9207a40f9b28ac46ab7c04994bd41", size = 558918, upload-time = "2025-08-03T05:03:30.085Z" }, { url = "https://files.pythonhosted.org/packages/a0/69/5b8bb6a19a36a569fac02153a9e083738785892636270f5f68a915956aea/pyzmq-27.0.2-cp311-cp311-win_arm64.whl", hash = "sha256:2ef3067cb5b51b090fb853f423ad7ed63836ec154374282780a62eb866bf5768", size = 559316, upload-time = "2025-08-21T04:21:26.1Z" },
{ url = "https://files.pythonhosted.org/packages/0e/9b/c0957041067c7724b310f22c398be46399297c12ed834c3bc42200a2756f/pyzmq-27.0.1-cp312-abi3-macosx_10_15_universal2.whl", hash = "sha256:af7ebce2a1e7caf30c0bb64a845f63a69e76a2fadbc1cac47178f7bb6e657bdd", size = 1305432, upload-time = "2025-08-03T05:03:32.177Z" }, { url = "https://files.pythonhosted.org/packages/68/69/b3a729e7b03e412bee2b1823ab8d22e20a92593634f664afd04c6c9d9ac0/pyzmq-27.0.2-cp312-abi3-macosx_10_15_universal2.whl", hash = "sha256:5da05e3c22c95e23bfc4afeee6ff7d4be9ff2233ad6cb171a0e8257cd46b169a", size = 1305910, upload-time = "2025-08-21T04:21:27.609Z" },
{ url = "https://files.pythonhosted.org/packages/8e/55/bd3a312790858f16b7def3897a0c3eb1804e974711bf7b9dcb5f47e7f82c/pyzmq-27.0.1-cp312-abi3-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:8f617f60a8b609a13099b313e7e525e67f84ef4524b6acad396d9ff153f6e4cd", size = 895095, upload-time = "2025-08-03T05:03:33.918Z" }, { url = "https://files.pythonhosted.org/packages/15/b7/f6a6a285193d489b223c340b38ee03a673467cb54914da21c3d7849f1b10/pyzmq-27.0.2-cp312-abi3-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:4e4520577971d01d47e2559bb3175fce1be9103b18621bf0b241abe0a933d040", size = 895507, upload-time = "2025-08-21T04:21:29.005Z" },
{ url = "https://files.pythonhosted.org/packages/20/50/fc384631d8282809fb1029a4460d2fe90fa0370a0e866a8318ed75c8d3bb/pyzmq-27.0.1-cp312-abi3-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1d59dad4173dc2a111f03e59315c7bd6e73da1a9d20a84a25cf08325b0582b1a", size = 651826, upload-time = "2025-08-03T05:03:35.818Z" }, { url = "https://files.pythonhosted.org/packages/17/e6/c4ed2da5ef9182cde1b1f5d0051a986e76339d71720ec1a00be0b49275ad/pyzmq-27.0.2-cp312-abi3-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:56d7de7bf73165b90bd25a8668659ccb134dd28449116bf3c7e9bab5cf8a8ec9", size = 652670, upload-time = "2025-08-21T04:21:30.71Z" },
{ url = "https://files.pythonhosted.org/packages/7e/0a/2356305c423a975000867de56888b79e44ec2192c690ff93c3109fd78081/pyzmq-27.0.1-cp312-abi3-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:f5b6133c8d313bde8bd0d123c169d22525300ff164c2189f849de495e1344577", size = 839751, upload-time = "2025-08-03T05:03:37.265Z" }, { url = "https://files.pythonhosted.org/packages/0e/66/d781ab0636570d32c745c4e389b1c6b713115905cca69ab6233508622edd/pyzmq-27.0.2-cp312-abi3-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:340e7cddc32f147c6c00d116a3f284ab07ee63dbd26c52be13b590520434533c", size = 840581, upload-time = "2025-08-21T04:21:32.008Z" },
{ url = "https://files.pythonhosted.org/packages/d7/1b/81e95ad256ca7e7ccd47f5294c1c6da6e2b64fbace65b84fe8a41470342e/pyzmq-27.0.1-cp312-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:58cca552567423f04d06a075f4b473e78ab5bdb906febe56bf4797633f54aa4e", size = 1641359, upload-time = "2025-08-03T05:03:38.799Z" }, { url = "https://files.pythonhosted.org/packages/a6/df/f24790caf565d72544f5c8d8500960b9562c1dc848d6f22f3c7e122e73d4/pyzmq-27.0.2-cp312-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:ba95693f9df8bb4a9826464fb0fe89033936f35fd4a8ff1edff09a473570afa0", size = 1641931, upload-time = "2025-08-21T04:21:33.371Z" },
{ url = "https://files.pythonhosted.org/packages/50/63/9f50ec965285f4e92c265c8f18344e46b12803666d8b73b65d254d441435/pyzmq-27.0.1-cp312-abi3-musllinux_1_2_i686.whl", hash = "sha256:4b9d8e26fb600d0d69cc9933e20af08552e97cc868a183d38a5c0d661e40dfbb", size = 2020281, upload-time = "2025-08-03T05:03:40.338Z" }, { url = "https://files.pythonhosted.org/packages/65/65/77d27b19fc5e845367f9100db90b9fce924f611b14770db480615944c9c9/pyzmq-27.0.2-cp312-abi3-musllinux_1_2_i686.whl", hash = "sha256:ca42a6ce2d697537da34f77a1960d21476c6a4af3e539eddb2b114c3cf65a78c", size = 2021226, upload-time = "2025-08-21T04:21:35.301Z" },
{ url = "https://files.pythonhosted.org/packages/02/4a/19e3398d0dc66ad2b463e4afa1fc541d697d7bc090305f9dfb948d3dfa29/pyzmq-27.0.1-cp312-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:2329f0c87f0466dce45bba32b63f47018dda5ca40a0085cc5c8558fea7d9fc55", size = 1877112, upload-time = "2025-08-03T05:03:42.012Z" }, { url = "https://files.pythonhosted.org/packages/5b/65/1ed14421ba27a4207fa694772003a311d1142b7f543179e4d1099b7eb746/pyzmq-27.0.2-cp312-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:3e44e665d78a07214b2772ccbd4b9bcc6d848d7895f1b2d7653f047b6318a4f6", size = 1878047, upload-time = "2025-08-21T04:21:36.749Z" },
{ url = "https://files.pythonhosted.org/packages/bf/42/c562e9151aa90ed1d70aac381ea22a929d6b3a2ce4e1d6e2e135d34fd9c6/pyzmq-27.0.1-cp312-abi3-win32.whl", hash = "sha256:57bb92abdb48467b89c2d21da1ab01a07d0745e536d62afd2e30d5acbd0092eb", size = 558177, upload-time = "2025-08-03T05:03:43.979Z" }, { url = "https://files.pythonhosted.org/packages/dd/dc/e578549b89b40dc78a387ec471c2a360766690c0a045cd8d1877d401012d/pyzmq-27.0.2-cp312-abi3-win32.whl", hash = "sha256:272d772d116615397d2be2b1417b3b8c8bc8671f93728c2f2c25002a4530e8f6", size = 558757, upload-time = "2025-08-21T04:21:38.2Z" },
{ url = "https://files.pythonhosted.org/packages/40/96/5c50a7d2d2b05b19994bf7336b97db254299353dd9b49b565bb71b485f03/pyzmq-27.0.1-cp312-abi3-win_amd64.whl", hash = "sha256:ff3f8757570e45da7a5bedaa140489846510014f7a9d5ee9301c61f3f1b8a686", size = 618923, upload-time = "2025-08-03T05:03:45.438Z" }, { url = "https://files.pythonhosted.org/packages/b5/89/06600980aefcc535c758414da969f37a5194ea4cdb73b745223f6af3acfb/pyzmq-27.0.2-cp312-abi3-win_amd64.whl", hash = "sha256:734be4f44efba0aa69bf5f015ed13eb69ff29bf0d17ea1e21588b095a3147b8e", size = 619281, upload-time = "2025-08-21T04:21:39.909Z" },
{ url = "https://files.pythonhosted.org/packages/13/33/1ec89c8f21c89d21a2eaff7def3676e21d8248d2675705e72554fb5a6f3f/pyzmq-27.0.1-cp312-abi3-win_arm64.whl", hash = "sha256:df2c55c958d3766bdb3e9d858b911288acec09a9aab15883f384fc7180df5bed", size = 552358, upload-time = "2025-08-03T05:03:46.887Z" }, { url = "https://files.pythonhosted.org/packages/30/84/df8a5c089552d17c9941d1aea4314b606edf1b1622361dae89aacedc6467/pyzmq-27.0.2-cp312-abi3-win_arm64.whl", hash = "sha256:41f0bd56d9279392810950feb2785a419c2920bbf007fdaaa7f4a07332ae492d", size = 552680, upload-time = "2025-08-21T04:21:41.571Z" },
{ url = "https://files.pythonhosted.org/packages/b4/1a/49f66fe0bc2b2568dd4280f1f520ac8fafd73f8d762140e278d48aeaf7b9/pyzmq-27.0.1-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:7fb0ee35845bef1e8c4a152d766242164e138c239e3182f558ae15cb4a891f94", size = 835949, upload-time = "2025-08-03T05:05:13.798Z" }, { url = "https://files.pythonhosted.org/packages/c7/60/027d0032a1e3b1aabcef0e309b9ff8a4099bdd5a60ab38b36a676ff2bd7b/pyzmq-27.0.2-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:e297784aea724294fe95e442e39a4376c2f08aa4fae4161c669f047051e31b02", size = 836007, upload-time = "2025-08-21T04:23:00.447Z" },
{ url = "https://files.pythonhosted.org/packages/49/94/443c1984b397eab59b14dd7ae8bc2ac7e8f32dbc646474453afcaa6508c4/pyzmq-27.0.1-pp311-pypy311_pp73-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:f379f11e138dfd56c3f24a04164f871a08281194dd9ddf656a278d7d080c8ad0", size = 799875, upload-time = "2025-08-03T05:05:15.632Z" }, { url = "https://files.pythonhosted.org/packages/25/20/2ed1e6168aaea323df9bb2c451309291f53ba3af372ffc16edd4ce15b9e5/pyzmq-27.0.2-pp311-pypy311_pp73-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:e3659a79ded9745bc9c2aef5b444ac8805606e7bc50d2d2eb16dc3ab5483d91f", size = 799932, upload-time = "2025-08-21T04:23:02.052Z" },
{ url = "https://files.pythonhosted.org/packages/30/f1/fd96138a0f152786a2ba517e9c6a8b1b3516719e412a90bb5d8eea6b660c/pyzmq-27.0.1-pp311-pypy311_pp73-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:b978c0678cffbe8860ec9edc91200e895c29ae1ac8a7085f947f8e8864c489fb", size = 567403, upload-time = "2025-08-03T05:05:17.326Z" }, { url = "https://files.pythonhosted.org/packages/fd/25/5c147307de546b502c9373688ce5b25dc22288d23a1ebebe5d587bf77610/pyzmq-27.0.2-pp311-pypy311_pp73-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f3dba49ff037d02373a9306b58d6c1e0be031438f822044e8767afccfdac4c6b", size = 567459, upload-time = "2025-08-21T04:23:03.593Z" },
{ url = "https://files.pythonhosted.org/packages/16/57/34e53ef2b55b1428dac5aabe3a974a16c8bda3bf20549ba500e3ff6cb426/pyzmq-27.0.1-pp311-pypy311_pp73-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:7ebccf0d760bc92a4a7c751aeb2fef6626144aace76ee8f5a63abeb100cae87f", size = 747032, upload-time = "2025-08-03T05:05:19.074Z" }, { url = "https://files.pythonhosted.org/packages/71/06/0dc56ffc615c8095cd089c9b98ce5c733e990f09ce4e8eea4aaf1041a532/pyzmq-27.0.2-pp311-pypy311_pp73-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:de84e1694f9507b29e7b263453a2255a73e3d099d258db0f14539bad258abe41", size = 747088, upload-time = "2025-08-21T04:23:05.334Z" },
{ url = "https://files.pythonhosted.org/packages/81/b7/769598c5ae336fdb657946950465569cf18803140fe89ce466d7f0a57c11/pyzmq-27.0.1-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:77fed80e30fa65708546c4119840a46691290efc231f6bfb2ac2a39b52e15811", size = 544566, upload-time = "2025-08-03T05:05:20.798Z" }, { url = "https://files.pythonhosted.org/packages/06/f6/4a50187e023b8848edd3f0a8e197b1a7fb08d261d8c60aae7cb6c3d71612/pyzmq-27.0.2-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:f0944d65ba2b872b9fcece08411d6347f15a874c775b4c3baae7f278550da0fb", size = 544639, upload-time = "2025-08-21T04:23:07.279Z" },
] ]
[[package]] [[package]]
@ -4524,7 +4565,7 @@ wheels = [
[[package]] [[package]]
name = "requests" name = "requests"
version = "2.32.4" version = "2.32.5"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
dependencies = [ dependencies = [
{ name = "certifi" }, { name = "certifi" },
@ -4532,21 +4573,21 @@ dependencies = [
{ name = "idna" }, { name = "idna" },
{ name = "urllib3" }, { name = "urllib3" },
] ]
sdist = { url = "https://files.pythonhosted.org/packages/e1/0a/929373653770d8a0d7ea76c37de6e41f11eb07559b103b1c02cafb3f7cf8/requests-2.32.4.tar.gz", hash = "sha256:27d0316682c8a29834d3264820024b62a36942083d52caf2f14c0591336d3422", size = 135258, upload-time = "2025-06-09T16:43:07.34Z" } sdist = { url = "https://files.pythonhosted.org/packages/c9/74/b3ff8e6c8446842c3f5c837e9c3dfcfe2018ea6ecef224c710c85ef728f4/requests-2.32.5.tar.gz", hash = "sha256:dbba0bac56e100853db0ea71b82b4dfd5fe2bf6d3754a8893c3af500cec7d7cf", size = 134517, upload-time = "2025-08-18T20:46:02.573Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/7c/e4/56027c4a6b4ae70ca9de302488c5ca95ad4a39e190093d6c1a8ace08341b/requests-2.32.4-py3-none-any.whl", hash = "sha256:27babd3cda2a6d50b30443204ee89830707d396671944c998b5975b031ac2b2c", size = 64847, upload-time = "2025-06-09T16:43:05.728Z" }, { url = "https://files.pythonhosted.org/packages/1e/db/4254e3eabe8020b458f1a747140d32277ec7a271daf1d235b70dc0b4e6e3/requests-2.32.5-py3-none-any.whl", hash = "sha256:2462f94637a34fd532264295e186976db0f5d453d1cdd31473c85a6a161affb6", size = 64738, upload-time = "2025-08-18T20:46:00.542Z" },
] ]
[[package]] [[package]]
name = "ruamel-yaml" name = "ruamel-yaml"
version = "0.18.14" version = "0.18.15"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
dependencies = [ dependencies = [
{ name = "ruamel-yaml-clib", marker = "platform_python_implementation == 'CPython'" }, { name = "ruamel-yaml-clib", marker = "platform_python_implementation == 'CPython'" },
] ]
sdist = { url = "https://files.pythonhosted.org/packages/39/87/6da0df742a4684263261c253f00edd5829e6aca970fff69e75028cccc547/ruamel.yaml-0.18.14.tar.gz", hash = "sha256:7227b76aaec364df15936730efbf7d72b30c0b79b1d578bbb8e3dcb2d81f52b7", size = 145511, upload-time = "2025-06-09T08:51:09.828Z" } sdist = { url = "https://files.pythonhosted.org/packages/3e/db/f3950f5e5031b618aae9f423a39bf81a55c148aecd15a34527898e752cf4/ruamel.yaml-0.18.15.tar.gz", hash = "sha256:dbfca74b018c4c3fba0b9cc9ee33e53c371194a9000e694995e620490fd40700", size = 146865, upload-time = "2025-08-19T11:15:10.694Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/af/6d/6fe4805235e193aad4aaf979160dd1f3c487c57d48b810c816e6e842171b/ruamel.yaml-0.18.14-py3-none-any.whl", hash = "sha256:710ff198bb53da66718c7db27eec4fbcc9aa6ca7204e4c1df2f282b6fe5eb6b2", size = 118570, upload-time = "2025-06-09T08:51:06.348Z" }, { url = "https://files.pythonhosted.org/packages/d1/e5/f2a0621f1781b76a38194acae72f01e37b1941470407345b6e8653ad7640/ruamel.yaml-0.18.15-py3-none-any.whl", hash = "sha256:148f6488d698b7a5eded5ea793a025308b25eca97208181b6a026037f391f701", size = 119702, upload-time = "2025-08-19T11:15:07.696Z" },
] ]
[[package]] [[package]]
@ -4586,28 +4627,28 @@ wheels = [
[[package]] [[package]]
name = "ruff" name = "ruff"
version = "0.12.9" version = "0.12.11"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/4a/45/2e403fa7007816b5fbb324cb4f8ed3c7402a927a0a0cb2b6279879a8bfdc/ruff-0.12.9.tar.gz", hash = "sha256:fbd94b2e3c623f659962934e52c2bea6fc6da11f667a427a368adaf3af2c866a", size = 5254702, upload-time = "2025-08-14T16:08:55.2Z" } sdist = { url = "https://files.pythonhosted.org/packages/de/55/16ab6a7d88d93001e1ae4c34cbdcfb376652d761799459ff27c1dc20f6fa/ruff-0.12.11.tar.gz", hash = "sha256:c6b09ae8426a65bbee5425b9d0b82796dbb07cb1af045743c79bfb163001165d", size = 5347103, upload-time = "2025-08-28T13:59:08.87Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/ad/20/53bf098537adb7b6a97d98fcdebf6e916fcd11b2e21d15f8c171507909cc/ruff-0.12.9-py3-none-linux_armv6l.whl", hash = "sha256:fcebc6c79fcae3f220d05585229463621f5dbf24d79fdc4936d9302e177cfa3e", size = 11759705, upload-time = "2025-08-14T16:08:12.968Z" }, { url = "https://files.pythonhosted.org/packages/d6/a2/3b3573e474de39a7a475f3fbaf36a25600bfeb238e1a90392799163b64a0/ruff-0.12.11-py3-none-linux_armv6l.whl", hash = "sha256:93fce71e1cac3a8bf9200e63a38ac5c078f3b6baebffb74ba5274fb2ab276065", size = 11979885, upload-time = "2025-08-28T13:58:26.654Z" },
{ url = "https://files.pythonhosted.org/packages/20/4d/c764ee423002aac1ec66b9d541285dd29d2c0640a8086c87de59ebbe80d5/ruff-0.12.9-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:aed9d15f8c5755c0e74467731a007fcad41f19bcce41cd75f768bbd687f8535f", size = 12527042, upload-time = "2025-08-14T16:08:16.54Z" }, { url = "https://files.pythonhosted.org/packages/76/e4/235ad6d1785a2012d3ded2350fd9bc5c5af8c6f56820e696b0118dfe7d24/ruff-0.12.11-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:b8e33ac7b28c772440afa80cebb972ffd823621ded90404f29e5ab6d1e2d4b93", size = 12742364, upload-time = "2025-08-28T13:58:30.256Z" },
{ url = "https://files.pythonhosted.org/packages/8b/45/cfcdf6d3eb5fc78a5b419e7e616d6ccba0013dc5b180522920af2897e1be/ruff-0.12.9-py3-none-macosx_11_0_arm64.whl", hash = "sha256:5b15ea354c6ff0d7423814ba6d44be2807644d0c05e9ed60caca87e963e93f70", size = 11724457, upload-time = "2025-08-14T16:08:18.686Z" }, { url = "https://files.pythonhosted.org/packages/2c/0d/15b72c5fe6b1e402a543aa9d8960e0a7e19dfb079f5b0b424db48b7febab/ruff-0.12.11-py3-none-macosx_11_0_arm64.whl", hash = "sha256:d69fb9d4937aa19adb2e9f058bc4fbfe986c2040acb1a4a9747734834eaa0bfd", size = 11920111, upload-time = "2025-08-28T13:58:33.677Z" },
{ url = "https://files.pythonhosted.org/packages/72/e6/44615c754b55662200c48bebb02196dbb14111b6e266ab071b7e7297b4ec/ruff-0.12.9-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d596c2d0393c2502eaabfef723bd74ca35348a8dac4267d18a94910087807c53", size = 11949446, upload-time = "2025-08-14T16:08:21.059Z" }, { url = "https://files.pythonhosted.org/packages/3e/c0/f66339d7893798ad3e17fa5a1e587d6fd9806f7c1c062b63f8b09dda6702/ruff-0.12.11-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:411954eca8464595077a93e580e2918d0a01a19317af0a72132283e28ae21bee", size = 12160060, upload-time = "2025-08-28T13:58:35.74Z" },
{ url = "https://files.pythonhosted.org/packages/fd/d1/9b7d46625d617c7df520d40d5ac6cdcdf20cbccb88fad4b5ecd476a6bb8d/ruff-0.12.9-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:1b15599931a1a7a03c388b9c5df1bfa62be7ede6eb7ef753b272381f39c3d0ff", size = 11566350, upload-time = "2025-08-14T16:08:23.433Z" }, { url = "https://files.pythonhosted.org/packages/03/69/9870368326db26f20c946205fb2d0008988aea552dbaec35fbacbb46efaa/ruff-0.12.11-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:6a2c0a2e1a450f387bf2c6237c727dd22191ae8c00e448e0672d624b2bbd7fb0", size = 11799848, upload-time = "2025-08-28T13:58:38.051Z" },
{ url = "https://files.pythonhosted.org/packages/59/20/b73132f66f2856bc29d2d263c6ca457f8476b0bbbe064dac3ac3337a270f/ruff-0.12.9-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3d02faa2977fb6f3f32ddb7828e212b7dd499c59eb896ae6c03ea5c303575756", size = 13270430, upload-time = "2025-08-14T16:08:25.837Z" }, { url = "https://files.pythonhosted.org/packages/25/8c/dd2c7f990e9b3a8a55eee09d4e675027d31727ce33cdb29eab32d025bdc9/ruff-0.12.11-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8ca4c3a7f937725fd2413c0e884b5248a19369ab9bdd850b5781348ba283f644", size = 13536288, upload-time = "2025-08-28T13:58:40.046Z" },
{ url = "https://files.pythonhosted.org/packages/a2/21/eaf3806f0a3d4c6be0a69d435646fba775b65f3f2097d54898b0fd4bb12e/ruff-0.12.9-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:17d5b6b0b3a25259b69ebcba87908496e6830e03acfb929ef9fd4c58675fa2ea", size = 14264717, upload-time = "2025-08-14T16:08:27.907Z" }, { url = "https://files.pythonhosted.org/packages/7a/30/d5496fa09aba59b5e01ea76775a4c8897b13055884f56f1c35a4194c2297/ruff-0.12.11-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:4d1df0098124006f6a66ecf3581a7f7e754c4df7644b2e6704cd7ca80ff95211", size = 14490633, upload-time = "2025-08-28T13:58:42.285Z" },
{ url = "https://files.pythonhosted.org/packages/d2/82/1d0c53bd37dcb582b2c521d352fbf4876b1e28bc0d8894344198f6c9950d/ruff-0.12.9-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:72db7521860e246adbb43f6ef464dd2a532ef2ef1f5dd0d470455b8d9f1773e0", size = 13684331, upload-time = "2025-08-14T16:08:30.352Z" }, { url = "https://files.pythonhosted.org/packages/9b/2f/81f998180ad53445d403c386549d6946d0748e536d58fce5b5e173511183/ruff-0.12.11-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5a8dd5f230efc99a24ace3b77e3555d3fbc0343aeed3fc84c8d89e75ab2ff793", size = 13888430, upload-time = "2025-08-28T13:58:44.641Z" },
{ url = "https://files.pythonhosted.org/packages/3b/2f/1c5cf6d8f656306d42a686f1e207f71d7cebdcbe7b2aa18e4e8a0cb74da3/ruff-0.12.9-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a03242c1522b4e0885af63320ad754d53983c9599157ee33e77d748363c561ce", size = 12739151, upload-time = "2025-08-14T16:08:32.55Z" }, { url = "https://files.pythonhosted.org/packages/87/71/23a0d1d5892a377478c61dbbcffe82a3476b050f38b5162171942a029ef3/ruff-0.12.11-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4dc75533039d0ed04cd33fb8ca9ac9620b99672fe7ff1533b6402206901c34ee", size = 12913133, upload-time = "2025-08-28T13:58:47.039Z" },
{ url = "https://files.pythonhosted.org/packages/47/09/25033198bff89b24d734e6479e39b1968e4c992e82262d61cdccaf11afb9/ruff-0.12.9-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9fc83e4e9751e6c13b5046d7162f205d0a7bac5840183c5beebf824b08a27340", size = 12954992, upload-time = "2025-08-14T16:08:34.816Z" }, { url = "https://files.pythonhosted.org/packages/80/22/3c6cef96627f89b344c933781ed38329bfb87737aa438f15da95907cbfd5/ruff-0.12.11-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4fc58f9266d62c6eccc75261a665f26b4ef64840887fc6cbc552ce5b29f96cc8", size = 13169082, upload-time = "2025-08-28T13:58:49.157Z" },
{ url = "https://files.pythonhosted.org/packages/52/8e/d0dbf2f9dca66c2d7131feefc386523404014968cd6d22f057763935ab32/ruff-0.12.9-py3-none-manylinux_2_31_riscv64.whl", hash = "sha256:881465ed56ba4dd26a691954650de6ad389a2d1fdb130fe51ff18a25639fe4bb", size = 12899569, upload-time = "2025-08-14T16:08:36.852Z" }, { url = "https://files.pythonhosted.org/packages/05/b5/68b3ff96160d8b49e8dd10785ff3186be18fd650d356036a3770386e6c7f/ruff-0.12.11-py3-none-manylinux_2_31_riscv64.whl", hash = "sha256:5a0113bd6eafd545146440225fe60b4e9489f59eb5f5f107acd715ba5f0b3d2f", size = 13139490, upload-time = "2025-08-28T13:58:51.593Z" },
{ url = "https://files.pythonhosted.org/packages/a0/bd/b614d7c08515b1428ed4d3f1d4e3d687deffb2479703b90237682586fa66/ruff-0.12.9-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:43f07a3ccfc62cdb4d3a3348bf0588358a66da756aa113e071b8ca8c3b9826af", size = 11751983, upload-time = "2025-08-14T16:08:39.314Z" }, { url = "https://files.pythonhosted.org/packages/59/b9/050a3278ecd558f74f7ee016fbdf10591d50119df8d5f5da45a22c6afafc/ruff-0.12.11-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:0d737b4059d66295c3ea5720e6efc152623bb83fde5444209b69cd33a53e2000", size = 11958928, upload-time = "2025-08-28T13:58:53.943Z" },
{ url = "https://files.pythonhosted.org/packages/58/d6/383e9f818a2441b1a0ed898d7875f11273f10882f997388b2b51cb2ae8b5/ruff-0.12.9-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:07adb221c54b6bba24387911e5734357f042e5669fa5718920ee728aba3cbadc", size = 11538635, upload-time = "2025-08-14T16:08:41.297Z" }, { url = "https://files.pythonhosted.org/packages/f9/bc/93be37347db854806904a43b0493af8d6873472dfb4b4b8cbb27786eb651/ruff-0.12.11-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:916fc5defee32dbc1fc1650b576a8fed68f5e8256e2180d4d9855aea43d6aab2", size = 11764513, upload-time = "2025-08-28T13:58:55.976Z" },
{ url = "https://files.pythonhosted.org/packages/20/9c/56f869d314edaa9fc1f491706d1d8a47747b9d714130368fbd69ce9024e9/ruff-0.12.9-py3-none-musllinux_1_2_i686.whl", hash = "sha256:f5cd34fabfdea3933ab85d72359f118035882a01bff15bd1d2b15261d85d5f66", size = 12534346, upload-time = "2025-08-14T16:08:43.39Z" }, { url = "https://files.pythonhosted.org/packages/7a/a1/1471751e2015a81fd8e166cd311456c11df74c7e8769d4aabfbc7584c7ac/ruff-0.12.11-py3-none-musllinux_1_2_i686.whl", hash = "sha256:c984f07d7adb42d3ded5be894fb4007f30f82c87559438b4879fe7aa08c62b39", size = 12745154, upload-time = "2025-08-28T13:58:58.16Z" },
{ url = "https://files.pythonhosted.org/packages/bd/4b/d8b95c6795a6c93b439bc913ee7a94fda42bb30a79285d47b80074003ee7/ruff-0.12.9-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:f6be1d2ca0686c54564da8e7ee9e25f93bdd6868263805f8c0b8fc6a449db6d7", size = 13017021, upload-time = "2025-08-14T16:08:45.889Z" }, { url = "https://files.pythonhosted.org/packages/68/ab/2542b14890d0f4872dd81b7b2a6aed3ac1786fae1ce9b17e11e6df9e31e3/ruff-0.12.11-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:e07fbb89f2e9249f219d88331c833860489b49cdf4b032b8e4432e9b13e8a4b9", size = 13227653, upload-time = "2025-08-28T13:59:00.276Z" },
{ url = "https://files.pythonhosted.org/packages/c7/c1/5f9a839a697ce1acd7af44836f7c2181cdae5accd17a5cb85fcbd694075e/ruff-0.12.9-py3-none-win32.whl", hash = "sha256:cc7a37bd2509974379d0115cc5608a1a4a6c4bff1b452ea69db83c8855d53f93", size = 11734785, upload-time = "2025-08-14T16:08:48.062Z" }, { url = "https://files.pythonhosted.org/packages/22/16/2fbfc61047dbfd009c58a28369a693a1484ad15441723be1cd7fe69bb679/ruff-0.12.11-py3-none-win32.whl", hash = "sha256:c792e8f597c9c756e9bcd4d87cf407a00b60af77078c96f7b6366ea2ce9ba9d3", size = 11944270, upload-time = "2025-08-28T13:59:02.347Z" },
{ url = "https://files.pythonhosted.org/packages/fa/66/cdddc2d1d9a9f677520b7cfc490d234336f523d4b429c1298de359a3be08/ruff-0.12.9-py3-none-win_amd64.whl", hash = "sha256:6fb15b1977309741d7d098c8a3cb7a30bc112760a00fb6efb7abc85f00ba5908", size = 12840654, upload-time = "2025-08-14T16:08:50.158Z" }, { url = "https://files.pythonhosted.org/packages/08/a5/34276984705bfe069cd383101c45077ee029c3fe3b28225bf67aa35f0647/ruff-0.12.11-py3-none-win_amd64.whl", hash = "sha256:a3283325960307915b6deb3576b96919ee89432ebd9c48771ca12ee8afe4a0fd", size = 13046600, upload-time = "2025-08-28T13:59:04.751Z" },
{ url = "https://files.pythonhosted.org/packages/ac/fd/669816bc6b5b93b9586f3c1d87cd6bc05028470b3ecfebb5938252c47a35/ruff-0.12.9-py3-none-win_arm64.whl", hash = "sha256:63c8c819739d86b96d500cce885956a1a48ab056bbcbc61b747ad494b2485089", size = 11949623, upload-time = "2025-08-14T16:08:52.233Z" }, { url = "https://files.pythonhosted.org/packages/84/a8/001d4a7c2b37623a3fd7463208267fb906df40ff31db496157549cfd6e72/ruff-0.12.11-py3-none-win_arm64.whl", hash = "sha256:bae4d6e6a2676f8fb0f98b74594a048bae1b944aab17e9f5d504062303c6dbea", size = 12135290, upload-time = "2025-08-28T13:59:06.933Z" },
] ]
[[package]] [[package]]
@ -4621,15 +4662,15 @@ wheels = [
[[package]] [[package]]
name = "sentry-sdk" name = "sentry-sdk"
version = "2.35.0" version = "2.35.2"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
dependencies = [ dependencies = [
{ name = "certifi" }, { name = "certifi" },
{ name = "urllib3" }, { name = "urllib3" },
] ]
sdist = { url = "https://files.pythonhosted.org/packages/31/83/055dc157b719651ef13db569bb8cf2103df11174478649735c1b2bf3f6bc/sentry_sdk-2.35.0.tar.gz", hash = "sha256:5ea58d352779ce45d17bc2fa71ec7185205295b83a9dbb5707273deb64720092", size = 343014, upload-time = "2025-08-14T17:11:20.223Z" } sdist = { url = "https://files.pythonhosted.org/packages/bd/79/0ecb942f3f1ad26c40c27f81ff82392d85c01d26a45e3c72c2b37807e680/sentry_sdk-2.35.2.tar.gz", hash = "sha256:e9e8f3c795044beb59f2c8f4c6b9b0f9779e5e604099882df05eec525e782cc6", size = 343377, upload-time = "2025-09-01T11:00:58.633Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/36/3d/742617a7c644deb0c1628dcf6bb2d2165ab7c6aab56fe5222758994007f8/sentry_sdk-2.35.0-py2.py3-none-any.whl", hash = "sha256:6e0c29b9a5d34de8575ffb04d289a987ff3053cf2c98ede445bea995e3830263", size = 363806, upload-time = "2025-08-14T17:11:18.29Z" }, { url = "https://files.pythonhosted.org/packages/c0/91/a43308dc82a0e32d80cd0dfdcfca401ecbd0f431ab45f24e48bb97b7800d/sentry_sdk-2.35.2-py2.py3-none-any.whl", hash = "sha256:38c98e3cbb620dd3dd80a8d6e39c753d453dd41f8a9df581b0584c19a52bc926", size = 363975, upload-time = "2025-09-01T11:00:56.574Z" },
] ]
[[package]] [[package]]
@ -4824,11 +4865,11 @@ wheels = [
[[package]] [[package]]
name = "typing-extensions" name = "typing-extensions"
version = "4.14.1" version = "4.15.0"
source = { registry = "https://pypi.org/simple" } source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/98/5a/da40306b885cc8c09109dc2e1abd358d5684b1425678151cdaed4731c822/typing_extensions-4.14.1.tar.gz", hash = "sha256:38b39f4aeeab64884ce9f74c94263ef78f3c22467c8724005483154c26648d36", size = 107673, upload-time = "2025-07-04T13:28:34.16Z" } sdist = { url = "https://files.pythonhosted.org/packages/72/94/1a15dd82efb362ac84269196e94cf00f187f7ed21c242792a923cdb1c61f/typing_extensions-4.15.0.tar.gz", hash = "sha256:0cea48d173cc12fa28ecabc3b837ea3cf6f38c6d1136f85cbaaf598984861466", size = 109391, upload-time = "2025-08-25T13:49:26.313Z" }
wheels = [ wheels = [
{ url = "https://files.pythonhosted.org/packages/b5/00/d631e67a838026495268c2f6884f3711a15a9a2a96cd244fdaea53b823fb/typing_extensions-4.14.1-py3-none-any.whl", hash = "sha256:d1e1e3b58374dc93031d6eda2420a48ea44a36c2b4766a4fdeb3710755731d76", size = 43906, upload-time = "2025-07-04T13:28:32.743Z" }, { url = "https://files.pythonhosted.org/packages/18/67/36e9267722cc04a6b9f15c7f3441c2363321a3ea07da7ae0c0707beb2a9c/typing_extensions-4.15.0-py3-none-any.whl", hash = "sha256:f0fa19c6845758ab08074a0cfa8b7aecb71c999ca73d62883bc25cc018c4e548", size = 44614, upload-time = "2025-08-25T13:49:24.86Z" },
] ]
[[package]] [[package]]

Loading…
Cancel
Save