diff --git a/.github/workflows/release.yaml b/.github/workflows/release.yaml index 4065b0ef3e..0f4ce6cb3a 100644 --- a/.github/workflows/release.yaml +++ b/.github/workflows/release.yaml @@ -39,4 +39,4 @@ jobs: git config --global --add safe.directory '*' git lfs pull - name: Push master-ci - run: BRANCH=__nightly release/build_devel.sh + run: BRANCH=__nightly release/build_stripped.sh diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 1684a0af46..cdafbbfede 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -27,7 +27,7 @@ env: RUN: docker run --shm-size 2G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e CI=1 -e PYTHONWARNINGS=error -e FILEREADER_CACHE=1 -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v $GITHUB_WORKSPACE/.ci_cache/scons_cache:/tmp/scons_cache -v $GITHUB_WORKSPACE/.ci_cache/comma_download_cache:/tmp/comma_download_cache -v $GITHUB_WORKSPACE/.ci_cache/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/bash -c - PYTEST: pytest --continue-on-collection-errors --durations=0 --durations-min=5 -n logical + PYTEST: pytest --continue-on-collection-errors --durations=0 -n logical jobs: build_release: @@ -52,7 +52,7 @@ jobs: command: git lfs pull - name: Build devel 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 - 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 @@ -161,7 +161,9 @@ jobs: - name: Run unit tests timeout-minutes: ${{ contains(runner.name, 'nsc') && ((steps.setup-step.outputs.duration < 18) && 1 || 2) || 20 }} run: | - ${{ env.RUN }} "$PYTEST --collect-only -m 'not slow' &> /dev/null && \ + ${{ env.RUN }} "source selfdrive/test/setup_xvfb.sh && \ + # Pre-compile Python bytecode so each pytest worker doesn't need to + $PYTEST --collect-only -m 'not slow' -qq && \ MAX_EXAMPLES=1 $PYTEST -m 'not slow' && \ ./selfdrive/ui/tests/create_test_translations.sh && \ QT_QPA_PLATFORM=offscreen ./selfdrive/ui/tests/test_translations && \ diff --git a/.gitignore b/.gitignore index ac4021529b..8dc8f41de5 100644 --- a/.gitignore +++ b/.gitignore @@ -13,9 +13,11 @@ venv/ model2.png a.out .hypothesis +.cache/ /docs_site/ +*.mp4 *.dylib *.DSYM *.d diff --git a/Jenkinsfile b/Jenkinsfile index a14bf59299..0905abd6da 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -167,7 +167,7 @@ node { env.GIT_COMMIT = checkout(scm).GIT_COMMIT def excludeBranches = ['__nightly', 'devel', 'devel-staging', 'release3', 'release3-staging', - 'testing-closet*', 'hotfix-*'] + 'release-tici', 'testing-closet*', 'hotfix-*'] def excludeRegex = excludeBranches.join('|').replaceAll('\\*', '.*') if (env.BRANCH_NAME != 'master' && !env.BRANCH_NAME.contains('__jenkins_loop_')) { diff --git a/README.md b/README.md index dcf645ff61..f3af58f85b 100644 --- a/README.md +++ b/README.md @@ -56,7 +56,6 @@ We have detailed instructions for [how to install the harness and device in a ca | `release3-staging` | openpilot-test.comma.ai | This is the staging branch for releases. Use it to get new releases slightly early. | | `nightly` | openpilot-nightly.comma.ai | This is the bleeding edge development branch. Do not expect this to be stable. | | `nightly-dev` | installer.comma.ai/commaai/nightly-dev | Same as nightly, but includes experimental development features for some cars. | -| `secretgoodopenpilot` | installer.comma.ai/commaai/secretgoodopenpilot | This is a preview branch from the autonomy team where new driving models get merged earlier than master. | To start developing openpilot ------ diff --git a/RELEASES.md b/RELEASES.md index 58d0d07a74..dacf0eaa17 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,11 +1,22 @@ -Version 0.10.0 (2025-07-07) +Version 0.10.1 (2025-09-08) +======================== +* Record driving feedback using LKAS button +* Honda City 2023 support thanks to drFritz! + +Version 0.10.0 (2025-08-05) ======================== * New driving model - * Lead car ground-truth fixes - * Ported over VAE from the MLSIM stack - * New training architecture described in CVPR paper + * New training architecture + * Described in our CVPR paper: "Learning to Drive from a World Model" + * Longitudinal MPC replaced by E2E planning from World Model in Experimental Mode + * Action from lateral MPC as training objective replaced by E2E planning from World Model + * Low-speed lead car ground-truth fixes * Enable live-learned steering actuation delay * Opt-in audio recording for dashcam video +* Acura MDX 2025 support thanks to vanillagorillaa and MVL! +* Honda Accord 2023-25 support thanks to vanillagorillaa and MVL! +* Honda CR-V 2023-25 support thanks to vanillagorillaa and MVL! +* Honda Pilot 2023-25 support thanks to vanillagorillaa and MVL! Version 0.9.9 (2025-05-23) ======================== diff --git a/cereal/log.capnp b/cereal/log.capnp index b9f4170265..e756843562 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -127,8 +127,9 @@ struct OnroadEvent @0xc4fa6047f024e718 { espActive @90; personalityChanged @91; aeb @92; - userFlag @95; + userBookmark @95; excessiveActuation @96; + audioFeedback @97; soundsUnavailableDEPRECATED @47; } @@ -2468,7 +2469,7 @@ struct DebugAlert { alertText2 @1 :Text; } -struct UserFlag { +struct UserBookmark @0xfe346a9de48d9b50 { } struct SoundPressure @0xdc24138990726023 { @@ -2486,6 +2487,11 @@ struct AudioData { sampleRate @1 :UInt32; } +struct AudioFeedback { + audio @0 :AudioData; + blockNum @1 :UInt16; +} + struct Touch { sec @0 :Int64; usec @1 :Int64; @@ -2586,9 +2592,13 @@ struct Event { mapRenderState @105: MapRenderState; # UI services - userFlag @93 :UserFlag; uiDebug @102 :UIDebug; + # driving feedback + userBookmark @93 :UserBookmark; + bookmarkButton @148 :UserBookmark; + audioFeedback @149 :AudioFeedback; + # *********** debug *********** testJoystick @52 :Joystick; roadEncodeData @86 :EncodeData; diff --git a/cereal/messaging/tests/test_pub_sub_master.py b/cereal/messaging/tests/test_pub_sub_master.py index e47e713393..5e26b49701 100644 --- a/cereal/messaging/tests/test_pub_sub_master.py +++ b/cereal/messaging/tests/test_pub_sub_master.py @@ -86,7 +86,7 @@ class TestSubMaster: "cameraOdometry": (20, 10), "liveCalibration": (4, 4), "carParams": (None, None), - "userFlag": (None, None), + "userBookmark": (None, None), } for service, (max_freq, min_freq) in checks.items(): diff --git a/cereal/services.py b/cereal/services.py index a13fc810f4..a4c7463f20 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -72,9 +72,11 @@ _services: dict[str, tuple] = { "navRoute": (True, 0.), "navThumbnail": (True, 0.), "qRoadEncodeIdx": (False, 20.), - "userFlag": (True, 0., 1), + "userBookmark": (True, 0., 1), "soundPressure": (True, 10., 10), "rawAudioData": (False, 20.), + "bookmarkButton": (True, 0., 1), + "audioFeedback": (True, 0., 1), # debug "uiDebug": (True, 0., 1), diff --git a/common/params_keys.h b/common/params_keys.h index 5cd6f9691b..c54600462c 100644 --- a/common/params_keys.h +++ b/common/params_keys.h @@ -73,9 +73,9 @@ inline static std::unordered_map keys = { {"LastOffroadStatusPacket", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, JSON}}, {"LastPowerDropDetected", {CLEAR_ON_MANAGER_START, STRING}}, {"LastUpdateException", {CLEAR_ON_MANAGER_START, STRING}}, - {"LastUpdateRouteCount", {PERSISTENT, INT}}, + {"LastUpdateRouteCount", {PERSISTENT, INT, "0"}}, {"LastUpdateTime", {PERSISTENT, TIME}}, - {"LastUpdateUptimeOnroad", {PERSISTENT, FLOAT}}, + {"LastUpdateUptimeOnroad", {PERSISTENT, FLOAT, "0.0"}}, {"LiveDelay", {PERSISTENT, BYTES}}, {"LiveParameters", {PERSISTENT, JSON}}, {"LiveParametersV2", {PERSISTENT, BYTES}}, @@ -105,6 +105,7 @@ inline static std::unordered_map keys = { {"PandaSignatures", {CLEAR_ON_MANAGER_START, BYTES}}, {"PrimeType", {PERSISTENT, INT}}, {"RecordAudio", {PERSISTENT, BOOL}}, + {"RecordAudioFeedback", {PERSISTENT, BOOL, "0"}}, {"RecordFront", {PERSISTENT, BOOL}}, {"RecordFrontLock", {PERSISTENT, BOOL}}, // for the internal fleet {"SecOCKey", {PERSISTENT | DONT_LOG, STRING}}, diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx index 1c76e75846..93c550f22a 100644 --- a/common/params_pyx.pyx +++ b/common/params_pyx.pyx @@ -102,14 +102,14 @@ cdef class Params: return cast(value) raise TypeError(f"Type mismatch while writing param {key}: {proposed_type=} {expected_type=} {value=}") - def cpp2python(self, t, value, default, key): + def _cpp2python(self, t, value, default, key): if value is None: return None try: return CPP_2_PYTHON[t](value) except (KeyError, TypeError, ValueError): cloudlog.warning(f"Failed to cast param {key} with {value=} from type {t=}") - return self.cpp2python(t, default, None, key) + return self._cpp2python(t, default, None, key) def get(self, key, bool block=False, bool return_default=False): cdef string k = self.check_key(key) @@ -126,8 +126,8 @@ cdef class Params: # it means we got an interrupt while waiting raise KeyboardInterrupt else: - return self.cpp2python(t, default_val, None, key) - return self.cpp2python(t, val, default_val, key) + return self._cpp2python(t, default_val, None, key) + return self._cpp2python(t, val, default_val, key) def get_bool(self, key, bool block=False): cdef string k = self.check_key(key) @@ -188,4 +188,9 @@ cdef class Params: cdef string k = self.check_key(key) cdef ParamKeyType t = self.p.getKeyType(k) cdef optional[string] default = self.p.getKeyDefaultValue(k) - return self.cpp2python(t, default.value(), None, key) if default.has_value() else None + return self._cpp2python(t, default.value(), None, key) if default.has_value() else None + + def cpp2python(self, key, value): + cdef string k = self.check_key(key) + cdef ParamKeyType t = self.p.getKeyType(k) + return self._cpp2python(t, value, None, key) diff --git a/common/pid.py b/common/pid.py index f2ab935f45..99142280ca 100644 --- a/common/pid.py +++ b/common/pid.py @@ -14,10 +14,8 @@ class PIDController: if isinstance(self._k_d, Number): self._k_d = [[0], [self._k_d]] - self.pos_limit = pos_limit - self.neg_limit = neg_limit + self.set_limits(pos_limit, neg_limit) - self.i_unwind_rate = 0.3 / rate self.i_rate = 1.0 / rate self.speed = 0.0 @@ -35,10 +33,6 @@ class PIDController: def k_d(self): return np.interp(self.speed, self._k_d[0], self._k_d[1]) - @property - def error_integral(self): - return self.i/self.k_i - def reset(self): self.p = 0.0 self.i = 0.0 @@ -46,25 +40,25 @@ class PIDController: self.f = 0.0 self.control = 0 - def update(self, error, error_rate=0.0, speed=0.0, override=False, feedforward=0., freeze_integrator=False): - self.speed = speed + def set_limits(self, pos_limit, neg_limit): + self.pos_limit = pos_limit + self.neg_limit = neg_limit + def update(self, error, error_rate=0.0, speed=0.0, feedforward=0., freeze_integrator=False): + self.speed = speed self.p = float(error) * self.k_p self.f = feedforward * self.k_f self.d = error_rate * self.k_d - if override: - self.i -= self.i_unwind_rate * float(np.sign(self.i)) - else: - if not freeze_integrator: - self.i = self.i + error * self.k_i * self.i_rate + if not freeze_integrator: + i = self.i + error * self.k_i * self.i_rate - # Clip i to prevent exceeding control limits - control_no_i = self.p + self.d + self.f - control_no_i = np.clip(control_no_i, self.neg_limit, self.pos_limit) - self.i = np.clip(self.i, self.neg_limit - control_no_i, self.pos_limit - control_no_i) + # Don't allow windup if already clipping + test_control = self.p + i + self.d + self.f + i_upperbound = self.i if test_control > self.pos_limit else self.pos_limit + i_lowerbound = self.i if test_control < self.neg_limit else self.neg_limit + self.i = np.clip(i, i_lowerbound, i_upperbound) control = self.p + self.i + self.d + self.f - self.control = np.clip(control, self.neg_limit, self.pos_limit) return self.control diff --git a/common/run.py b/common/run.py index 06deb6388d..75395ead1f 100644 --- a/common/run.py +++ b/common/run.py @@ -1,4 +1,6 @@ import subprocess +from contextlib import contextmanager +from subprocess import Popen, PIPE, TimeoutExpired def run_cmd(cmd: list[str], cwd=None, env=None) -> str: @@ -11,3 +13,16 @@ def run_cmd_default(cmd: list[str], default: str = "", cwd=None, env=None) -> st except subprocess.CalledProcessError: return default + +@contextmanager +def managed_proc(cmd: list[str], env: dict[str, str]): + proc = Popen(cmd, env=env, stdout=PIPE, stderr=PIPE) + try: + yield proc + finally: + if proc.poll() is None: + proc.terminate() + try: + proc.wait(timeout=5) + except TimeoutExpired: + proc.kill() diff --git a/common/version.h b/common/version.h index af827e20a6..669f303211 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.10.0" +#define COMMA_VERSION "0.10.1" diff --git a/docs/CARS.md b/docs/CARS.md index d6107b726b..7269f25737 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,12 +4,13 @@ A supported vehicle is one that just works when you install a comma device. All supported cars provide a better experience than any stock system. Supported vehicles reference the US market unless otherwise specified. -# 313 Supported Cars +# 321 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Hardware Needed
 |Video|Setup Video| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:|:---:| |Acura|ILX 2016-18|Technology Plus Package or AcuraWatch Plus|openpilot|26 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Acura|ILX 2019|All|openpilot|26 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Acura|MDX 2025|All except Type S|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Acura|RDX 2016-18|AcuraWatch Plus or Advance Package|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Acura|RDX 2019-21|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,16](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable (9.5 ft)
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| @@ -72,18 +73,24 @@ A supported vehicle is one that just works when you install a comma device. All |Genesis|GV80 2023[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |GMC|Sierra 1500 2020-21|Driver Alert Package II|openpilot available[1](#footnotes)|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Accord 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Accord 2023-25|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Accord Hybrid 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Accord Hybrid 2023-25|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|City (Brazil only) 2023|All|openpilot available[1](#footnotes)|0 mph|14 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Civic 2019-21|All|openpilot available[1](#footnotes)|0 mph|2 mph[5](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Civic 2022-24|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| -|Honda|Civic Hatchback 2017-21|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Civic Hatchback 2017-18|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Civic Hatchback 2019-21|All|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Civic Hatchback 2022-24|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Civic Hatchback Hybrid 2025|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Civic Hatchback Hybrid (Europe only) 2023|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Civic Hybrid 2025|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|CR-V 2015-16|Touring Trim|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|CR-V 2017-22|Honda Sensing|openpilot available[1](#footnotes)|0 mph|15 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|CR-V 2023-25|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|CR-V Hybrid 2017-22|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|CR-V Hybrid 2023-25|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|e 2020|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Fit 2018-20|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Freed 2020|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| @@ -94,6 +101,7 @@ A supported vehicle is one that just works when you install a comma device. All |Honda|Odyssey 2018-20|Honda Sensing|openpilot|26 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Passport 2019-25|All|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Pilot 2016-22|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| +|Honda|Pilot 2023-25|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch C connector
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Honda|Ridgeline 2017-25|Honda Sensing|openpilot|26 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Hyundai|Azera 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| |Hyundai|Azera Hybrid 2019|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 comma 3X
- 1 comma power v3
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
||| diff --git a/docs/CONTRIBUTING.md b/docs/CONTRIBUTING.md index 1950db8a05..154734b7fc 100644 --- a/docs/CONTRIBUTING.md +++ b/docs/CONTRIBUTING.md @@ -6,7 +6,7 @@ Development is coordinated through [Discord](https://discord.comma.ai) and GitHu ### Getting Started -* Setup your [development environment](../tools/) +* Set up your [development environment](/tools/) * Join our [Discord](https://discord.comma.ai) * Docs are at https://docs.comma.ai and https://blog.comma.ai diff --git a/docs/how-to/turn-the-speed-blue.md b/docs/how-to/turn-the-speed-blue.md index 64f4475dfa..13b3b03e80 100644 --- a/docs/how-to/turn-the-speed-blue.md +++ b/docs/how-to/turn-the-speed-blue.md @@ -1,11 +1,11 @@ # Turn the speed blue *A getting started guide for openpilot development* -In 30 minutes, we'll get an openpilot development environment setup 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. -## 1. Setup your development environment +## 1. Set up your development environment Run this to clone openpilot and install all the dependencies: ```bash diff --git a/launch_env.sh b/launch_env.sh index b0bff4e57f..4c011c6ac0 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="12.4" + export AGNOS_VERSION="12.8" fi export STAGING_ROOT="/data/safe_staging" diff --git a/opendbc_repo b/opendbc_repo index 22b8df68fb..43006b9a41 160000 --- a/opendbc_repo +++ b/opendbc_repo @@ -1 +1 @@ -Subproject commit 22b8df68fb6d8aa197fb9b432a428da6dd96c98c +Subproject commit 43006b9a41e233325cb7cbcb6ff40de0234217a0 diff --git a/panda b/panda index c2723b2f6b..3dc2138623 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit c2723b2f6bcce7e2d97f685db1ec2472a8dd28f5 +Subproject commit 3dc21386239e3073a623156b75901aa302340d6c diff --git a/pyproject.toml b/pyproject.toml index e50b73e0dd..7103163458 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -120,7 +120,6 @@ dev = [ tools = [ "metadrive-simulator @ https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal-0.4.2.4/metadrive_simulator-0.4.2.4-py3-none-any.whl ; (platform_machine != 'aarch64')", - #"rerun-sdk >= 0.18", # this is pretty big, so only enable once we use it ] [project.urls] diff --git a/release/README.md b/release/README.md index 06404be6ab..fb651fa05a 100644 --- a/release/README.md +++ b/release/README.md @@ -3,29 +3,34 @@ ``` ## release checklist -**Go to `devel-staging`** +### Go to staging +- [ ] make a GitHub issue to track release +- [ ] create release master branch - [ ] update RELEASES.md -- [ ] update `devel-staging`: `git reset --hard origin/master-ci` -- [ ] open a pull request from `devel-staging` to `devel` -- [ ] post on Discord - -**Go to `devel`** - [ ] bump version on master: `common/version.h` and `RELEASES.md` -- [ ] before merging the pull request +- [ ] build new userdata partition from `release3-staging` +- [ ] post on Discord, tag `@release crew` + +Updating staging: +1. either rebase on master or cherry-pick changes +2. run this to update: `BRANCH=devel-staging release/build_devel.sh` +3. build new userdata partition from `release3-staging` + +### Go to release +- [ ] before going to release, test the following: - [ ] update from previous release -> new release - [ ] update from new release -> previous release - [ ] fresh install with `openpilot-test.comma.ai` - [ ] drive on fresh install - [ ] no submodules or LFS - [ ] check sentry, MTBF, etc. - -**Go to `release3`** + - [ ] stress test passes in production - [ ] publish the blog post - [ ] `git reset --hard origin/release3-staging` - [ ] tag the release: `git tag v0.X.X && git push origin v0.X.X` - [ ] create GitHub release - [ ] final test install on `openpilot.comma.ai` - [ ] update factory provisioning -- [ ] close out milestone +- [ ] close out milestone and issue - [ ] post on Discord, X, etc. ``` diff --git a/release/build_devel.sh b/release/build_stripped.sh similarity index 83% rename from release/build_devel.sh rename to release/build_stripped.sh index 05dcaafcaa..6f1a568c25 100755 --- a/release/build_devel.sh +++ b/release/build_stripped.sh @@ -17,28 +17,23 @@ rm -rf $TARGET_DIR mkdir -p $TARGET_DIR cd $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 -git fetch --depth 1 origin __nightly -git fetch --depth 1 origin devel - -git checkout -f --track origin/__nightly -git reset --hard __nightly -git checkout __nightly -git reset --hard origin/devel -git clean -xdff -git lfs uninstall +# tmp branch +git checkout --orphan tmp # remove everything except .git 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 '{}' \; -# reset source tree +# cleanup before the copy cd $SOURCE_DIR git clean -xdff +git submodule foreach --recursive git clean -xdff # do the files copy echo "[-] copying files T=$SECONDS" @@ -47,6 +42,7 @@ cp -pR --parents $(./release/release_files.py) $TARGET_DIR/ # in the directory cd $TARGET_DIR +rm -rf .git/modules/ rm -f panda/board/obj/panda.bin.signed # include source commit hash and build date in commit @@ -85,7 +81,7 @@ fi if [ ! -z "$BRANCH" ]; then echo "[-] Pushing to $BRANCH T=$SECONDS" - git push -f origin __nightly:$BRANCH + git push -f origin tmp:$BRANCH fi echo "[-] done T=$SECONDS, ready at $TARGET_DIR" diff --git a/selfdrive/assets/icons/link.png b/selfdrive/assets/icons/link.png new file mode 100644 index 0000000000..8a795c05b8 --- /dev/null +++ b/selfdrive/assets/icons/link.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a69514fe68dd1b4c73f28771640dcba10fc40989d1c7e771cb48bfd830fef206 +size 5713 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index dd7968b732..029d16e59e 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -40,7 +40,7 @@ class Controls: 'driverMonitoringState', 'onroadEvents', 'driverAssistance'], poll='selfdriveState') self.pm = messaging.PubMaster(['carControl', 'controlsState']) - self.steer_limited_by_controls = False + self.steer_limited_by_safety = False self.curvature = 0.0 self.desired_curvature = 0.0 @@ -120,7 +120,7 @@ class Controls: actuators.curvature = self.desired_curvature steer, steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, - self.steer_limited_by_controls, self.desired_curvature, + self.steer_limited_by_safety, self.desired_curvature, curvature_limited) # TODO what if not available actuators.torque = float(steer) actuators.steeringAngleDeg = float(steeringAngleDeg) @@ -167,10 +167,10 @@ class Controls: if self.sm['selfdriveState'].active: CO = self.sm['carOutput'] if self.CP.steerControlType == car.CarParams.SteerControlType.angle: - self.steer_limited_by_controls = abs(CC.actuators.steeringAngleDeg - CO.actuatorsOutput.steeringAngleDeg) > \ + self.steer_limited_by_safety = abs(CC.actuators.steeringAngleDeg - CO.actuatorsOutput.steeringAngleDeg) > \ STEER_ANGLE_SATURATION_THRESHOLD else: - self.steer_limited_by_controls = abs(CC.actuators.torque - CO.actuatorsOutput.torque) > 1e-2 + self.steer_limited_by_safety = abs(CC.actuators.torque - CO.actuatorsOutput.torque) > 1e-2 # TODO: both controlsState and carControl valids should be set by # sm.all_checks(), but this creates a circular dependency diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py index d67a4aa959..2a8b873e2e 100644 --- a/selfdrive/controls/lib/latcontrol.py +++ b/selfdrive/controls/lib/latcontrol.py @@ -15,15 +15,15 @@ class LatControl(ABC): self.steer_max = 1.0 @abstractmethod - def update(self, active, CS, VM, params, steer_limited_by_controls, desired_curvature, calibrated_pose, curvature_limited): + def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, calibrated_pose, curvature_limited): pass def reset(self): self.sat_count = 0. - def _check_saturation(self, saturated, CS, steer_limited_by_controls, curvature_limited): + def _check_saturation(self, saturated, CS, steer_limited_by_safety, curvature_limited): # Saturated only if control output is not being limited by car torque/angle rate limits - if (saturated or curvature_limited) and CS.vEgo > self.sat_check_min_speed and not steer_limited_by_controls and not CS.steeringPressed: + if (saturated or curvature_limited) and CS.vEgo > self.sat_check_min_speed and not steer_limited_by_safety and not CS.steeringPressed: self.sat_count += self.sat_count_rate else: self.sat_count -= self.sat_count_rate diff --git a/selfdrive/controls/lib/latcontrol_angle.py b/selfdrive/controls/lib/latcontrol_angle.py index 807161735c..ac35151487 100644 --- a/selfdrive/controls/lib/latcontrol_angle.py +++ b/selfdrive/controls/lib/latcontrol_angle.py @@ -3,6 +3,7 @@ import math from cereal import log from openpilot.selfdrive.controls.lib.latcontrol import LatControl +# TODO This is speed dependent STEER_ANGLE_SATURATION_THRESHOLD = 2.5 # Degrees @@ -10,9 +11,9 @@ class LatControlAngle(LatControl): def __init__(self, CP, CI): super().__init__(CP, CI) self.sat_check_min_speed = 5. - self.use_steer_limited_by_controls = CP.brand == "tesla" + self.use_steer_limited_by_safety = CP.brand == "tesla" - def update(self, active, CS, VM, params, steer_limited_by_controls, desired_curvature, curvature_limited): + def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, curvature_limited): angle_log = log.ControlsState.LateralAngleState.new_message() if not active: @@ -23,9 +24,9 @@ class LatControlAngle(LatControl): angle_steers_des = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo, params.roll)) angle_steers_des += params.angleOffsetDeg - if self.use_steer_limited_by_controls: + if self.use_steer_limited_by_safety: # these cars' carcontrollers calculate max lateral accel and jerk, so we can rely on carOutput for saturation - angle_control_saturated = steer_limited_by_controls + angle_control_saturated = steer_limited_by_safety else: # for cars which use a method of limiting torque such as a torque signal (Nissan and Toyota) # or relying on EPS (Ford Q3), carOutput does not capture maxing out torque # TODO: this can be improved diff --git a/selfdrive/controls/lib/latcontrol_pid.py b/selfdrive/controls/lib/latcontrol_pid.py index 4e4e0772fe..00a083509f 100644 --- a/selfdrive/controls/lib/latcontrol_pid.py +++ b/selfdrive/controls/lib/latcontrol_pid.py @@ -13,11 +13,7 @@ class LatControlPID(LatControl): k_f=CP.lateralTuning.pid.kf, pos_limit=self.steer_max, neg_limit=-self.steer_max) self.get_steer_feedforward = CI.get_steer_feedforward_function() - def reset(self): - super().reset() - self.pid.reset() - - def update(self, active, CS, VM, params, steer_limited_by_controls, desired_curvature, curvature_limited): + def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, curvature_limited): pid_log = log.ControlsState.LateralPIDState.new_message() pid_log.steeringAngleDeg = float(CS.steeringAngleDeg) pid_log.steeringRateDeg = float(CS.steeringRateDeg) @@ -29,20 +25,24 @@ class LatControlPID(LatControl): pid_log.steeringAngleDesiredDeg = angle_steers_des pid_log.angleError = error if not active: - output_steer = 0.0 + output_torque = 0.0 pid_log.active = False - self.pid.reset() + else: # offset does not contribute to resistive torque - steer_feedforward = self.get_steer_feedforward(angle_steers_des_no_offset, CS.vEgo) + ff = self.get_steer_feedforward(angle_steers_des_no_offset, CS.vEgo) + freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5 + + output_torque = self.pid.update(error, + feedforward=ff, + speed=CS.vEgo, + freeze_integrator=freeze_integrator) - output_steer = self.pid.update(error, override=CS.steeringPressed, - feedforward=steer_feedforward, speed=CS.vEgo) pid_log.active = True pid_log.p = float(self.pid.p) pid_log.i = float(self.pid.i) pid_log.f = float(self.pid.f) - pid_log.output = float(output_steer) - pid_log.saturated = bool(self._check_saturation(self.steer_max - abs(output_steer) < 1e-3, CS, steer_limited_by_controls, curvature_limited)) + pid_log.output = float(output_torque) + pid_log.saturated = bool(self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited_by_safety, curvature_limited)) - return output_steer, angle_steers_des, pid_log + return output_torque, angle_steers_des, pid_log diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 991ac3439b..dffe85c473 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -3,7 +3,6 @@ import numpy as np from cereal import log from opendbc.car.lateral import FRICTION_THRESHOLD, get_friction -from opendbc.car.interfaces import LatControlInputs from openpilot.common.constants import ACCELERATION_DUE_TO_GRAVITY from openpilot.selfdrive.controls.lib.latcontrol import LatControl from openpilot.common.pid import PIDController @@ -27,17 +26,24 @@ class LatControlTorque(LatControl): def __init__(self, CP, CI): super().__init__(CP, CI) self.torque_params = CP.lateralTuning.torque.as_builder() - self.pid = PIDController(self.torque_params.kp, self.torque_params.ki, - k_f=self.torque_params.kf, pos_limit=self.steer_max, neg_limit=-self.steer_max) self.torque_from_lateral_accel = CI.torque_from_lateral_accel() + self.lateral_accel_from_torque = CI.lateral_accel_from_torque() + self.pid = PIDController(self.torque_params.kp, self.torque_params.ki, + k_f=self.torque_params.kf) + self.update_limits() self.steering_angle_deadzone_deg = self.torque_params.steeringAngleDeadzoneDeg def update_live_torque_params(self, latAccelFactor, latAccelOffset, friction): self.torque_params.latAccelFactor = latAccelFactor self.torque_params.latAccelOffset = latAccelOffset self.torque_params.friction = friction + self.update_limits() - def update(self, active, CS, VM, params, steer_limited_by_controls, desired_curvature, curvature_limited): + def update_limits(self): + self.pid.set_limits(self.lateral_accel_from_torque(self.steer_max, self.torque_params), + self.lateral_accel_from_torque(-self.steer_max, self.torque_params)) + + def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, curvature_limited): pid_log = log.ControlsState.LateralTorqueState.new_message() if not active: output_torque = 0.0 @@ -57,30 +63,28 @@ class LatControlTorque(LatControl): setpoint = desired_lateral_accel + low_speed_factor * desired_curvature measurement = actual_lateral_accel + low_speed_factor * actual_curvature gravity_adjusted_lateral_accel = desired_lateral_accel - roll_compensation - torque_from_setpoint = self.torque_from_lateral_accel(LatControlInputs(setpoint, roll_compensation, CS.vEgo, CS.aEgo), self.torque_params, - gravity_adjusted=False) - torque_from_measurement = self.torque_from_lateral_accel(LatControlInputs(measurement, roll_compensation, CS.vEgo, CS.aEgo), self.torque_params, - gravity_adjusted=False) - pid_log.error = float(torque_from_setpoint - torque_from_measurement) - ff = self.torque_from_lateral_accel(LatControlInputs(gravity_adjusted_lateral_accel, roll_compensation, CS.vEgo, CS.aEgo), self.torque_params, - gravity_adjusted=True) + + # do error correction in lateral acceleration space, convert at end to handle non-linear torque responses correctly + pid_log.error = float(setpoint - measurement) + ff = gravity_adjusted_lateral_accel ff += get_friction(desired_lateral_accel - actual_lateral_accel, lateral_accel_deadzone, FRICTION_THRESHOLD, self.torque_params) - freeze_integrator = steer_limited_by_controls or CS.steeringPressed or CS.vEgo < 5 - output_torque = self.pid.update(pid_log.error, + freeze_integrator = steer_limited_by_safety or CS.steeringPressed or CS.vEgo < 5 + output_lataccel = self.pid.update(pid_log.error, feedforward=ff, speed=CS.vEgo, freeze_integrator=freeze_integrator) + output_torque = self.torque_from_lateral_accel(output_lataccel, self.torque_params) pid_log.active = True pid_log.p = float(self.pid.p) pid_log.i = float(self.pid.i) pid_log.d = float(self.pid.d) pid_log.f = float(self.pid.f) - pid_log.output = float(-output_torque) + pid_log.output = float(-output_torque) # TODO: log lat accel? pid_log.actualLateralAccel = float(actual_lateral_accel) pid_log.desiredLateralAccel = float(desired_lateral_accel) - pid_log.saturated = bool(self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited_by_controls, curvature_limited)) + pid_log.saturated = bool(self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited_by_safety, curvature_limited)) # TODO left is positive in this convention return -output_torque, 0.0, pid_log diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 2149e60078..34fc85f8a5 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -19,7 +19,7 @@ LON_MPC_STEP = 0.2 # first step is 0.2s A_CRUISE_MAX_VALS = [1.6, 1.2, 0.8, 0.6] A_CRUISE_MAX_BP = [0., 10.0, 25., 40.] CONTROL_N_T_IDX = ModelConstants.T_IDXS[:CONTROL_N] -ALLOW_THROTTLE_THRESHOLD = 0.5 +ALLOW_THROTTLE_THRESHOLD = 0.4 MIN_ALLOW_THROTTLE_SPEED = 2.5 # Lookup table for turns @@ -90,7 +90,7 @@ class LongitudinalPlanner: return x, v, a, j, throttle_prob def update(self, sm): - self.mode = 'blended' if sm['selfdriveState'].experimentalMode else 'acc' + mode = 'blended' if sm['selfdriveState'].experimentalMode else 'acc' if len(sm['carControl'].orientationNED) == 3: accel_coast = get_coast_accel(sm['carControl'].orientationNED[1]) @@ -113,7 +113,7 @@ class LongitudinalPlanner: # No change cost when user is controlling the speed, or when standstill prev_accel_constraint = not (reset_state or sm['carState'].standstill) - if self.mode == 'acc': + if mode == 'acc': accel_clip = [ACCEL_MIN, get_max_accel(v_ego)] steer_angle_without_offset = sm['carState'].steeringAngleDeg - sm['liveParameters'].angleOffsetDeg accel_clip = limit_accel_in_turns(v_ego, steer_angle_without_offset, accel_clip, self.CP) @@ -163,7 +163,7 @@ class LongitudinalPlanner: output_a_target_e2e = sm['modelV2'].action.desiredAcceleration output_should_stop_e2e = sm['modelV2'].action.shouldStop - if self.mode == 'acc': + if mode == 'acc': output_a_target = output_a_target_mpc self.output_should_stop = output_should_stop_mpc else: diff --git a/selfdrive/controls/lib/tests/__init__.py b/selfdrive/controls/lib/tests/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/selfdrive/controls/lib/tests/test_latcontrol.py b/selfdrive/controls/tests/test_latcontrol.py similarity index 88% rename from selfdrive/controls/lib/tests/test_latcontrol.py rename to selfdrive/controls/tests/test_latcontrol.py index f32e20b1e5..0ce06dc996 100644 --- a/selfdrive/controls/lib/tests/test_latcontrol.py +++ b/selfdrive/controls/tests/test_latcontrol.py @@ -5,6 +5,7 @@ from opendbc.car.car_helpers import interfaces from opendbc.car.honda.values import CAR as HONDA from opendbc.car.toyota.values import CAR as TOYOTA from opendbc.car.nissan.values import CAR as NISSAN +from opendbc.car.gm.values import CAR as GM from opendbc.car.vehicle_model import VehicleModel from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque @@ -13,7 +14,8 @@ from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle class TestLatControl: - @parameterized.expand([(HONDA.HONDA_CIVIC, LatControlPID), (TOYOTA.TOYOTA_RAV4, LatControlTorque), (NISSAN.NISSAN_LEAF, LatControlAngle)]) + @parameterized.expand([(HONDA.HONDA_CIVIC, LatControlPID), (TOYOTA.TOYOTA_RAV4, LatControlTorque), + (NISSAN.NISSAN_LEAF, LatControlAngle), (GM.CHEVROLET_BOLT_EUV, LatControlTorque)]) def test_saturation(self, car_name, controller): CarInterface = interfaces[car_name] CP = CarInterface.get_non_essential_params(car_name) diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py index 3aafbd591d..71b5291dfb 100755 --- a/selfdrive/locationd/torqued.py +++ b/selfdrive/locationd/torqued.py @@ -32,7 +32,7 @@ MIN_BUCKET_POINTS = np.array([100, 300, 500, 500, 500, 500, 300, 100]) MIN_ENGAGE_BUFFER = 2 # secs VERSION = 1 # bump this to invalidate old parameter caches -ALLOWED_CARS = ['toyota', 'hyundai', 'rivian'] +ALLOWED_CARS = ['toyota', 'hyundai', 'rivian', 'honda'] def slope2rot(slope): diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index 707b221bb9..8bc8bf01ab 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -102,15 +102,12 @@ class ModelState: 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.full_prev_desired_curv = np.zeros((1, ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.PREV_DESIRED_CURV_LEN), dtype=np.float32) self.temporal_idxs = slice(-1-(ModelConstants.TEMPORAL_SKIP*(ModelConstants.INPUT_HISTORY_BUFFER_LEN-1)), None, ModelConstants.TEMPORAL_SKIP) # policy inputs self.numpy_inputs = { 'desire': np.zeros((1, ModelConstants.INPUT_HISTORY_BUFFER_LEN, ModelConstants.DESIRE_LEN), dtype=np.float32), 'traffic_convention': np.zeros((1, ModelConstants.TRAFFIC_CONVENTION_LEN), dtype=np.float32), - 'lateral_control_params': np.zeros((1, ModelConstants.LATERAL_CONTROL_PARAMS_LEN), dtype=np.float32), - 'prev_desired_curv': np.zeros((1, ModelConstants.INPUT_HISTORY_BUFFER_LEN, ModelConstants.PREV_DESIRED_CURV_LEN), dtype=np.float32), 'features_buffer': np.zeros((1, ModelConstants.INPUT_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32), } @@ -143,7 +140,6 @@ class ModelState: 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'] - self.numpy_inputs['lateral_control_params'][:] = inputs['lateral_control_params'] imgs_cl = {name: self.frames[name].prepare(bufs[name], transforms[name].flatten()) for name in self.vision_input_names} if TICI and not USBGPU: @@ -169,11 +165,6 @@ class ModelState: 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)) - # TODO model only uses last value now - self.full_prev_desired_curv[0,:-1] = self.full_prev_desired_curv[0,1:] - self.full_prev_desired_curv[0,-1,:] = policy_outputs_dict['desired_curvature'][0, :] - self.numpy_inputs['prev_desired_curv'][:] = 0*self.full_prev_desired_curv[0, self.temporal_idxs] - combined_outputs_dict = {**vision_outputs_dict, **policy_outputs_dict} if SEND_RAW_PRED: combined_outputs_dict['raw_pred'] = np.concatenate([self.vision_output.copy(), self.policy_output.copy()]) @@ -292,7 +283,6 @@ def main(demo=False): frame_id = sm["roadCameraState"].frameId v_ego = max(sm["carState"].vEgo, 0.) lat_delay = sm["liveDelay"].lateralDelay + LAT_SMOOTH_SECONDS - lateral_control_params = np.array([v_ego, lat_delay], dtype=np.float32) if sm.updated["liveCalibration"] and sm.seen['roadCameraState'] and sm.seen['deviceState']: device_from_calib_euler = np.array(sm["liveCalibration"].rpyCalib, dtype=np.float32) dc = DEVICE_CAMERAS[(str(sm['deviceState'].deviceType), str(sm['roadCameraState'].sensor))] @@ -325,7 +315,6 @@ def main(demo=False): inputs:dict[str, np.ndarray] = { 'desire': vec_desire, 'traffic_convention': traffic_convention, - 'lateral_control_params': lateral_control_params, } mt1 = time.perf_counter() diff --git a/selfdrive/modeld/models/driving_policy.onnx b/selfdrive/modeld/models/driving_policy.onnx index 187a3b2ecf..867a0d3b9b 100644 --- a/selfdrive/modeld/models/driving_policy.onnx +++ b/selfdrive/modeld/models/driving_policy.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:22aec22a10ce09384d4a4af2a0bbff08d54af7e0c888503508f356fae4ff0e29 -size 15583374 +oid sha256:04b763fb71efe57a8a4c4168a8043ecd58939015026ded0dc755ded6905ac251 +size 12343523 diff --git a/selfdrive/modeld/models/driving_vision.onnx b/selfdrive/modeld/models/driving_vision.onnx index 18f63358db..ce0dc927e7 100644 --- a/selfdrive/modeld/models/driving_vision.onnx +++ b/selfdrive/modeld/models/driving_vision.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:c824f68646a3b94f117f01c70dc8316fb466e05fbd42ccdba440b8a8dc86914b -size 46265993 +oid sha256:e66bb8d53eced3786ed71a59b55ffc6810944cb217f0518621cc76303260a1ef +size 46271991 diff --git a/selfdrive/modeld/parse_model_outputs.py b/selfdrive/modeld/parse_model_outputs.py index b89de27594..038f51ca9c 100644 --- a/selfdrive/modeld/parse_model_outputs.py +++ b/selfdrive/modeld/parse_model_outputs.py @@ -22,9 +22,10 @@ class Parser: self.ignore_missing = ignore_missing def check_missing(self, outs, name): - if name not in outs and not self.ignore_missing: + missing = name not in outs + if missing and not self.ignore_missing: raise ValueError(f"Missing output {name}") - return name not in outs + return missing def parse_categorical_crossentropy(self, name, outs, out_shape=None): if self.check_missing(outs, name): @@ -84,6 +85,13 @@ class Parser: outs[name] = pred_mu_final.reshape(final_shape) outs[name + '_stds'] = pred_std_final.reshape(final_shape) + def is_mhp(self, outs, name, shape): + if self.check_missing(outs, name): + return False + if outs[name].shape[1] == 2 * shape: + return False + return True + def parse_vision_outputs(self, outs: dict[str, np.ndarray]) -> dict[str, np.ndarray]: self.parse_mdn('pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,)) self.parse_mdn('wide_from_device_euler', outs, in_N=0, out_N=0, out_shape=(ModelConstants.WIDE_FROM_DEVICE_WIDTH,)) @@ -94,17 +102,17 @@ class Parser: self.parse_categorical_crossentropy('desire_pred', outs, out_shape=(ModelConstants.DESIRE_PRED_LEN,ModelConstants.DESIRE_PRED_WIDTH)) self.parse_binary_crossentropy('meta', outs) self.parse_binary_crossentropy('lead_prob', outs) - self.parse_mdn('lead', outs, in_N=ModelConstants.LEAD_MHP_N, out_N=ModelConstants.LEAD_MHP_SELECTION, - out_shape=(ModelConstants.LEAD_TRAJ_LEN,ModelConstants.LEAD_WIDTH)) + lead_mhp = self.is_mhp(outs, 'lead', ModelConstants.LEAD_MHP_SELECTION * ModelConstants.LEAD_TRAJ_LEN * ModelConstants.LEAD_WIDTH) + lead_in_N, lead_out_N = (ModelConstants.LEAD_MHP_N, ModelConstants.LEAD_MHP_SELECTION) if lead_mhp else (0, 0) + lead_out_shape = (ModelConstants.LEAD_TRAJ_LEN, ModelConstants.LEAD_WIDTH) if lead_mhp else \ + (ModelConstants.LEAD_MHP_SELECTION, ModelConstants.LEAD_TRAJ_LEN, ModelConstants.LEAD_WIDTH) + self.parse_mdn('lead', outs, in_N=lead_in_N, out_N=lead_out_N, out_shape=lead_out_shape) return outs def parse_policy_outputs(self, outs: dict[str, np.ndarray]) -> dict[str, np.ndarray]: - self.parse_mdn('plan', outs, in_N=ModelConstants.PLAN_MHP_N, out_N=ModelConstants.PLAN_MHP_SELECTION, - out_shape=(ModelConstants.IDX_N,ModelConstants.PLAN_WIDTH)) - if 'lat_planner_solution' in outs: - self.parse_mdn('lat_planner_solution', outs, in_N=0, out_N=0, out_shape=(ModelConstants.IDX_N,ModelConstants.LAT_PLANNER_SOLUTION_WIDTH)) - if 'desired_curvature' in outs: - self.parse_mdn('desired_curvature', outs, in_N=0, out_N=0, out_shape=(ModelConstants.DESIRED_CURV_WIDTH,)) + plan_mhp = self.is_mhp(outs, 'plan', ModelConstants.IDX_N * ModelConstants.PLAN_WIDTH) + plan_in_N, plan_out_N = (ModelConstants.PLAN_MHP_N, ModelConstants.PLAN_MHP_SELECTION) if plan_mhp else (0, 0) + self.parse_mdn('plan', outs, in_N=plan_in_N, out_N=plan_out_N, out_shape=(ModelConstants.IDX_N, ModelConstants.PLAN_WIDTH)) self.parse_categorical_crossentropy('desire_state', outs, out_shape=(ModelConstants.DESIRE_PRED_WIDTH,)) return outs diff --git a/selfdrive/pandad/pandad.py b/selfdrive/pandad/pandad.py index b33ffb6473..4e49813f5d 100755 --- a/selfdrive/pandad/pandad.py +++ b/selfdrive/pandad/pandad.py @@ -87,7 +87,7 @@ def main() -> None: # TODO: remove this in the next AGNOS # wait until USB is up before counting - if time.monotonic() < 35.: + if time.monotonic() < 60.: no_internal_panda_count = 0 # Handle missing internal panda diff --git a/selfdrive/selfdrived/alerts_offroad.json b/selfdrive/selfdrived/alerts_offroad.json index 7c97f5a1c2..42aca22008 100644 --- a/selfdrive/selfdrived/alerts_offroad.json +++ b/selfdrive/selfdrived/alerts_offroad.json @@ -42,7 +42,7 @@ "severity": 0 }, "Offroad_ExcessiveActuation": { - "text": "openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support.", + "text": "openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting.", "severity": 1, "_comment": "Set extra field to lateral or longitudinal." } diff --git a/selfdrive/selfdrived/events.py b/selfdrive/selfdrived/events.py index 49c2cea4ac..9da7125dd8 100755 --- a/selfdrive/selfdrived/events.py +++ b/selfdrive/selfdrived/events.py @@ -11,6 +11,8 @@ from openpilot.common.constants import CV from openpilot.common.git import get_short_branch from openpilot.common.realtime import DT_CTRL from openpilot.selfdrive.locationd.calibrationd import MIN_SPEED_FILTER +from openpilot.system.micd import SAMPLE_RATE, SAMPLE_BUFFER +from openpilot.selfdrive.ui.feedback.feedbackd import FEEDBACK_MAX_DURATION AlertSize = log.SelfdriveState.AlertSize AlertStatus = log.SelfdriveState.AlertStatus @@ -198,6 +200,7 @@ class StartupAlert(Alert): Priority.LOWER, VisualAlert.none, AudibleAlert.none, 5.), + # ********** helper functions ********** def get_display_speed(speed_ms: float, metric: bool) -> str: speed = int(round(speed_ms * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH))) @@ -252,6 +255,14 @@ def calibration_incomplete_alert(CP: car.CarParams, CS: car.CarState, sm: messag Priority.LOWEST, VisualAlert.none, AudibleAlert.none, .2) +def audio_feedback_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: + duration = FEEDBACK_MAX_DURATION - ((sm['audioFeedback'].blockNum + 1) * SAMPLE_BUFFER / SAMPLE_RATE) + return NormalPermanentAlert( + "Recording Audio Feedback", + f"{round(duration)} second{'s' if round(duration) != 1 else ''} remaining. Press again to save early.", + priority=Priority.LOW) + + # *** debug alerts *** def out_of_space_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: @@ -370,6 +381,7 @@ def invalid_lkas_setting_alert(CP: car.CarParams, CS: car.CarState, sm: messagin return NormalPermanentAlert("Invalid LKAS setting", text) + EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { # ********** events with no alerts ********** @@ -991,9 +1003,13 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { ET.WARNING: personality_changed_alert, }, - EventName.userFlag: { + EventName.userBookmark: { ET.PERMANENT: NormalPermanentAlert("Bookmark Saved", duration=1.5), }, + + EventName.audioFeedback: { + ET.PERMANENT: audio_feedback_alert, + }, } diff --git a/selfdrive/selfdrived/helpers.py b/selfdrive/selfdrived/helpers.py new file mode 100644 index 0000000000..f7468cbe43 --- /dev/null +++ b/selfdrive/selfdrived/helpers.py @@ -0,0 +1,54 @@ +import math +from enum import StrEnum, auto + +from cereal import car, messaging +from openpilot.common.realtime import DT_CTRL +from openpilot.selfdrive.locationd.helpers import Pose +from opendbc.car import ACCELERATION_DUE_TO_GRAVITY +from opendbc.car.lateral import ISO_LATERAL_ACCEL +from opendbc.car.interfaces import ACCEL_MIN, ACCEL_MAX + +MIN_EXCESSIVE_ACTUATION_COUNT = int(0.25 / DT_CTRL) +MIN_LATERAL_ENGAGE_BUFFER = int(1 / DT_CTRL) + + +class ExcessiveActuationType(StrEnum): + LONGITUDINAL = auto() + LATERAL = auto() + + +class ExcessiveActuationCheck: + def __init__(self): + self._excessive_counter = 0 + self._engaged_counter = 0 + + def update(self, sm: messaging.SubMaster, CS: car.CarState, calibrated_pose: Pose) -> ExcessiveActuationType | None: + # CS.aEgo can be noisy to bumps in the road, transitioning from standstill, losing traction, etc. + # longitudinal + accel_calibrated = calibrated_pose.acceleration.x + excessive_long_actuation = sm['carControl'].longActive and (accel_calibrated > ACCEL_MAX * 2 or accel_calibrated < ACCEL_MIN * 2) + + # lateral + yaw_rate = calibrated_pose.angular_velocity.yaw + roll = sm['liveParameters'].roll + roll_compensated_lateral_accel = (CS.vEgo * yaw_rate) - (math.sin(roll) * ACCELERATION_DUE_TO_GRAVITY) + + # Prevent false positives after overriding + excessive_lat_actuation = False + self._engaged_counter = self._engaged_counter + 1 if sm['carControl'].latActive and not CS.steeringPressed else 0 + if self._engaged_counter > MIN_LATERAL_ENGAGE_BUFFER: + if abs(roll_compensated_lateral_accel) > ISO_LATERAL_ACCEL * 2: + excessive_lat_actuation = True + + # livePose acceleration can be noisy due to bad mounting or aliased livePose measurements + livepose_valid = abs(CS.aEgo - accel_calibrated) < 2 + self._excessive_counter = self._excessive_counter + 1 if livepose_valid and (excessive_long_actuation or excessive_lat_actuation) else 0 + + excessive_type = None + if self._excessive_counter > MIN_EXCESSIVE_ACTUATION_COUNT: + if excessive_long_actuation: + excessive_type = ExcessiveActuationType.LONGITUDINAL + else: + excessive_type = ExcessiveActuationType.LATERAL + + return excessive_type diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py index 96077414de..cf22040e84 100755 --- a/selfdrive/selfdrived/selfdrived.py +++ b/selfdrive/selfdrived/selfdrived.py @@ -7,7 +7,6 @@ import cereal.messaging as messaging from cereal import car, log from msgq.visionipc import VisionIpcClient, VisionStreamType -from opendbc.car.interfaces import ACCEL_MIN, ACCEL_MAX from openpilot.common.params import Params @@ -18,6 +17,7 @@ from openpilot.common.gps import get_gps_location_service from openpilot.selfdrive.car.car_specific import CarSpecificEvents from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose from openpilot.selfdrive.selfdrived.events import Events, ET +from openpilot.selfdrive.selfdrived.helpers import ExcessiveActuationCheck from openpilot.selfdrive.selfdrived.state import StateMachine from openpilot.selfdrive.selfdrived.alertmanager import AlertManager, set_offroad_alert @@ -29,7 +29,6 @@ SIMULATION = "SIMULATION" in os.environ TESTING_CLOSET = "TESTING_CLOSET" in os.environ LONGITUDINAL_PERSONALITY_MAP = {v: k for k, v in log.LongitudinalPersonality.schema.enumerants.items()} -MIN_EXCESSIVE_ACTUATION_COUNT = int(0.25 / DT_CTRL) ThermalStatus = log.DeviceState.ThermalStatus State = log.SelfdriveState.OpenpilotState @@ -43,19 +42,6 @@ SafetyModel = car.CarParams.SafetyModel IGNORED_SAFETY_MODES = (SafetyModel.silent, SafetyModel.noOutput) -def check_excessive_actuation(sm: messaging.SubMaster, CS: car.CarState, calibrated_pose: Pose, counter: int) -> tuple[int, bool]: - # CS.aEgo can be noisy to bumps in the road, transitioning from standstill, losing traction, etc. - accel_calibrated = calibrated_pose.acceleration.x - - # livePose acceleration can be noisy due to bad mounting or aliased livePose measurements - accel_valid = abs(CS.aEgo - accel_calibrated) < 2 - - excessive_actuation = accel_calibrated > ACCEL_MAX * 2 or accel_calibrated < ACCEL_MIN * 2 - counter = counter + 1 if sm['carControl'].longActive and excessive_actuation and accel_valid else 0 - - return counter, counter > MIN_EXCESSIVE_ACTUATION_COUNT - - class SelfdriveD: def __init__(self, CP=None): self.params = Params() @@ -74,6 +60,8 @@ class SelfdriveD: self.pose_calibrator = PoseCalibrator() self.calibrated_pose: Pose | None = None + self.excessive_actuation_check = ExcessiveActuationCheck() + self.excessive_actuation = self.params.get("Offroad_ExcessiveActuation") is not None # Setup sockets self.pm = messaging.PubMaster(['selfdriveState', 'onroadEvents']) @@ -95,7 +83,7 @@ class SelfdriveD: self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', 'liveDelay', 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', - 'controlsState', 'carControl', 'driverAssistance', 'alertDebug', 'userFlag'] + \ + 'controlsState', 'carControl', 'driverAssistance', 'alertDebug', 'userBookmark', 'audioFeedback'] + \ self.camera_packets + self.sensor_packets + self.gps_packets, ignore_alive=ignore, ignore_avg_freq=ignore, ignore_valid=ignore, frequency=int(1/DT_CTRL)) @@ -131,8 +119,6 @@ class SelfdriveD: self.experimental_mode = False self.personality = self.params.get("LongitudinalPersonality", return_default=True) self.recalibrating_seen = False - self.excessive_actuation = self.params.get("Offroad_ExcessiveActuation") is not None - self.excessive_actuation_counter = 0 self.state_machine = StateMachine() self.rk = Ratekeeper(100, print_delay_threshold=None) @@ -181,9 +167,12 @@ class SelfdriveD: self.events.add(EventName.selfdriveInitializing) return - # Check for user flag (bookmark) press - if self.sm.updated['userFlag']: - self.events.add(EventName.userFlag) + # Check for user bookmark press (bookmark button or end of LKAS button feedback) + if self.sm.updated['userBookmark']: + self.events.add(EventName.userBookmark) + + if self.sm.updated['audioFeedback']: + self.events.add(EventName.audioFeedback) # Don't add any more events while in dashcam mode if self.CP.passive: @@ -249,7 +238,10 @@ class SelfdriveD: if self.sm['driverAssistance'].leftLaneDeparture or self.sm['driverAssistance'].rightLaneDeparture: self.events.add(EventName.ldw) - # Check for excessive (longitudinal) actuation + # ****************************************************************************************** + # NOTE: To fork maintainers. + # Disabling or nerfing safety features will get you and your users banned from our servers. + # We recommend that you do not change these numbers from the defaults. if self.sm.updated['liveCalibration']: self.pose_calibrator.feed_live_calib(self.sm['liveCalibration']) if self.sm.updated['livePose']: @@ -257,13 +249,14 @@ class SelfdriveD: self.calibrated_pose = self.pose_calibrator.build_calibrated_pose(device_pose) if self.calibrated_pose is not None: - self.excessive_actuation_counter, excessive_actuation = check_excessive_actuation(self.sm, CS, self.calibrated_pose, self.excessive_actuation_counter) - if not self.excessive_actuation and excessive_actuation: - set_offroad_alert("Offroad_ExcessiveActuation", True, extra_text="longitudinal") + excessive_actuation = self.excessive_actuation_check.update(self.sm, CS, self.calibrated_pose) + if not self.excessive_actuation and excessive_actuation is not None: + set_offroad_alert("Offroad_ExcessiveActuation", True, extra_text=str(excessive_actuation)) self.excessive_actuation = True if self.excessive_actuation: self.events.add(EventName.excessiveActuation) + # ****************************************************************************************** # Handle lane change if self.sm['modelV2'].meta.laneChangeState == LaneChangeState.preLaneChange: diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 29a268b452..56a0fdb61a 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -418,10 +418,10 @@ CONFIGS = [ proc_name="selfdrived", pubs=[ "carState", "deviceState", "pandaStates", "peripheralState", "liveCalibration", "driverMonitoringState", - "longitudinalPlan", "livePose", "liveDelay", "liveParameters", "radarState", - "modelV2", "driverCameraState", "roadCameraState", "wideRoadCameraState", "managerState", - "liveTorqueParameters", "accelerometer", "gyroscope", "carOutput", - "gpsLocationExternal", "gpsLocation", "controlsState", "carControl", "driverAssistance", "alertDebug", + "longitudinalPlan", "livePose", "liveDelay", "liveParameters", "radarState", "modelV2", + "driverCameraState", "roadCameraState", "wideRoadCameraState", "managerState", "liveTorqueParameters", + "accelerometer", "gyroscope", "carOutput", "gpsLocationExternal", "gpsLocation", "controlsState", + "carControl", "driverAssistance", "alertDebug", "audioFeedback", ], subs=["selfdriveState", "onroadEvents"], ignore=["logMonoTime"], diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index eb178b0562..a4297096c0 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -8ff1b4c9c7a34589142a07579b0051acddfe7699 \ No newline at end of file +6d3219bca9f66a229b38a5382d301a92b0147edb \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 54e7039a4e..5868ca4c1c 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -61,7 +61,7 @@ segments = [ ] # dashcamOnly makes don't need to be tested until a full port is done -excluded_interfaces = ["mock", "body"] +excluded_interfaces = ["mock", "body", "psa"] BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" REF_COMMIT_FN = os.path.join(PROC_REPLAY_DIR, "ref_commit") diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index d717698514..98909bfb52 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -54,6 +54,7 @@ while true; do # /data/ciui.py & #fi + awk '{print \$1}' /proc/uptime > /var/tmp/power_watchdog sleep 5s done diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index cd702377e7..0149653c84 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -55,6 +55,7 @@ PROCS = { "selfdrive.locationd.paramsd": 9.0, "selfdrive.locationd.lagd": 11.0, "selfdrive.ui.soundd": 3.0, + "selfdrive.ui.feedback.feedbackd": 1.0, "selfdrive.monitoring.dmonitoringd": 4.0, "./proclogd": 2.0, "system.logmessaged": 1.0, @@ -332,20 +333,18 @@ class TestOnroad: assert np.all(eof_sof_diff > 0) assert np.all(eof_sof_diff < 50*1e6) - first_fid = {c: min(self.ts[c]['frameId']) for c in cams} + first_fid = {min(self.ts[c]['frameId']) for c in cams} + assert len(first_fid) == 1, "Cameras don't start on same frame ID" if cam.endswith('CameraState'): # camerad guarantees that all cams start on frame ID 0 # (note loggerd also needs to start up fast enough to catch it) - assert set(first_fid.values()) == {0, }, "Cameras don't start on frame ID 0" - else: - # encoder guarantees all cams start on the same frame ID - assert len(set(first_fid.values())) == 1, "Cameras don't start on same frame ID" + assert next(iter(first_fid)) < 100, "Cameras start on frame ID too high" # we don't do a full segment rotation, so these might not match exactly - last_fid = {c: max(self.ts[c]['frameId']) for c in cams} - assert max(last_fid.values()) - min(last_fid.values()) < 10 + last_fid = {max(self.ts[c]['frameId']) for c in cams} + assert max(last_fid) - min(last_fid) < 10 - start, end = min(first_fid.values()), min(last_fid.values()) + start, end = min(first_fid), min(last_fid) for i in range(end-start): ts = {c: round(self.ts[c]['timestampSof'][i]/1e6, 1) for c in cams} diff = (max(ts.values()) - min(ts.values())) diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 9d59e2bd48..ba9fa8b7a6 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -63,14 +63,8 @@ if GetOption('extras'): qt_src.remove("main.cc") # replaced by test_runner qt_env.Program('tests/test_translations', [asset_obj, 'tests/test_runner.cc', 'tests/test_translations.cc'] + qt_src, LIBS=qt_libs) - qt_env.SharedLibrary("qt/python_helpers", ["qt/qt_window.cc"], LIBS=qt_libs) - - # setup - qt_env.Program("qt/setup/setup", ["qt/setup/setup.cc", asset_obj], - LIBS=qt_libs + ['curl', 'common']) - + # build installers if arch != "Darwin": - # build installers raylib_env = env.Clone() raylib_env['LIBPATH'] += [f'#third_party/raylib/{arch}/'] raylib_env['LINKFLAGS'].append('-Wl,-strip-debug') @@ -102,7 +96,3 @@ if GetOption('extras'): f = raylib_env.Program(f"installer/installers/installer_{name}", [obj, cont, inter], LIBS=raylib_libs) # keep installers small assert f[0].get_size() < 1900*1e3, f[0].get_size() - -# build watch3 -if arch in ['x86_64', 'aarch64', 'Darwin'] or GetOption('extras'): - qt_env.Program("watch3", ["watch3.cc"], LIBS=qt_libs + ['common', 'msgq', 'visionipc']) diff --git a/selfdrive/ui/feedback/feedbackd.py b/selfdrive/ui/feedback/feedbackd.py new file mode 100755 index 0000000000..2d131a0d5e --- /dev/null +++ b/selfdrive/ui/feedback/feedbackd.py @@ -0,0 +1,71 @@ +#!/usr/bin/env python3 +import cereal.messaging as messaging +from openpilot.common.params import Params +from openpilot.common.swaglog import cloudlog +from cereal import car +from openpilot.system.micd import SAMPLE_RATE, SAMPLE_BUFFER + +FEEDBACK_MAX_DURATION = 10.0 +ButtonType = car.CarState.ButtonEvent.Type + + +def main(): + params = Params() + pm = messaging.PubMaster(['userBookmark', 'audioFeedback']) + sm = messaging.SubMaster(['rawAudioData', 'bookmarkButton', 'carState']) + should_record_audio = False + block_num = 0 + waiting_for_release = False + early_stop_triggered = False + + while True: + sm.update() + should_send_bookmark = False + + # TODO: https://github.com/commaai/openpilot/issues/36015 + if False and sm.updated['carState'] and sm['carState'].canValid: + for be in sm['carState'].buttonEvents: + if be.type == ButtonType.lkas: + if be.pressed: + if not should_record_audio: + if params.get_bool("RecordAudioFeedback"): # Start recording on first press if toggle set + should_record_audio = True + block_num = 0 + waiting_for_release = False + early_stop_triggered = False + cloudlog.info("LKAS button pressed - starting 10-second audio feedback") + else: + should_send_bookmark = True # immediately send bookmark if toggle false + cloudlog.info("LKAS button pressed - bookmarking") + elif should_record_audio and not waiting_for_release: # Wait for release of second press to stop recording early + waiting_for_release = True + elif waiting_for_release: # Second press released + waiting_for_release = False + early_stop_triggered = True + cloudlog.info("LKAS button released - ending recording early") + + if should_record_audio and sm.updated['rawAudioData']: + raw_audio = sm['rawAudioData'] + msg = messaging.new_message('audioFeedback', valid=True) + msg.audioFeedback.audio.data = raw_audio.data + msg.audioFeedback.audio.sampleRate = raw_audio.sampleRate + msg.audioFeedback.blockNum = block_num + block_num += 1 + if (block_num * SAMPLE_BUFFER / SAMPLE_RATE) >= FEEDBACK_MAX_DURATION or early_stop_triggered: # Check for timeout or early stop + should_send_bookmark = True # send bookmark at end of audio segment + should_record_audio = False + early_stop_triggered = False + cloudlog.info("10-second recording completed or second button press - stopping audio feedback") + pm.send('audioFeedback', msg) + + if sm.updated['bookmarkButton']: + cloudlog.info("Bookmark button pressed!") + should_send_bookmark = True + + if should_send_bookmark: + msg = messaging.new_message('userBookmark', valid=True) + pm.send('userBookmark', msg) + + +if __name__ == '__main__': + main() diff --git a/selfdrive/ui/installer/installer.cc b/selfdrive/ui/installer/installer.cc index 7326e089ab..a9b84b5c06 100644 --- a/selfdrive/ui/installer/installer.cc +++ b/selfdrive/ui/installer/installer.cc @@ -24,11 +24,13 @@ const std::string BRANCH_STR = get_str(BRANCH "? #define GIT_SSH_URL "git@github.com:commaai/openpilot.git" #define CONTINUE_PATH "/data/continue.sh" -const std::string CACHE_PATH = "/data/openpilot.cache"; +const std::string INSTALL_PATH = "/data/openpilot"; +const std::string VALID_CACHE_PATH = "/data/.openpilot_cache"; -#define INSTALL_PATH "/data/openpilot" #define TMP_INSTALL_PATH "/data/tmppilot" +const int FONT_SIZE = 120; + extern const uint8_t str_continue[] asm("_binary_selfdrive_ui_installer_continue_openpilot_sh_start"); extern const uint8_t str_continue_end[] asm("_binary_selfdrive_ui_installer_continue_openpilot_sh_end"); extern const uint8_t inter_ttf[] asm("_binary_selfdrive_ui_installer_inter_ascii_ttf_start"); @@ -41,6 +43,16 @@ void run(const char* cmd) { assert(err == 0); } +void finishInstall() { + BeginDrawing(); + ClearBackground(BLACK); + const char *m = "Finishing install..."; + int text_width = MeasureText(m, FONT_SIZE); + DrawTextEx(font, m, (Vector2){(float)(GetScreenWidth() - text_width)/2 + FONT_SIZE, (float)(GetScreenHeight() - FONT_SIZE)/2}, FONT_SIZE, 0, WHITE); + EndDrawing(); + util::sleep_for(60 * 1000); +} + void renderProgress(int progress) { BeginDrawing(); ClearBackground(BLACK); @@ -62,11 +74,11 @@ int doInstall() { } // cleanup previous install attempts - run("rm -rf " TMP_INSTALL_PATH " " INSTALL_PATH); + run("rm -rf " TMP_INSTALL_PATH); // do the install - if (util::file_exists(CACHE_PATH)) { - return cachedFetch(CACHE_PATH); + if (util::file_exists(INSTALL_PATH) && util::file_exists(VALID_CACHE_PATH)) { + return cachedFetch(INSTALL_PATH); } else { return freshClone(); } @@ -135,7 +147,9 @@ void cloneFinished(int exitCode) { run("git submodule update --init"); // move into place - run("mv " TMP_INSTALL_PATH " " INSTALL_PATH); + run(("rm -f " + VALID_CACHE_PATH).c_str()); + run(("rm -rf " + INSTALL_PATH).c_str()); + run(util::string_format("mv %s %s", TMP_INSTALL_PATH, INSTALL_PATH.c_str()).c_str()); #ifdef INTERNAL run("mkdir -p /data/params/d/"); @@ -153,9 +167,9 @@ void cloneFinished(int exitCode) { param << value; param.close(); } - run("cd " INSTALL_PATH " && " + run(("cd " + INSTALL_PATH + " && " "git remote set-url origin --push " GIT_SSH_URL " && " - "git config --replace-all remote.origin.fetch \"+refs/heads/*:refs/remotes/origin/*\""); + "git config --replace-all remote.origin.fetch \"+refs/heads/*:refs/remotes/origin/*\"").c_str()); #endif // write continue.sh @@ -171,16 +185,22 @@ void cloneFinished(int exitCode) { run("mv /data/continue.sh.new " CONTINUE_PATH); // wait for the installed software's UI to take over - util::sleep_for(60 * 1000); + finishInstall(); } int main(int argc, char *argv[]) { InitWindow(2160, 1080, "Installer"); - font = LoadFontFromMemory(".ttf", inter_ttf, inter_ttf_end - inter_ttf, 120, NULL, 0); + font = LoadFontFromMemory(".ttf", inter_ttf, inter_ttf_end - inter_ttf, FONT_SIZE, NULL, 0); SetTextureFilter(font.texture, TEXTURE_FILTER_BILINEAR); - renderProgress(0); - int result = doInstall(); - cloneFinished(result); + + if (util::file_exists(CONTINUE_PATH)) { + finishInstall(); + } else { + renderProgress(0); + int result = doInstall(); + cloneFinished(result); + } + CloseWindow(); UnloadFont(font); return 0; diff --git a/selfdrive/ui/layouts/main.py b/selfdrive/ui/layouts/main.py index 144d34e02f..3ab8525d33 100644 --- a/selfdrive/ui/layouts/main.py +++ b/selfdrive/ui/layouts/main.py @@ -19,7 +19,7 @@ class MainLayout(Widget): def __init__(self): super().__init__() - self._pm = messaging.PubMaster(['userFlag']) + self._pm = messaging.PubMaster(['bookmarkButton']) self._sidebar = Sidebar() self._current_mode = MainState.HOME @@ -40,7 +40,7 @@ class MainLayout(Widget): def _setup_callbacks(self): self._sidebar.set_callbacks(on_settings=self._on_settings_clicked, - on_flag=self._on_flag_clicked) + on_flag=self._on_bookmark_clicked) self._layouts[MainState.HOME]._setup_widget.set_open_settings_callback(lambda: self.open_settings(PanelType.FIREHOSE)) self._layouts[MainState.SETTINGS].set_callbacks(on_close=self._set_mode_for_state) self._layouts[MainState.ONROAD].set_callbacks(on_click=self._on_onroad_clicked) @@ -76,10 +76,10 @@ class MainLayout(Widget): def _on_settings_clicked(self): self.open_settings(PanelType.DEVICE) - def _on_flag_clicked(self): - user_flag = messaging.new_message('userFlag') - user_flag.valid = True - self._pm.send('userFlag', user_flag) + def _on_bookmark_clicked(self): + user_bookmark = messaging.new_message('bookmarkButton') + user_bookmark.valid = True + self._pm.send('bookmarkButton', user_bookmark) def _on_onroad_clicked(self): self._sidebar.set_visible(not self._sidebar.is_visible) diff --git a/selfdrive/ui/layouts/settings/settings.py b/selfdrive/ui/layouts/settings/settings.py index a322f21e80..674e5005f4 100644 --- a/selfdrive/ui/layouts/settings/settings.py +++ b/selfdrive/ui/layouts/settings/settings.py @@ -28,7 +28,7 @@ PANEL_COLOR = rl.Color(41, 41, 41, 255) CLOSE_BTN_COLOR = rl.Color(41, 41, 41, 255) CLOSE_BTN_PRESSED = rl.Color(59, 59, 59, 255) TEXT_NORMAL = rl.Color(128, 128, 128, 255) -TEXT_SELECTED = rl.Color(255, 255, 255, 255) +TEXT_SELECTED = rl.WHITE class PanelType(IntEnum): diff --git a/selfdrive/ui/layouts/sidebar.py b/selfdrive/ui/layouts/sidebar.py index 82d499716d..cdbfa4c04c 100644 --- a/selfdrive/ui/layouts/sidebar.py +++ b/selfdrive/ui/layouts/sidebar.py @@ -24,18 +24,18 @@ NetworkType = log.DeviceState.NetworkType # Color scheme class Colors: SIDEBAR_BG = rl.Color(57, 57, 57, 255) - WHITE = rl.Color(255, 255, 255, 255) + WHITE = rl.WHITE WHITE_DIM = rl.Color(255, 255, 255, 85) GRAY = rl.Color(84, 84, 84, 255) # Status colors - GOOD = rl.Color(255, 255, 255, 255) + GOOD = rl.WHITE WARNING = rl.Color(218, 202, 37, 255) DANGER = rl.Color(201, 34, 49, 255) # UI elements METRIC_BORDER = rl.Color(255, 255, 255, 85) - BUTTON_NORMAL = rl.Color(255, 255, 255, 255) + BUTTON_NORMAL = rl.WHITE BUTTON_PRESSED = rl.Color(255, 255, 255, 166) @@ -146,7 +146,7 @@ class Sidebar(Widget): def _draw_buttons(self, rect: rl.Rectangle): mouse_pos = rl.get_mouse_position() - mouse_down = self._is_pressed and rl.is_mouse_button_down(rl.MouseButton.MOUSE_BUTTON_LEFT) + mouse_down = self.is_pressed and rl.is_mouse_button_down(rl.MouseButton.MOUSE_BUTTON_LEFT) # Settings button settings_down = mouse_down and rl.check_collision_point_rec(mouse_pos, SETTINGS_BTN) diff --git a/selfdrive/ui/lib/prime_state.py b/selfdrive/ui/lib/prime_state.py index b6c0d88469..da2ff899dd 100644 --- a/selfdrive/ui/lib/prime_state.py +++ b/selfdrive/ui/lib/prime_state.py @@ -2,12 +2,15 @@ from enum import IntEnum import os import threading import time +from functools import lru_cache from openpilot.common.api import Api, api_get from openpilot.common.params import Params from openpilot.common.swaglog import cloudlog from openpilot.system.athena.registration import UNREGISTERED_DONGLE_ID +TOKEN_EXPIRY_HOURS = 2 + class PrimeType(IntEnum): UNKNOWN = -2, @@ -20,6 +23,12 @@ class PrimeType(IntEnum): PURPLE = 5, +@lru_cache(maxsize=1) +def get_token(dongle_id: str, t: int): + print('getting token') + return Api(dongle_id).get_token(expiry_hours=TOKEN_EXPIRY_HOURS) + + class PrimeState: FETCH_INTERVAL = 5.0 # seconds between API calls API_TIMEOUT = 10.0 # seconds for API requests @@ -49,13 +58,15 @@ class PrimeState: return try: - identity_token = Api(dongle_id).get_token() + identity_token = get_token(dongle_id, int(time.monotonic() / (TOKEN_EXPIRY_HOURS / 2 * 60 * 60))) response = api_get(f"v1.1/devices/{dongle_id}", timeout=self.API_TIMEOUT, access_token=identity_token) if response.status_code == 200: data = response.json() is_paired = data.get("is_paired", False) prime_type = data.get("prime_type", 0) self.set_type(PrimeType(prime_type) if is_paired else PrimeType.UNPAIRED) + elif response.status_code == 401: + get_token.cache_clear() except Exception as e: cloudlog.error(f"Failed to fetch prime status: {e}") diff --git a/selfdrive/ui/onroad/cameraview.py b/selfdrive/ui/onroad/cameraview.py index cc2c6b4fe7..ca031e2f17 100644 --- a/selfdrive/ui/onroad/cameraview.py +++ b/selfdrive/ui/onroad/cameraview.py @@ -141,6 +141,9 @@ class CameraView(Widget): self.client = None + def __del__(self): + self.close() + def _calc_frame_matrix(self, rect: rl.Rectangle) -> np.ndarray: if not self.frame: return np.eye(3) @@ -337,16 +340,7 @@ class CameraView(Widget): if __name__ == "__main__": - gui_app.init_window("watch3") - road_camera_view = CameraView("camerad", VisionStreamType.VISION_STREAM_ROAD) - driver_camera_view = CameraView("camerad", VisionStreamType.VISION_STREAM_DRIVER) - wide_road_camera_view = CameraView("camerad", VisionStreamType.VISION_STREAM_WIDE_ROAD) - try: - for _ in gui_app.render(): - road_camera_view.render(rl.Rectangle(gui_app.width // 4, 0, gui_app.width // 2, gui_app.height // 2)) - driver_camera_view.render(rl.Rectangle(0, gui_app.height // 2, gui_app.width // 2, gui_app.height // 2)) - wide_road_camera_view.render(rl.Rectangle(gui_app.width // 2, gui_app.height // 2, gui_app.width // 2, gui_app.height // 2)) - finally: - road_camera_view.close() - driver_camera_view.close() - wide_road_camera_view.close() + gui_app.init_window("camera view") + road = CameraView("camerad", VisionStreamType.VISION_STREAM_ROAD) + for _ in gui_app.render(): + road.render(rl.Rectangle(0, 0, gui_app.width, gui_app.height)) diff --git a/selfdrive/ui/onroad/exp_button.py b/selfdrive/ui/onroad/exp_button.py index e6748e4e09..27f5763077 100644 --- a/selfdrive/ui/onroad/exp_button.py +++ b/selfdrive/ui/onroad/exp_button.py @@ -50,7 +50,7 @@ class ExpButton(Widget): center_y = int(self._rect.y + self._rect.height // 2) mouse_over = rl.check_collision_point_rec(rl.get_mouse_position(), self._rect) - mouse_down = rl.is_mouse_button_down(rl.MouseButton.MOUSE_BUTTON_LEFT) and self._is_pressed + mouse_down = rl.is_mouse_button_down(rl.MouseButton.MOUSE_BUTTON_LEFT) and self.is_pressed self._white_color.a = 180 if (mouse_down and mouse_over) or not self._engageable else 255 texture = self._txt_exp if self._held_or_actual_mode() else self._txt_wheel diff --git a/selfdrive/ui/onroad/hud_renderer.py b/selfdrive/ui/onroad/hud_renderer.py index 4ae713d9db..536d993389 100644 --- a/selfdrive/ui/onroad/hud_renderer.py +++ b/selfdrive/ui/onroad/hud_renderer.py @@ -34,7 +34,7 @@ class FontSizes: @dataclass(frozen=True) class Colors: - white: rl.Color = rl.Color(255, 255, 255, 255) + white: rl.Color = rl.WHITE disengaged: rl.Color = rl.Color(145, 155, 149, 255) override: rl.Color = rl.Color(145, 155, 149, 255) # Added engaged: rl.Color = rl.Color(128, 216, 166, 255) @@ -47,7 +47,7 @@ class Colors: white_translucent: rl.Color = rl.Color(255, 255, 255, 200) border_translucent: rl.Color = rl.Color(255, 255, 255, 75) header_gradient_start: rl.Color = rl.Color(0, 0, 0, 114) - header_gradient_end: rl.Color = rl.Color(0, 0, 0, 0) + header_gradient_end: rl.Color = rl.BLANK UI_CONFIG = UIConfig() diff --git a/selfdrive/ui/onroad/model_renderer.py b/selfdrive/ui/onroad/model_renderer.py index 4439141a40..932773755d 100644 --- a/selfdrive/ui/onroad/model_renderer.py +++ b/selfdrive/ui/onroad/model_renderer.py @@ -187,9 +187,9 @@ class ModelRenderer(Widget): self._path.raw_points, 0.9, self._path_offset_z, max_idx, allow_invert=False ) - self._update_experimental_gradient(self._rect.height) + self._update_experimental_gradient() - def _update_experimental_gradient(self, height): + def _update_experimental_gradient(self): """Pre-calculate experimental mode gradient colors""" if not self._experimental_mode: return @@ -201,22 +201,21 @@ class ModelRenderer(Widget): i = 0 while i < max_len: - track_idx = max_len - i - 1 # flip idx to start from bottom right - track_y = self._path.projected_points[track_idx][1] - if track_y < 0 or track_y > height: + # Some points (screen space) are out of frame (rect space) + track_y = self._path.projected_points[i][1] + if track_y < self._rect.y or track_y > (self._rect.y + self._rect.height): i += 1 continue - # Calculate color based on acceleration - lin_grad_point = (height - track_y) / height + # Calculate color based on acceleration (0 is bottom, 1 is top) + lin_grad_point = 1 - (track_y - self._rect.y) / self._rect.height # speed up: 120, slow down: 0 - path_hue = max(min(60 + self._acceleration_x[i] * 35, 120), 0) - path_hue = int(path_hue * 100 + 0.5) / 100 + path_hue = np.clip(60 + self._acceleration_x[i] * 35, 0, 120) saturation = min(abs(self._acceleration_x[i] * 1.5), 1) - lightness = self._map_val(saturation, 0.0, 1.0, 0.95, 0.62) - alpha = self._map_val(lin_grad_point, 0.75 / 2.0, 0.75, 0.4, 0.0) + lightness = np.interp(saturation, [0.0, 1.0], [0.95, 0.62]) + alpha = np.interp(lin_grad_point, [0.75 / 2.0, 0.75], [0.4, 0.0]) # Use HSL to RGB conversion color = self._hsla_to_color(path_hue / 360.0, saturation, lightness, alpha) @@ -280,7 +279,7 @@ class ModelRenderer(Widget): if self._experimental_mode: # Draw with acceleration coloring - if len(self._exp_gradient['colors']) > 2: + if len(self._exp_gradient['colors']) > 1: draw_polygon(self._rect, self._path.projected_points, gradient=self._exp_gradient) else: draw_polygon(self._rect, self._path.projected_points, rl.Color(255, 255, 255, 30)) @@ -409,13 +408,6 @@ class ModelRenderer(Widget): return np.vstack((left_screen.T, right_screen[:, ::-1].T)).astype(np.float32) - @staticmethod - def _map_val(x, x0, x1, y0, y1): - x = np.clip(x, x0, x1) - ra = x1 - x0 - rb = y1 - y0 - return (x - x0) * rb / ra + y0 if ra != 0 else y0 - @staticmethod def _hsla_to_color(h, s, l, a): rgb = colorsys.hls_to_rgb(h, l, s) diff --git a/selfdrive/ui/qt/python_helpers.py b/selfdrive/ui/qt/python_helpers.py deleted file mode 100644 index 1f6d43f309..0000000000 --- a/selfdrive/ui/qt/python_helpers.py +++ /dev/null @@ -1,23 +0,0 @@ -import os -import platform -from cffi import FFI - -import sip - -from openpilot.common.basedir import BASEDIR - -def suffix(): - return ".dylib" if platform.system() == "Darwin" else ".so" - - -def get_ffi(): - lib = os.path.join(BASEDIR, "selfdrive", "ui", "qt", "libpython_helpers" + suffix()) - - ffi = FFI() - ffi.cdef("void set_main_window(void *w);") - return ffi, ffi.dlopen(lib) - - -def set_main_window(widget): - ffi, lib = get_ffi() - lib.set_main_window(ffi.cast('void*', sip.unwrapinstance(widget))) diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc deleted file mode 100644 index 38955bf59d..0000000000 --- a/selfdrive/ui/qt/setup/setup.cc +++ /dev/null @@ -1,541 +0,0 @@ -#include "selfdrive/ui/qt/setup/setup.h" - -#include -#include -#include -#include - -#include -#include -#include - -#include - -#include "common/util.h" -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/api.h" -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/network/networking.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/input.h" - -const std::string USER_AGENT = "AGNOSSetup-"; -const QString OPENPILOT_URL = "https://openpilot.comma.ai"; - -bool is_elf(char *fname) { - FILE *fp = fopen(fname, "rb"); - if (fp == NULL) { - return false; - } - char buf[4]; - size_t n = fread(buf, 1, 4, fp); - fclose(fp); - return n == 4 && buf[0] == 0x7f && buf[1] == 'E' && buf[2] == 'L' && buf[3] == 'F'; -} - -void Setup::download(QString url) { - // autocomplete incomplete urls - if (QRegularExpression("^([^/.]+)/([^/]+)$").match(url).hasMatch()) { - url.prepend("https://installer.comma.ai/"); - } - - CURL *curl = curl_easy_init(); - if (!curl) { - emit finished(url, tr("Something went wrong. Reboot the device.")); - return; - } - - auto version = util::read_file("/VERSION"); - - struct curl_slist *list = NULL; - std::string header = "X-openpilot-serial: " + Hardware::get_serial(); - list = curl_slist_append(list, header.c_str()); - - char tmpfile[] = "/tmp/installer_XXXXXX"; - FILE *fp = fdopen(mkstemp(tmpfile), "wb"); - - curl_easy_setopt(curl, CURLOPT_URL, url.toStdString().c_str()); - curl_easy_setopt(curl, CURLOPT_WRITEFUNCTION, NULL); - curl_easy_setopt(curl, CURLOPT_WRITEDATA, fp); - curl_easy_setopt(curl, CURLOPT_VERBOSE, 1L); - curl_easy_setopt(curl, CURLOPT_FOLLOWLOCATION, 1L); - curl_easy_setopt(curl, CURLOPT_USERAGENT, (USER_AGENT + version).c_str()); - curl_easy_setopt(curl, CURLOPT_HTTPHEADER, list); - curl_easy_setopt(curl, CURLOPT_TIMEOUT, 30L); - - int ret = curl_easy_perform(curl); - long res_status = 0; - curl_easy_getinfo(curl, CURLINFO_RESPONSE_CODE, &res_status); - - if (ret != CURLE_OK || res_status != 200) { - emit finished(url, tr("Ensure the entered URL is valid, and the device’s internet connection is good.")); - } else if (!is_elf(tmpfile)) { - emit finished(url, tr("No custom software found at this URL.")); - } else { - rename(tmpfile, "/tmp/installer"); - - FILE *fp_url = fopen("/tmp/installer_url", "w"); - fprintf(fp_url, "%s", url.toStdString().c_str()); - fclose(fp_url); - - emit finished(url); - } - - curl_slist_free_all(list); - curl_easy_cleanup(curl); - fclose(fp); -} - -QWidget * Setup::low_voltage() { - QWidget *widget = new QWidget(); - QVBoxLayout *main_layout = new QVBoxLayout(widget); - main_layout->setContentsMargins(55, 0, 55, 55); - main_layout->setSpacing(0); - - // inner text layout: warning icon, title, and body - QVBoxLayout *inner_layout = new QVBoxLayout(); - inner_layout->setContentsMargins(110, 144, 365, 0); - main_layout->addLayout(inner_layout); - - QLabel *triangle = new QLabel(); - triangle->setPixmap(QPixmap(ASSET_PATH + "icons/warning.png")); - inner_layout->addWidget(triangle, 0, Qt::AlignTop | Qt::AlignLeft); - inner_layout->addSpacing(80); - - QLabel *title = new QLabel(tr("WARNING: Low Voltage")); - title->setStyleSheet("font-size: 90px; font-weight: 500; color: #FF594F;"); - inner_layout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); - - inner_layout->addSpacing(25); - - QLabel *body = new QLabel(tr("Power your device in a car with a harness or proceed at your own risk.")); - body->setWordWrap(true); - body->setAlignment(Qt::AlignTop | Qt::AlignLeft); - body->setStyleSheet("font-size: 80px; font-weight: 300;"); - inner_layout->addWidget(body); - - inner_layout->addStretch(); - - // power off + continue buttons - QHBoxLayout *blayout = new QHBoxLayout(); - blayout->setSpacing(50); - main_layout->addLayout(blayout, 0); - - QPushButton *poweroff = new QPushButton(tr("Power off")); - poweroff->setObjectName("navBtn"); - blayout->addWidget(poweroff); - QObject::connect(poweroff, &QPushButton::clicked, this, [=]() { - Hardware::poweroff(); - }); - - QPushButton *cont = new QPushButton(tr("Continue")); - cont->setObjectName("navBtn"); - blayout->addWidget(cont); - QObject::connect(cont, &QPushButton::clicked, this, &Setup::nextPage); - - return widget; -} - -QWidget * Setup::custom_software_warning() { - QWidget *widget = new QWidget(); - QVBoxLayout *main_layout = new QVBoxLayout(widget); - main_layout->setContentsMargins(55, 0, 55, 55); - main_layout->setSpacing(0); - - QVBoxLayout *inner_layout = new QVBoxLayout(); - inner_layout->setContentsMargins(110, 110, 300, 0); - main_layout->addLayout(inner_layout); - - QLabel *title = new QLabel(tr("WARNING: Custom Software")); - title->setStyleSheet("font-size: 90px; font-weight: 500; color: #FF594F;"); - inner_layout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); - - inner_layout->addSpacing(25); - - QLabel *body = new QLabel(tr("Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle.\n\nIf you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later.")); - body->setWordWrap(true); - body->setAlignment(Qt::AlignTop | Qt::AlignLeft); - body->setStyleSheet("font-size: 65px; font-weight: 300;"); - inner_layout->addWidget(body); - - inner_layout->addStretch(); - - QHBoxLayout *blayout = new QHBoxLayout(); - blayout->setSpacing(50); - main_layout->addLayout(blayout, 0); - - QPushButton *back = new QPushButton(tr("Back")); - back->setObjectName("navBtn"); - blayout->addWidget(back); - QObject::connect(back, &QPushButton::clicked, this, &Setup::prevPage); - - QPushButton *cont = new QPushButton(tr("Continue")); - cont->setObjectName("navBtn"); - blayout->addWidget(cont); - QObject::connect(cont, &QPushButton::clicked, this, [=]() { - QTimer::singleShot(0, [=]() { - setCurrentWidget(downloading_widget); - }); - QString url = InputDialog::getText(tr("Enter URL"), this, tr("for Custom Software")); - if (!url.isEmpty()) { - QTimer::singleShot(1000, this, [=]() { - download(url); - }); - } else { - setCurrentWidget(software_selection_widget); - } - }); - - return widget; -} - -QWidget * Setup::getting_started() { - QWidget *widget = new QWidget(); - - QHBoxLayout *main_layout = new QHBoxLayout(widget); - main_layout->setMargin(0); - - QVBoxLayout *vlayout = new QVBoxLayout(); - vlayout->setContentsMargins(165, 280, 100, 0); - main_layout->addLayout(vlayout); - - QLabel *title = new QLabel(tr("Getting Started")); - title->setStyleSheet("font-size: 90px; font-weight: 500;"); - vlayout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); - - vlayout->addSpacing(90); - QLabel *desc = new QLabel(tr("Before we get on the road, let’s finish installation and cover some details.")); - desc->setWordWrap(true); - desc->setStyleSheet("font-size: 80px; font-weight: 300;"); - vlayout->addWidget(desc, 0, Qt::AlignTop | Qt::AlignLeft); - - vlayout->addStretch(); - - QPushButton *btn = new QPushButton(); - btn->setIcon(QIcon(":/images/button_continue_triangle.svg")); - btn->setIconSize(QSize(54, 106)); - btn->setFixedSize(310, 1080); - btn->setProperty("primary", true); - btn->setStyleSheet("border: none;"); - main_layout->addWidget(btn, 0, Qt::AlignRight); - QObject::connect(btn, &QPushButton::clicked, this, &Setup::nextPage); - - return widget; -} - -QWidget * Setup::network_setup() { - QWidget *widget = new QWidget(); - QVBoxLayout *main_layout = new QVBoxLayout(widget); - main_layout->setContentsMargins(55, 50, 55, 50); - - // title - QLabel *title = new QLabel(tr("Connect to Wi-Fi")); - title->setStyleSheet("font-size: 90px; font-weight: 500;"); - main_layout->addWidget(title, 0, Qt::AlignLeft | Qt::AlignTop); - - main_layout->addSpacing(25); - - // wifi widget - Networking *networking = new Networking(this, false); - networking->setStyleSheet("Networking {background-color: #292929; border-radius: 13px;}"); - main_layout->addWidget(networking, 1); - - main_layout->addSpacing(35); - - // back + continue buttons - QHBoxLayout *blayout = new QHBoxLayout; - main_layout->addLayout(blayout); - blayout->setSpacing(50); - - QPushButton *back = new QPushButton(tr("Back")); - back->setObjectName("navBtn"); - QObject::connect(back, &QPushButton::clicked, this, &Setup::prevPage); - blayout->addWidget(back); - - QPushButton *cont = new QPushButton(); - cont->setObjectName("navBtn"); - cont->setProperty("primary", true); - cont->setEnabled(false); - QObject::connect(cont, &QPushButton::clicked, this, &Setup::nextPage); - blayout->addWidget(cont); - - // setup timer for testing internet connection - HttpRequest *request = new HttpRequest(this, false, 2500); - QObject::connect(request, &HttpRequest::requestDone, [=](const QString &, bool success) { - cont->setEnabled(success); - if (success) { - const bool wifi = networking->wifi->currentNetworkType() == NetworkType::WIFI; - cont->setText(wifi ? tr("Continue") : tr("Continue without Wi-Fi")); - } else { - cont->setText(tr("Waiting for internet")); - } - repaint(); - }); - request->sendRequest(OPENPILOT_URL); - QTimer *timer = new QTimer(this); - QObject::connect(timer, &QTimer::timeout, [=]() { - if (!request->active() && cont->isVisible()) { - request->sendRequest(OPENPILOT_URL); - } - }); - timer->start(1000); - - return widget; -} - -QWidget * radio_button(QString title, QButtonGroup *group) { - QPushButton *btn = new QPushButton(title); - btn->setCheckable(true); - group->addButton(btn); - btn->setStyleSheet(R"( - QPushButton { - height: 230; - padding-left: 100px; - padding-right: 100px; - text-align: left; - font-size: 80px; - font-weight: 400; - border-radius: 10px; - background-color: #4F4F4F; - } - QPushButton:checked { - background-color: #465BEA; - } - )"); - - // checkmark icon - QPixmap pix(":/icons/circled_check.svg"); - btn->setIcon(pix); - btn->setIconSize(QSize(0, 0)); - btn->setLayoutDirection(Qt::RightToLeft); - QObject::connect(btn, &QPushButton::toggled, [=](bool checked) { - btn->setIconSize(checked ? QSize(104, 104) : QSize(0, 0)); - }); - return btn; -} - -QWidget * Setup::software_selection() { - QWidget *widget = new QWidget(); - QVBoxLayout *main_layout = new QVBoxLayout(widget); - main_layout->setContentsMargins(55, 50, 55, 50); - main_layout->setSpacing(0); - - // title - QLabel *title = new QLabel(tr("Choose Software to Install")); - title->setStyleSheet("font-size: 90px; font-weight: 500;"); - main_layout->addWidget(title, 0, Qt::AlignLeft | Qt::AlignTop); - - main_layout->addSpacing(50); - - // openpilot + custom radio buttons - QButtonGroup *group = new QButtonGroup(widget); - group->setExclusive(true); - - QWidget *openpilot = radio_button(tr("openpilot"), group); - main_layout->addWidget(openpilot); - - main_layout->addSpacing(30); - - QWidget *custom = radio_button(tr("Custom Software"), group); - main_layout->addWidget(custom); - - main_layout->addStretch(); - - // back + continue buttons - QHBoxLayout *blayout = new QHBoxLayout; - main_layout->addLayout(blayout); - blayout->setSpacing(50); - - QPushButton *back = new QPushButton(tr("Back")); - back->setObjectName("navBtn"); - QObject::connect(back, &QPushButton::clicked, this, &Setup::prevPage); - blayout->addWidget(back); - - QPushButton *cont = new QPushButton(tr("Continue")); - cont->setObjectName("navBtn"); - cont->setEnabled(false); - cont->setProperty("primary", true); - blayout->addWidget(cont); - - QObject::connect(cont, &QPushButton::clicked, [=]() { - if (group->checkedButton() != openpilot) { - QTimer::singleShot(0, [=]() { - setCurrentWidget(custom_software_warning_widget); - }); - } else { - QTimer::singleShot(0, [=]() { - setCurrentWidget(downloading_widget); - }); - QTimer::singleShot(1000, this, [=]() { - download(OPENPILOT_URL); - }); - } - }); - - connect(group, QOverload::of(&QButtonGroup::buttonClicked), [=](QAbstractButton *btn) { - btn->setChecked(true); - cont->setEnabled(true); - }); - - return widget; -} - -QWidget * Setup::downloading() { - QWidget *widget = new QWidget(); - QVBoxLayout *main_layout = new QVBoxLayout(widget); - QLabel *txt = new QLabel(tr("Downloading...")); - txt->setStyleSheet("font-size: 90px; font-weight: 500;"); - main_layout->addWidget(txt, 0, Qt::AlignCenter); - return widget; -} - -QWidget * Setup::download_failed(QLabel *url, QLabel *body) { - QWidget *widget = new QWidget(); - QVBoxLayout *main_layout = new QVBoxLayout(widget); - main_layout->setContentsMargins(55, 185, 55, 55); - main_layout->setSpacing(0); - - QLabel *title = new QLabel(tr("Download Failed")); - title->setStyleSheet("font-size: 90px; font-weight: 500;"); - main_layout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); - - main_layout->addSpacing(67); - - url->setWordWrap(true); - url->setAlignment(Qt::AlignTop | Qt::AlignLeft); - url->setStyleSheet("font-family: \"JetBrains Mono\"; font-size: 64px; font-weight: 400; margin-right: 100px;"); - main_layout->addWidget(url); - - main_layout->addSpacing(48); - - body->setWordWrap(true); - body->setAlignment(Qt::AlignTop | Qt::AlignLeft); - body->setStyleSheet("font-size: 80px; font-weight: 300; margin-right: 100px;"); - main_layout->addWidget(body); - - main_layout->addStretch(); - - // reboot + start over buttons - QHBoxLayout *blayout = new QHBoxLayout(); - blayout->setSpacing(50); - main_layout->addLayout(blayout, 0); - - QPushButton *reboot = new QPushButton(tr("Reboot device")); - reboot->setObjectName("navBtn"); - blayout->addWidget(reboot); - QObject::connect(reboot, &QPushButton::clicked, this, [=]() { - Hardware::reboot(); - }); - - QPushButton *restart = new QPushButton(tr("Start over")); - restart->setObjectName("navBtn"); - restart->setProperty("primary", true); - blayout->addWidget(restart); - QObject::connect(restart, &QPushButton::clicked, this, [=]() { - setCurrentIndex(1); - }); - - widget->setStyleSheet(R"( - QLabel { - margin-left: 117; - } - )"); - return widget; -} - -void Setup::prevPage() { - setCurrentIndex(currentIndex() - 1); -} - -void Setup::nextPage() { - setCurrentIndex(currentIndex() + 1); -} - -Setup::Setup(QWidget *parent) : QStackedWidget(parent) { - if (std::getenv("MULTILANG")) { - selectLanguage(); - } - - std::stringstream buffer; - buffer << std::ifstream("/sys/class/hwmon/hwmon1/in1_input").rdbuf(); - float voltage = (float)std::atoi(buffer.str().c_str()) / 1000.; - if (voltage < 7) { - addWidget(low_voltage()); - } - - addWidget(getting_started()); - addWidget(network_setup()); - software_selection_widget = software_selection(); - addWidget(software_selection_widget); - custom_software_warning_widget = custom_software_warning(); - addWidget(custom_software_warning_widget); - downloading_widget = downloading(); - addWidget(downloading_widget); - - QLabel *url_label = new QLabel(); - QLabel *body_label = new QLabel(); - failed_widget = download_failed(url_label, body_label); - addWidget(failed_widget); - - QObject::connect(this, &Setup::finished, [=](const QString &url, const QString &error) { - qDebug() << "finished" << url << error; - if (error.isEmpty()) { - // hide setup on success - QTimer::singleShot(3000, this, &QWidget::hide); - } else { - url_label->setText(url); - body_label->setText(error); - setCurrentWidget(failed_widget); - } - }); - - // TODO: revisit pressed bg color - setStyleSheet(R"( - * { - color: white; - font-family: Inter; - } - Setup { - background-color: black; - } - QPushButton#navBtn { - height: 160; - font-size: 55px; - font-weight: 400; - border-radius: 10px; - background-color: #333333; - } - QPushButton#navBtn:disabled, QPushButton[primary='true']:disabled { - color: #808080; - background-color: #333333; - } - QPushButton#navBtn:pressed { - background-color: #444444; - } - QPushButton[primary='true'], #navBtn[primary='true'] { - background-color: #465BEA; - } - QPushButton[primary='true']:pressed, #navBtn:pressed[primary='true'] { - background-color: #3049F4; - } - )"); -} - -void Setup::selectLanguage() { - QMap langs = getSupportedLanguages(); - QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), "", this); - if (!selection.isEmpty()) { - QString selectedLang = langs[selection]; - Params().put("LanguageSetting", selectedLang.toStdString()); - if (translator.load(":/" + selectedLang)) { - qApp->installTranslator(&translator); - } - } -} - -int main(int argc, char *argv[]) { - QApplication a(argc, argv); - Setup setup; - setMainWindow(&setup); - return a.exec(); -} diff --git a/selfdrive/ui/qt/setup/setup.h b/selfdrive/ui/qt/setup/setup.h deleted file mode 100644 index 986956c902..0000000000 --- a/selfdrive/ui/qt/setup/setup.h +++ /dev/null @@ -1,38 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -class Setup : public QStackedWidget { - Q_OBJECT - -public: - explicit Setup(QWidget *parent = 0); - -private: - void selectLanguage(); - QWidget *low_voltage(); - QWidget *custom_software_warning(); - QWidget *getting_started(); - QWidget *network_setup(); - QWidget *software_selection(); - QWidget *downloading(); - QWidget *download_failed(QLabel *url, QLabel *body); - - QWidget *failed_widget; - QWidget *downloading_widget; - QWidget *custom_software_warning_widget; - QWidget *software_selection_widget; - QTranslator translator; - -signals: - void finished(const QString &url, const QString &error = ""); - -public slots: - void nextPage(); - void prevPage(); - void download(QString url); -}; diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index e3b83573da..e9c6a2f7c0 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -29,6 +29,7 @@ Sidebar::Sidebar(QWidget *parent) : QFrame(parent), onroad(false), flag_pressed( flag_img = loadPixmap("../assets/images/button_flag.png", home_btn.size()); settings_img = loadPixmap("../assets/images/button_settings.png", settings_btn.size(), Qt::IgnoreAspectRatio); mic_img = loadPixmap("../assets/icons/microphone.png", QSize(30, 30)); + link_img = loadPixmap("../assets/icons/link.png", QSize(60, 60)); connect(this, &Sidebar::valueChanged, [=] { update(); }); @@ -38,7 +39,7 @@ Sidebar::Sidebar(QWidget *parent) : QFrame(parent), onroad(false), flag_pressed( QObject::connect(uiState(), &UIState::uiUpdate, this, &Sidebar::updateState); - pm = std::make_unique(std::vector{"userFlag"}); + pm = std::make_unique(std::vector{"bookmarkButton"}); } void Sidebar::mousePressEvent(QMouseEvent *event) { @@ -61,8 +62,8 @@ void Sidebar::mouseReleaseEvent(QMouseEvent *event) { } if (onroad && home_btn.contains(event->pos())) { MessageBuilder msg; - msg.initEvent().initUserFlag(); - pm->send("userFlag", msg); + msg.initEvent().initBookmarkButton(); + pm->send("bookmarkButton", msg); } else if (settings_btn.contains(event->pos())) { emit openSettings(); } else if (recording_audio && mic_indicator_btn.contains(event->pos())) { @@ -150,7 +151,12 @@ void Sidebar::paintEvent(QPaintEvent *event) { p.setFont(InterFont(35)); p.setPen(QColor(0xff, 0xff, 0xff)); const QRect r = QRect(58, 247, width() - 100, 50); - p.drawText(r, Qt::AlignLeft | Qt::AlignVCenter, net_type); + + if (net_type == "Hotspot") { + p.drawPixmap(r.x(), r.y() + (r.height() - link_img.height()) / 2, link_img); + } else { + p.drawText(r, Qt::AlignLeft | Qt::AlignVCenter, net_type); + } // metrics drawMetric(p, temp_status.first, temp_status.second, 338); diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index f05a4ab201..6a2b7b6951 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -37,7 +37,7 @@ protected: void mouseReleaseEvent(QMouseEvent *event) override; void drawMetric(QPainter &p, const QPair &label, QColor c, int y); - QPixmap home_img, flag_img, settings_img, mic_img; + QPixmap home_img, flag_img, settings_img, mic_img, link_img; bool onroad, recording_audio, flag_pressed, settings_pressed, mic_indicator_pressed; const QMap network_type = { {cereal::DeviceState::NetworkType::NONE, tr("--")}, diff --git a/selfdrive/ui/tests/test_feedbackd.py b/selfdrive/ui/tests/test_feedbackd.py new file mode 100644 index 0000000000..6b7ec44863 --- /dev/null +++ b/selfdrive/ui/tests/test_feedbackd.py @@ -0,0 +1,53 @@ +import pytest +import cereal.messaging as messaging +from cereal import car +from openpilot.common.params import Params +from openpilot.system.manager.process_config import managed_processes + + +@pytest.mark.skip("tmp disabled") +class TestFeedbackd: + def setup_method(self): + self.pm = messaging.PubMaster(['carState', 'rawAudioData']) + self.sm = messaging.SubMaster(['audioFeedback']) + + def _send_lkas_button(self, pressed: bool): + msg = messaging.new_message('carState') + msg.carState.canValid = True + msg.carState.buttonEvents = [{'type': car.CarState.ButtonEvent.Type.lkas, 'pressed': pressed}] + self.pm.send('carState', msg) + + def _send_audio_data(self, count: int = 5): + for _ in range(count): + audio_msg = messaging.new_message('rawAudioData') + audio_msg.rawAudioData.data = bytes(1600) # 800 samples of int16 + audio_msg.rawAudioData.sampleRate = 16000 + self.pm.send('rawAudioData', audio_msg) + self.sm.update(timeout=100) + + @pytest.mark.parametrize("record_feedback", [False, True]) + def test_audio_feedback(self, record_feedback): + Params().put_bool("RecordAudioFeedback", record_feedback) + + managed_processes["feedbackd"].start() + assert self.pm.wait_for_readers_to_update('carState', timeout=5) + assert self.pm.wait_for_readers_to_update('rawAudioData', timeout=5) + + self._send_lkas_button(pressed=True) + self._send_audio_data() + self._send_lkas_button(pressed=False) + self._send_audio_data() + + if record_feedback: + assert self.sm.updated['audioFeedback'], "audioFeedback should be published when enabled" + else: + assert not self.sm.updated['audioFeedback'], "audioFeedback should not be published when disabled" + + self._send_lkas_button(pressed=True) + self._send_audio_data() + self._send_lkas_button(pressed=False) + self._send_audio_data() + + assert not self.sm.updated['audioFeedback'], "audioFeedback should not be published after second press" + + managed_processes["feedbackd"].stop() diff --git a/selfdrive/ui/tests/test_raylib_ui.py b/selfdrive/ui/tests/test_raylib_ui.py new file mode 100644 index 0000000000..3f23301972 --- /dev/null +++ b/selfdrive/ui/tests/test_raylib_ui.py @@ -0,0 +1,8 @@ +import time +from openpilot.selfdrive.test.helpers import with_processes + + +@with_processes(["raylib_ui"]) +def test_raylib_ui(): + """Test initialization of the UI widgets is successful.""" + time.sleep(1) diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index 7d3d9edd05..ff2e7ab05c 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -507,7 +507,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp تأخير التحديث - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. @@ -700,111 +700,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp خرطوم الحريق - - Setup - - WARNING: Low Voltage - تحذير: الجهد منخفض - - - Power your device in a car with a harness or proceed at your own risk. - شغل جهازك في السيارة عن طريق شرطان التوصيل، أو تابع على مسؤوليتك. - - - Power off - إيقاف التشغيل - - - Continue - متابعة - - - Getting Started - البدء - - - Before we get on the road, let’s finish installation and cover some details. - قبل أن ننطلق في الطريق، دعنا ننتهي من التثبيت ونغطي بعض التفاصيل. - - - Connect to Wi-Fi - الاتصال بشبكة الواي فاي - - - Back - السابق - - - Continue without Wi-Fi - المتابعة بدون شبكة الواي فاي - - - Waiting for internet - بانتظار الاتصال بالإنترنت - - - Enter URL - أدخل رابط URL - - - for Custom Software - للبرامج المخصصة - - - Downloading... - يتم الآن التنزيل... - - - Download Failed - فشل التنزيل - - - Ensure the entered URL is valid, and the device’s internet connection is good. - تأكد من أن رابط URL الذي أدخلته صالح، وأن اتصال الجهاز بالإنترنت جيد. - - - Reboot device - إعادة التشغيل - - - Start over - البدء من جديد - - - Something went wrong. Reboot the device. - حدث خطأ ما. أعد التشغيل الجهاز. - - - No custom software found at this URL. - لم يتم العثور على برنامج خاص لعنوان URL ها. - - - Select a language - اختر لغة - - - Choose Software to Install - اختر البرنامج للتثبيت - - - openpilot - openpilot - - - Custom Software - البرمجيات المخصصة - - - WARNING: Custom Software - - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - - - SetupWidget @@ -1157,6 +1052,16 @@ If you'd like to proceed, use https://flash.comma.ai to restore your device Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. + + Record Audio Feedback with LKAS button + + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + + WiFiPromptWidget diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index 3489b4860e..52fe55720d 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -499,7 +499,7 @@ Der Firehose-Modus ermöglicht es dir, deine Trainingsdaten-Uploads zu maximiere Update pausieren - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. @@ -680,111 +680,6 @@ Der Firehose-Modus ermöglicht es dir, deine Trainingsdaten-Uploads zu maximiere Firehose - - Setup - - WARNING: Low Voltage - Warnung: Batteriespannung niedrig - - - Power your device in a car with a harness or proceed at your own risk. - Versorge dein Gerät über einen Kabelbaum im Auto mit Strom, oder fahre auf eigene Gefahr fort. - - - Power off - Ausschalten - - - Continue - Fortsetzen - - - Getting Started - Loslegen - - - Before we get on the road, let’s finish installation and cover some details. - Bevor wir uns auf die Straße begeben, lass uns die Installation fertigstellen und einige Details prüfen. - - - Connect to Wi-Fi - Mit WLAN verbinden - - - Back - Zurück - - - Continue without Wi-Fi - Ohne WLAN fortsetzen - - - Waiting for internet - Auf Internet warten - - - Enter URL - URL eingeben - - - for Custom Software - für spezifische Software - - - Downloading... - Herunterladen... - - - Download Failed - Herunterladen fehlgeschlagen - - - Ensure the entered URL is valid, and the device’s internet connection is good. - Stelle sicher, dass die eingegebene URL korrekt ist und dein Gerät eine stabile Internetverbindung hat. - - - Reboot device - Gerät neustarten - - - Start over - Von neuem beginnen - - - No custom software found at this URL. - Keine benutzerdefinierte Software unter dieser URL gefunden. - - - Something went wrong. Reboot the device. - Etwas ist schiefgelaufen. Starte das Gerät neu. - - - Select a language - Sprache wählen - - - Choose Software to Install - Wähle die zu installierende Software - - - openpilot - openpilot - - - Custom Software - Benutzerdefinierte Software - - - WARNING: Custom Software - - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - - - SetupWidget @@ -1139,6 +1034,16 @@ If you'd like to proceed, use https://flash.comma.ai to restore your device Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. + + Record Audio Feedback with LKAS button + + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + + WiFiPromptWidget diff --git a/selfdrive/ui/translations/main_es.ts b/selfdrive/ui/translations/main_es.ts index 5807accb92..145eb7ae67 100644 --- a/selfdrive/ui/translations/main_es.ts +++ b/selfdrive/ui/translations/main_es.ts @@ -503,7 +503,7 @@ El Modo Firehose te permite maximizar las subidas de datos de entrenamiento para Posponer Actualización - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. @@ -684,113 +684,6 @@ El Modo Firehose te permite maximizar las subidas de datos de entrenamiento para Firehose - - Setup - - Something went wrong. Reboot the device. - Algo ha ido mal. Reinicie el dispositivo. - - - Ensure the entered URL is valid, and the device’s internet connection is good. - Asegúrese de que la URL insertada es válida y que el dispositivo tiene buena conexión. - - - No custom software found at this URL. - No encontramos software personalizado en esta URL. - - - WARNING: Low Voltage - ALERTA: Voltaje bajo - - - Power your device in a car with a harness or proceed at your own risk. - Encienda su dispositivo en un auto con el arnés o proceda bajo su propio riesgo. - - - Power off - Apagar - - - Continue - Continuar - - - Getting Started - Comenzando - - - Before we get on the road, let’s finish installation and cover some details. - Antes de ponernos en marcha, terminemos la instalación y cubramos algunos detalles. - - - Connect to Wi-Fi - Conectarse al Wi-Fi - - - Back - Volver - - - Continue without Wi-Fi - Continuar sin Wi-Fi - - - Waiting for internet - Esperando conexión a internet - - - Choose Software to Install - Elija el software a instalar - - - openpilot - openpilot - - - Custom Software - Software personalizado - - - Enter URL - Insertar URL - - - for Custom Software - para Software personalizado - - - Downloading... - Descargando... - - - Download Failed - Descarga fallida - - - Reboot device - Reiniciar Dispositivo - - - Start over - Comenzar de nuevo - - - Select a language - Seleccione un idioma - - - WARNING: Custom Software - ADVERTENCIA: Software personalizado - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - Tenga cuidado al instalar software de terceros. El software de terceros no ha sido probado por comma y puede causar daños a su dispositivo y/o vehículo. - -Si desea continuar, utilice https://flash.comma.ai para restaurar su dispositivo a un estado de fábrica más tarde. - - SetupWidget @@ -1143,6 +1036,16 @@ Si desea continuar, utilice https://flash.comma.ai para restaurar su dispositivo Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. Graba y almacena el audio del micrófono mientras conduces. El audio se incluirá en el video de la cámara del tablero en comma connect. + + Record Audio Feedback with LKAS button + + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + + WiFiPromptWidget diff --git a/selfdrive/ui/translations/main_fr.ts b/selfdrive/ui/translations/main_fr.ts index ba1eb93b30..297d936139 100644 --- a/selfdrive/ui/translations/main_fr.ts +++ b/selfdrive/ui/translations/main_fr.ts @@ -497,7 +497,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Reporter la mise à jour - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. @@ -678,111 +678,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp - - Setup - - Something went wrong. Reboot the device. - Un problème est survenu. Redémarrez l'appareil. - - - Ensure the entered URL is valid, and the device’s internet connection is good. - Assurez-vous que l'URL saisie est valide et que la connexion internet de l'appareil est bonne. - - - No custom software found at this URL. - Aucun logiciel personnalisé trouvé à cette URL. - - - WARNING: Low Voltage - ATTENTION : Tension faible - - - Power your device in a car with a harness or proceed at your own risk. - Alimentez votre appareil dans une voiture avec un harness ou continuez à vos risques et périls. - - - Power off - Éteindre - - - Continue - Continuer - - - Getting Started - Commencer - - - Before we get on the road, let’s finish installation and cover some details. - Avant de prendre la route, terminons l'installation et passons en revue quelques détails. - - - Connect to Wi-Fi - Se connecter au Wi-Fi - - - Back - Retour - - - Enter URL - Entrer l'URL - - - for Custom Software - pour logiciel personnalisé - - - Continue without Wi-Fi - Continuer sans Wi-Fi - - - Waiting for internet - En attente d'internet - - - Downloading... - Téléchargement... - - - Download Failed - Échec du téléchargement - - - Reboot device - Redémarrer l'appareil - - - Start over - Recommencer - - - Select a language - Choisir une langue - - - Choose Software to Install - Choisir le logiciel à installer - - - openpilot - openpilot - - - Custom Software - Logiciel personnalisé - - - WARNING: Custom Software - - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - - - SetupWidget @@ -1135,6 +1030,16 @@ If you'd like to proceed, use https://flash.comma.ai to restore your device Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. + + Record Audio Feedback with LKAS button + + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + + WiFiPromptWidget diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index fea6e51c07..7bb5c5364f 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -501,8 +501,8 @@ Firehoseモードを有効にすると学習データを最大限アップロー また後で更新する - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. - openpilotが過剰な%1の作動を検出しました。ソフトウェアの不具合の可能性があります。https://comma.ai/support からサポートへご連絡下さい。 + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. + @@ -679,113 +679,6 @@ Firehoseモードを有効にすると学習データを最大限アップロー データ学習 - - Setup - - WARNING: Low Voltage - 警告:電圧低下 - - - Power your device in a car with a harness or proceed at your own risk. - ハーネスを使って車でデバイスに電源を供給するか、自己責任でこのまま継続して下さい。 - - - Power off - 電源を切る - - - Continue - 続ける - - - Getting Started - はじめに - - - Before we get on the road, let’s finish installation and cover some details. - 出発する前に、インストールを完了させて少し詳細を確認しましょう。 - - - Connect to Wi-Fi - Wi-Fiに接続 - - - Back - 戻る - - - Continue without Wi-Fi - Wi-Fiに接続せずに続行 - - - Waiting for internet - インターネット接続を待機中 - - - Enter URL - URLの入力 - - - for Custom Software - カスタムソフトウェア - - - Downloading... - ダウンロード中... - - - Download Failed - ダウンロードに失敗しました - - - Ensure the entered URL is valid, and the device’s internet connection is good. - 入力されたURLが正しいかどうか、インターネットに正常に接続できているかを確認してください。 - - - Reboot device - デバイスを再起動 - - - Start over - やり直す - - - No custom software found at this URL. - このURLはカスタムソフトウェアではありません。 - - - Something went wrong. Reboot the device. - 何かの問題が発生しました。デバイスを再起動してください。 - - - Select a language - 言語を選択 - - - Choose Software to Install - インストールするソフトウェアを選択してください。 - - - openpilot - openpilot - - - Custom Software - カスタムソフトウェア - - - WARNING: Custom Software - 警告: カスタムソフトウェア - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - サードパーティ製ソフトウェアをインストールする際は注意してください。サードパーティ製ソフトウェアはcommaによってテストされておらず、あなたのデバイスや車両に損害を与える可能性があります。 - -続行したい場合は、後でデバイスを工場出荷時の状態に戻すために https://flash.comma.ai を使用してください。 - - SetupWidget @@ -1138,6 +1031,16 @@ If you'd like to proceed, use https://flash.comma.ai to restore your device Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. 運転中にマイク音声を録音・保存します。音声は comma connect のドライブレコーダー映像に含まれます。 + + Record Audio Feedback with LKAS button + + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + + WiFiPromptWidget diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index aaefdb92b0..807996f182 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -501,8 +501,8 @@ Firehose Mode allows you to maximize your training data uploads to improve openp 업데이트 일시 중지 - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. - 오픈파일럿은 과도한 %1 작동을 감지했습니다. 소프트웨어 버그 때문일 수 있습니다. https://comma.ai/support 에 문의하여 지원받으세요. + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. + @@ -679,113 +679,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp 파이어호스 - - Setup - - WARNING: Low Voltage - 경고: 전압이 낮습니다 - - - Power your device in a car with a harness or proceed at your own risk. - 장치를 하네스를 통해 차량 전원에 연결하세요. USB 전원에서는 예상치 못한 문제가 생길 수 있습니다. - - - Power off - 전원 끄기 - - - Continue - 계속 - - - Getting Started - 시작하기 - - - Before we get on the road, let’s finish installation and cover some details. - 출발 전 설정을 완료하고 세부 사항을 살펴봅니다. - - - Connect to Wi-Fi - Wi-Fi 연결 - - - Back - 뒤로 - - - Continue without Wi-Fi - Wi-Fi 연결 없이 진행 - - - Waiting for internet - 인터넷 연결 대기 중 - - - Enter URL - URL 입력 - - - for Custom Software - 커스텀 소프트웨어 - - - Downloading... - 다운로드 중... - - - Download Failed - 다운로드 실패 - - - Ensure the entered URL is valid, and the device’s internet connection is good. - 입력된 URL이 유효하고 인터넷 연결이 원활한지 확인하세요. - - - Reboot device - 장치 재부팅 - - - Start over - 다시 시작 - - - Something went wrong. Reboot the device. - 문제가 발생했습니다. 장치를 재부팅하세요. - - - No custom software found at this URL. - 이 URL에서 커스텀 소프트웨어를 찾을 수 없습니다. - - - Select a language - 언어를 선택하세요 - - - Choose Software to Install - 설치할 소프트웨어 선택 - - - openpilot - 오픈파일럿 - - - Custom Software - 커스텀 소프트웨어 - - - WARNING: Custom Software - 경고: 커스텀 소프트웨어 - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - 타사 소프트웨어를 설치할 때는 주의하십시오. 타사 소프트웨어는 comma에 의해 테스트되지 않았으며 장치나 차량에 손상을 줄 수 있습니다. - -진행하려면 https://flash.comma.ai를 사용하여 나중에 장치를 공장 초기화하세요. - - SetupWidget @@ -1138,6 +1031,16 @@ If you'd like to proceed, use https://flash.comma.ai to restore your device Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. 운전 중에 마이크 오디오를 녹음하고 저장하십시오. 오디오는 comma connect의 대시캠 비디오에 포함됩니다. + + Record Audio Feedback with LKAS button + + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + + WiFiPromptWidget diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 976fc711db..7f41588e8f 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -503,8 +503,8 @@ O Modo Firehose permite maximizar o envio de dados de treinamento para melhorar Adiar Atualização - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. - O openpilot detectou uma atuação excessiva de %1. Isso pode ser causado por uma falha no software. Por favor, entre em contato com o suporte em https://comma.ai/support. + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. + openpilot detectou atuação excessiva de %1 na sua última condução. Entre em contato com o suporte em https://comma.ai/support e compartilhe o Dongle ID do seu dispositivo para solução de problemas. @@ -684,113 +684,6 @@ O Modo Firehose permite maximizar o envio de dados de treinamento para melhorar Firehose - - Setup - - WARNING: Low Voltage - ALERTA: Baixa Voltagem - - - Power your device in a car with a harness or proceed at your own risk. - Ligue seu dispositivo em um carro com um chicote ou prossiga por sua conta e risco. - - - Power off - Desligar - - - Continue - Continuar - - - Getting Started - Começando - - - Before we get on the road, let’s finish installation and cover some details. - Antes de pegarmos a estrada, vamos terminar a instalação e cobrir alguns detalhes. - - - Connect to Wi-Fi - Conectar ao Wi-Fi - - - Back - Voltar - - - Continue without Wi-Fi - Continuar sem Wi-Fi - - - Waiting for internet - Esperando pela internet - - - Enter URL - Preencher URL - - - for Custom Software - para o Software Customizado - - - Downloading... - Baixando... - - - Download Failed - Download Falhou - - - Ensure the entered URL is valid, and the device’s internet connection is good. - Garanta que a URL inserida é valida, e uma boa conexão à internet. - - - Reboot device - Reiniciar Dispositivo - - - Start over - Inicializar - - - No custom software found at this URL. - Não há software personalizado nesta URL. - - - Something went wrong. Reboot the device. - Algo deu errado. Reinicie o dispositivo. - - - Select a language - Selecione o Idioma - - - Choose Software to Install - Escolha o Software a ser Instalado - - - openpilot - openpilot - - - Custom Software - Software Customizado - - - WARNING: Custom Software - AVISO: Software Personalizado - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - Tenha cuidado ao instalar software de terceiros. Softwares de terceiros não foram testados pela comma e podem causar danos ao seu dispositivo e/ou veículo. - -Se quiser continuar, use https://flash.comma.ai para restaurar seu dispositivo ao estado de fábrica mais tarde. - - SetupWidget @@ -1143,6 +1036,18 @@ Se quiser continuar, use https://flash.comma.ai para restaurar seu dispositivo a Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. Grave e armazene o áudio do microfone enquanto estiver dirigindo. O áudio será incluído ao vídeo dashcam no comma connect. + + Record Audio Feedback with LKAS button + Gravar feedback de áudio com o botão LKAS + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + Pressione o botão LKAS para gravar e compartilhar feedback de direção com a equipe do openpilot. Quando esta opção estiver desativada, o botão funcionará como um botão de marcador. O evento será destacado no comma connect e o segmento será preservado no armazenamento do seu dispositivo. + +Observe que este recurso é compatível apenas com alguns modelos de carros. + WiFiPromptWidget diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index 3821b3b806..34824c2680 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -497,7 +497,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp เลื่อนการอัปเดต - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. @@ -675,111 +675,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp สายยางดับเพลิง - - Setup - - WARNING: Low Voltage - คำเตือน: แรงดันแบตเตอรี่ต่ำ - - - Power your device in a car with a harness or proceed at your own risk. - โปรดต่ออุปกรณ์ของคุณเข้ากับสายควบคุมในรถยนต์ หรือดำเนินการด้วยความเสี่ยงของคุณเอง - - - Power off - ปิดเครื่อง - - - Continue - ดำเนินการต่อ - - - Getting Started - เริ่มกันเลย - - - Before we get on the road, let’s finish installation and cover some details. - ก่อนออกเดินทาง เรามาทำการติดตั้งซอฟต์แวร์ และตรวจสอบการตั้งค่า - - - Connect to Wi-Fi - เชื่อมต่อ Wi-Fi - - - Back - ย้อนกลับ - - - Continue without Wi-Fi - ดำเนินการต่อโดยไม่ใช้ Wi-Fi - - - Waiting for internet - กำลังรอสัญญาณอินเตอร์เน็ต - - - Enter URL - ป้อน URL - - - for Custom Software - สำหรับซอฟต์แวร์ที่กำหนดเอง - - - Downloading... - กำลังดาวน์โหลด... - - - Download Failed - ดาวน์โหลดล้มเหลว - - - Ensure the entered URL is valid, and the device’s internet connection is good. - ตรวจสอบให้แน่ใจว่า URL ที่ป้อนนั้นถูกต้อง และอุปกรณ์เชื่อมต่ออินเทอร์เน็ตอยู่ - - - Reboot device - รีบูตอุปกรณ์ - - - Start over - เริ่มต้นใหม่ - - - Something went wrong. Reboot the device. - มีบางอย่างผิดพลาด รีบูตอุปกรณ์ - - - No custom software found at this URL. - ไม่พบซอฟต์แวร์ที่กำหนดเองที่ URL นี้ - - - Select a language - เลือกภาษา - - - Choose Software to Install - เลือกซอฟต์แวร์ที่จะติดตั้ง - - - openpilot - openpilot - - - Custom Software - ซอฟต์แวร์ที่กำหนดเอง - - - WARNING: Custom Software - - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - - - SetupWidget @@ -1132,6 +1027,16 @@ If you'd like to proceed, use https://flash.comma.ai to restore your device Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. + + Record Audio Feedback with LKAS button + + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + + WiFiPromptWidget diff --git a/selfdrive/ui/translations/main_tr.ts b/selfdrive/ui/translations/main_tr.ts index 6cafb1dffc..db6c4283a8 100644 --- a/selfdrive/ui/translations/main_tr.ts +++ b/selfdrive/ui/translations/main_tr.ts @@ -494,7 +494,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Güncellemeyi sessize al - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. @@ -672,111 +672,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp - - Setup - - WARNING: Low Voltage - UYARI: Düşük voltaj - - - Power your device in a car with a harness or proceed at your own risk. - Cihazınızı emniyet kemeri olan bir arabada çalıştırın veya riski kabul ederek devam edin. - - - Power off - Sistemi kapat - - - Continue - Devam et - - - Getting Started - Başlarken - - - Before we get on the road, let’s finish installation and cover some details. - Yola çıkmadan önce kurulumu bitirin ve bazı detayları gözden geçirin.. - - - Connect to Wi-Fi - Wi-Fi ile bağlan - - - Back - Geri - - - Continue without Wi-Fi - Wi-Fi bağlantısı olmadan devam edin - - - Waiting for internet - İnternet bağlantısı bekleniyor. - - - Enter URL - URL girin - - - for Custom Software - özel yazılım için - - - Downloading... - İndiriliyor... - - - Download Failed - İndirme başarısız. - - - Ensure the entered URL is valid, and the device’s internet connection is good. - Girilen URL nin geçerli olduğundan ve cihazın internet bağlantısının olduğunu kontrol edin - - - Reboot device - Cihazı yeniden başlat - - - Start over - Zacznij od początku - - - Something went wrong. Reboot the device. - - - - No custom software found at this URL. - - - - Select a language - Dil seçin - - - Choose Software to Install - - - - openpilot - openpilot - - - Custom Software - - - - WARNING: Custom Software - - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - - - SetupWidget @@ -1129,6 +1024,16 @@ If you'd like to proceed, use https://flash.comma.ai to restore your device Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. + + Record Audio Feedback with LKAS button + + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + + WiFiPromptWidget diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 5e5b9da311..667d81ddd4 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -494,15 +494,15 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Acknowledge Excessive Actuation - + 确认过度作动 Snooze Update - 暂停更新 + 推迟更新 - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. - + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. + openpilot 在您上一次驾驶中,检测到过度的 %1 作动。请访问 https://comma.ai/support 联系客服,并提供您设备的 Dongle ID 以便进行故障排查。 @@ -679,113 +679,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Firehose - - Setup - - WARNING: Low Voltage - 警告:低电压 - - - Power your device in a car with a harness or proceed at your own risk. - 请使用car harness线束为您的设备供电,或自行承担风险。 - - - Power off - 关机 - - - Continue - 继续 - - - Getting Started - 开始设置 - - - Before we get on the road, let’s finish installation and cover some details. - 开始旅程之前,让我们完成安装并介绍一些细节。 - - - Connect to Wi-Fi - 连接到WiFi - - - Back - 返回 - - - Continue without Wi-Fi - 不连接WiFi并继续 - - - Waiting for internet - 等待网络连接 - - - Enter URL - 输入网址 - - - for Custom Software - 以下载自定义软件 - - - Downloading... - 正在下载…… - - - Download Failed - 下载失败 - - - Ensure the entered URL is valid, and the device’s internet connection is good. - 请确保互联网连接良好且输入的URL有效。 - - - Reboot device - 重启设备 - - - Start over - 重来 - - - No custom software found at this URL. - 在此网址找不到自定义软件。 - - - Something went wrong. Reboot the device. - 发生了一些错误。请重新启动您的设备。 - - - Select a language - 选择语言 - - - Choose Software to Install - 选择要安装的软件 - - - openpilot - openpilot - - - Custom Software - 定制软件 - - - WARNING: Custom Software - 警告:自定义软件 - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - 请谨慎安装第三方软件。第三方软件未经 comma 测试,可能会损害您的设备和车辆。 - -如果您决定继续,后续可通过 https://flash.comma.ai 将设备恢复到出厂状态。 - - SetupWidget @@ -1138,6 +1031,18 @@ If you'd like to proceed, use https://flash.comma.ai to restore your device Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. 在驾驶时录制并存储麦克风音频。该音频将会包含在 comma connect 的行车记录仪视频中。 + + Record Audio Feedback with LKAS button + 使用“车道保持”按钮录制音频反馈 + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + 按下“车道保持”按钮,即可录制并分享驾驶反馈给 openpilot 团队。当此开关禁用时,该按钮将用作书签按钮。该事件将在 comma connect 中高亮显示,且对应的视频片段将被保留在您的设备存储空间中。 + +请注意,此功能仅兼容部分车型。 + WiFiPromptWidget diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 630dbf2a08..a0f1997a00 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -494,15 +494,15 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Acknowledge Excessive Actuation - + 確認過度作動 Snooze Update - 暫停更新 + 延後更新 - openpilot has detected excessive %1 actuation. This may be due to a software bug. Please contact support at https://comma.ai/support. - + openpilot detected excessive %1 actuation on your last drive. Please contact support at https://comma.ai/support and share your device's Dongle ID for troubleshooting. + openpilot 在您上次的駕駛中,偵測到過度的 %1 作動。請至 https://comma.ai/support 聯絡客服,並提供您裝置的 Dongle ID 以進行故障排除。 @@ -679,113 +679,6 @@ Firehose Mode allows you to maximize your training data uploads to improve openp Firehose - - Setup - - WARNING: Low Voltage - 警告:電壓過低 - - - Power your device in a car with a harness or proceed at your own risk. - 請使用車上 harness 提供的電源,若繼續的話您需要自擔風險。 - - - Power off - 關機 - - - Continue - 繼續 - - - Getting Started - 入門 - - - Before we get on the road, let’s finish installation and cover some details. - 在我們上路之前,讓我們完成安裝並介紹一些細節。 - - - Connect to Wi-Fi - 連接到無線網路 - - - Back - 回上頁 - - - Continue without Wi-Fi - 在沒有 Wi-Fi 的情況下繼續 - - - Waiting for internet - 連接至網路中 - - - Enter URL - 輸入網址 - - - for Custom Software - 訂製的軟體 - - - Downloading... - 下載中… - - - Download Failed - 下載失敗 - - - Ensure the entered URL is valid, and the device’s internet connection is good. - 請確定您輸入的是有效的安裝網址,並且確定裝置的網路連線狀態良好。 - - - Reboot device - 重新啟動 - - - Start over - 重新開始 - - - No custom software found at this URL. - 在此網址找不到自訂軟體。 - - - Something went wrong. Reboot the device. - 發生了一些錯誤。請重新啟動您的裝置。 - - - Select a language - 選擇語言 - - - Choose Software to Install - 選擇要安裝的軟體 - - - openpilot - openpilot - - - Custom Software - 自訂軟體 - - - WARNING: Custom Software - 警告:自訂軟體 - - - Use caution when installing third-party software. Third-party software has not been tested by comma, and may cause damage to your device and/or vehicle. - -If you'd like to proceed, use https://flash.comma.ai to restore your device to a factory state later. - 請謹慎安裝第三方軟體。第三方軟體未經 comma 測試,可能會損壞您的裝置及車輛。 - -若您仍要繼續,日後可使用 https://flash.comma.ai 將您的裝置恢復至出廠狀態。 - - SetupWidget @@ -1138,6 +1031,18 @@ If you'd like to proceed, use https://flash.comma.ai to restore your device Record and store microphone audio while driving. The audio will be included in the dashcam video in comma connect. 在駕駛時錄製並儲存麥克風音訊。此音訊將會收錄在 comma connect 的行車記錄器影片中。 + + Record Audio Feedback with LKAS button + 使用「車道維持」按鈕錄製音訊回饋 + + + Press the LKAS button to record and share driving feedback with the openpilot team. When this toggle is disabled, the button acts as a bookmark button. The event will be highlighted in comma connect and the segment will be preserved on your device's storage. + +Note that this feature is only compatible with select cars. + 按下「車道維持」按鈕,即可錄製並分享駕駛回饋給 openpilot 團隊。當此開關停用時,該按鈕的功能將轉為書籤按鈕。該事件將會在 comma connect 中被標註,且對應的路段影像將保留在您的裝置儲存空間中。 + +請注意,此功能僅與特定車款相容。 + WiFiPromptWidget diff --git a/selfdrive/ui/watch3.cc b/selfdrive/ui/watch3.cc deleted file mode 100644 index 258e2a7bd6..0000000000 --- a/selfdrive/ui/watch3.cc +++ /dev/null @@ -1,33 +0,0 @@ -#include -#include - -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/cameraview.h" - -int main(int argc, char *argv[]) { - initApp(argc, argv); - - QApplication a(argc, argv); - QWidget w; - setMainWindow(&w); - - QVBoxLayout *layout = new QVBoxLayout(&w); - layout->setMargin(0); - layout->setSpacing(0); - - { - QHBoxLayout *hlayout = new QHBoxLayout(); - layout->addLayout(hlayout); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_ROAD)); - } - - { - QHBoxLayout *hlayout = new QHBoxLayout(); - layout->addLayout(hlayout); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_DRIVER)); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_WIDE_ROAD)); - } - - return a.exec(); -} diff --git a/selfdrive/ui/watch3.py b/selfdrive/ui/watch3.py new file mode 100755 index 0000000000..bb64cdc4d5 --- /dev/null +++ b/selfdrive/ui/watch3.py @@ -0,0 +1,17 @@ +#!/usr/bin/env python3 +import pyray as rl + +from msgq.visionipc import VisionStreamType +from openpilot.system.ui.lib.application import gui_app +from openpilot.selfdrive.ui.onroad.cameraview import CameraView + + +if __name__ == "__main__": + gui_app.init_window("watch3") + road = CameraView("camerad", VisionStreamType.VISION_STREAM_ROAD) + driver = CameraView("camerad", VisionStreamType.VISION_STREAM_DRIVER) + wide = CameraView("camerad", VisionStreamType.VISION_STREAM_WIDE_ROAD) + for _ in gui_app.render(): + road.render(rl.Rectangle(gui_app.width // 4, 0, gui_app.width // 2, gui_app.height // 2)) + driver.render(rl.Rectangle(0, gui_app.height // 2, gui_app.width // 2, gui_app.height // 2)) + wide.render(rl.Rectangle(gui_app.width // 2, gui_app.height // 2, gui_app.width // 2, gui_app.height // 2)) diff --git a/selfdrive/ui/widgets/exp_mode_button.py b/selfdrive/ui/widgets/exp_mode_button.py index be50c59d06..9618768957 100644 --- a/selfdrive/ui/widgets/exp_mode_button.py +++ b/selfdrive/ui/widgets/exp_mode_button.py @@ -14,7 +14,6 @@ class ExperimentalModeButton(Widget): self.params = Params() self.experimental_mode = self.params.get_bool("ExperimentalMode") - self.is_pressed = False self.chill_pixmap = gui_app.texture("icons/couch.png", self.img_width, self.img_width) self.experimental_pixmap = gui_app.texture("icons/experimental_grey.png", self.img_width, self.img_width) @@ -32,20 +31,13 @@ class ExperimentalModeButton(Widget): rl.draw_rectangle_gradient_h(int(rect.x), int(rect.y), int(rect.width), int(rect.height), start_color, end_color) - def _handle_interaction(self, rect): - mouse_pos = rl.get_mouse_position() - mouse_in_rect = rl.check_collision_point_rec(mouse_pos, rect) - - self.is_pressed = mouse_in_rect and rl.is_mouse_button_down(rl.MOUSE_BUTTON_LEFT) - return mouse_in_rect and rl.is_mouse_button_released(rl.MOUSE_BUTTON_LEFT) + def _handle_mouse_release(self, mouse_pos): + self.experimental_mode = not self.experimental_mode + # TODO: Opening settings for ExperimentalMode + self.params.put_bool("ExperimentalMode", self.experimental_mode) def _render(self, rect): - if self._handle_interaction(rect): - self.experimental_mode = not self.experimental_mode - # TODO: Opening settings for ExperimentalMode - self.params.put_bool("ExperimentalMode", self.experimental_mode) - - rl.draw_rectangle_rounded(rect, 0.08, 20, rl.Color(255, 255, 255, 255)) + rl.draw_rectangle_rounded(rect, 0.08, 20, rl.WHITE) rl.begin_scissor_mode(int(rect.x), int(rect.y), int(rect.width), int(rect.height)) self._draw_gradient_background(rect) @@ -61,7 +53,7 @@ class ExperimentalModeButton(Widget): text_x = rect.x + self.horizontal_padding text_y = rect.y + rect.height / 2 - 45 // 2 # Center vertically - rl.draw_text_ex(gui_app.font(FontWeight.NORMAL), text, rl.Vector2(int(text_x), int(text_y)), 45, 0, rl.Color(0, 0, 0, 255)) + rl.draw_text_ex(gui_app.font(FontWeight.NORMAL), text, rl.Vector2(int(text_x), int(text_y)), 45, 0, rl.BLACK) # Draw icon (right aligned) icon_x = rect.x + rect.width - self.horizontal_padding - self.img_width @@ -71,4 +63,4 @@ class ExperimentalModeButton(Widget): # Draw current mode icon current_icon = self.experimental_pixmap if self.experimental_mode else self.chill_pixmap source_rect = rl.Rectangle(0, 0, current_icon.width, current_icon.height) - rl.draw_texture_pro(current_icon, source_rect, icon_rect, rl.Vector2(0, 0), 0, rl.Color(255, 255, 255, 255)) + rl.draw_texture_pro(current_icon, source_rect, icon_rect, rl.Vector2(0, 0), 0, rl.WHITE) diff --git a/selfdrive/ui/widgets/prime.py b/selfdrive/ui/widgets/prime.py index 86234ee149..6b601f6dff 100644 --- a/selfdrive/ui/widgets/prime.py +++ b/selfdrive/ui/widgets/prime.py @@ -36,7 +36,7 @@ class PrimeWidget(Widget): font = gui_app.font(FontWeight.LIGHT) wrapped_text = "\n".join(wrap_text(font, "Become a comma prime member at connect.comma.ai", 56, int(w))) text_size = measure_text_cached(font, wrapped_text, 56) - rl.draw_text_ex(font, wrapped_text, rl.Vector2(x, desc_y), 56, 0, rl.Color(255, 255, 255, 255)) + rl.draw_text_ex(font, wrapped_text, rl.Vector2(x, desc_y), 56, 0, rl.WHITE) # Features section features_y = desc_y + text_size.y + 50 diff --git a/system/camerad/sensors/ar0231_cl.h b/system/camerad/sensors/ar0231_cl.h deleted file mode 100644 index c79242543b..0000000000 --- a/system/camerad/sensors/ar0231_cl.h +++ /dev/null @@ -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 diff --git a/system/camerad/sensors/os04c10_cl.h b/system/camerad/sensors/os04c10_cl.h deleted file mode 100644 index 3b5cf88839..0000000000 --- a/system/camerad/sensors/os04c10_cl.h +++ /dev/null @@ -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 diff --git a/system/camerad/sensors/ox03c10_cl.h b/system/camerad/sensors/ox03c10_cl.h deleted file mode 100644 index c8cec7cf8a..0000000000 --- a/system/camerad/sensors/ox03c10_cl.h +++ /dev/null @@ -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 diff --git a/system/hardware/fan_controller.py b/system/hardware/fan_controller.py index 7d5bec0509..4c7adc0a3e 100755 --- a/system/hardware/fan_controller.py +++ b/system/hardware/fan_controller.py @@ -21,16 +21,16 @@ class TiciFanController(BaseFanController): self.controller = PIDController(k_p=0, k_i=4e-3, k_f=1, rate=(1 / DT_HW)) def update(self, cur_temp: float, ignition: bool) -> int: - self.controller.neg_limit = -(100 if ignition else 30) - self.controller.pos_limit = -(30 if ignition else 0) + self.controller.pos_limit = 100 if ignition else 30 + self.controller.neg_limit = 30 if ignition else 0 if ignition != self.last_ignition: self.controller.reset() - error = 75 - cur_temp - fan_pwr_out = -int(self.controller.update( + error = cur_temp - 75 + fan_pwr_out = int(self.controller.update( error=error, - feedforward=np.interp(cur_temp, [60.0, 100.0], [0, -100]) + feedforward=np.interp(cur_temp, [60.0, 100.0], [0, 100]) )) self.last_ignition = ignition diff --git a/system/hardware/tici/agnos.json b/system/hardware/tici/agnos.json index ec2557422c..941a4956bf 100644 --- a/system/hardware/tici/agnos.json +++ b/system/hardware/tici/agnos.json @@ -1,25 +1,25 @@ [ { "name": "xbl", - "url": "https://commadist.azureedge.net/agnosupdate/xbl-6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1.img.xz", - "hash": "6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1", - "hash_raw": "6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1", + "url": "https://commadist.azureedge.net/agnosupdate/xbl-effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b.img.xz", + "hash": "effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b", + "hash_raw": "effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b", "size": 3282256, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "003a17ab1be68a696f7efe4c9938e8be511d4aacfc2f3211fc896bdc1681d089" + "ondevice_hash": "ed61a650bea0c56652dd0fc68465d8fc722a4e6489dc8f257630c42c6adcdc89" }, { "name": "xbl_config", - "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535.img.xz", - "hash": "63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535", - "hash_raw": "63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535", + "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c.img.xz", + "hash": "63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c", + "hash_raw": "63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c", "size": 98124, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "2a855dd636cc94718b64bea83a44d0a31741ecaa8f72a63613ff348ec7404091" + "ondevice_hash": "b12801ffaa81e58e3cef914488d3b447e35483ba549b28c6cd9deb4814c3265f" }, { "name": "abl", @@ -56,28 +56,28 @@ }, { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-4de8f892dbac3fa3fee1efe68ca76e23e75812e81a6577d00d52e2da1ef624ef.img.xz", - "hash": "4de8f892dbac3fa3fee1efe68ca76e23e75812e81a6577d00d52e2da1ef624ef", - "hash_raw": "4de8f892dbac3fa3fee1efe68ca76e23e75812e81a6577d00d52e2da1ef624ef", - "size": 18479104, + "url": "https://commadist.azureedge.net/agnosupdate/boot-0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4.img.xz", + "hash": "0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4", + "hash_raw": "0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4", + "size": 18515968, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "8d7094d774faa4e801e36b403a31b53b913b31d086f4dc682d2f64710c557e8a" + "ondevice_hash": "492ae27f569e8db457c79d0e358a7a6297d1a1c685c2b1ae6deba7315d3a6cb0" }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-4bc3951f4aa3f70c53837dc2542d8b0666d37103b353fd81417cc7de1bbebe39.img.xz", - "hash": "cccd7073d067027396f2afd49874729757db0bbbc79853a0bf2938bd356fe164", - "hash_raw": "4bc3951f4aa3f70c53837dc2542d8b0666d37103b353fd81417cc7de1bbebe39", + "url": "https://commadist.azureedge.net/agnosupdate/system-e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087.img.xz", + "hash": "1468d50b7ad0fda0f04074755d21e786e3b1b6ca5dd5b17eb2608202025e6126", + "hash_raw": "e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087", "size": 5368709120, "sparse": true, "full_check": false, "has_ab": true, - "ondevice_hash": "c7707f16ce7d977748677cc354e250943b4ff6c21b9a19a492053d32397cf9ec", + "ondevice_hash": "242aa5adad1c04e1398e00e2440d1babf962022eb12b89adf2e60ee3068946e7", "alt": { - "hash": "4bc3951f4aa3f70c53837dc2542d8b0666d37103b353fd81417cc7de1bbebe39", - "url": "https://commadist.azureedge.net/agnosupdate/system-4bc3951f4aa3f70c53837dc2542d8b0666d37103b353fd81417cc7de1bbebe39.img", + "hash": "e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087", + "url": "https://commadist.azureedge.net/agnosupdate/system-e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087.img", "size": 5368709120 } } diff --git a/system/hardware/tici/all-partitions.json b/system/hardware/tici/all-partitions.json index d28b48128b..5891e2748a 100644 --- a/system/hardware/tici/all-partitions.json +++ b/system/hardware/tici/all-partitions.json @@ -97,14 +97,14 @@ }, { "name": "persist", - "url": "https://commadist.azureedge.net/agnosupdate/persist-9814b07851292f510f3794b767489f38ab379a99f0ea75dc620ad2d3a496d54d.img.xz", - "hash": "9814b07851292f510f3794b767489f38ab379a99f0ea75dc620ad2d3a496d54d", - "hash_raw": "9814b07851292f510f3794b767489f38ab379a99f0ea75dc620ad2d3a496d54d", - "size": 33554432, + "url": "https://commadist.azureedge.net/agnosupdate/persist-d6af4ec18df180c7417353b52a9e05e43a6480b29425f087874136436cefe786.img.xz", + "hash": "d6af4ec18df180c7417353b52a9e05e43a6480b29425f087874136436cefe786", + "hash_raw": "d6af4ec18df180c7417353b52a9e05e43a6480b29425f087874136436cefe786", + "size": 4096, "sparse": false, "full_check": true, "has_ab": false, - "ondevice_hash": "9814b07851292f510f3794b767489f38ab379a99f0ea75dc620ad2d3a496d54d" + "ondevice_hash": "d6af4ec18df180c7417353b52a9e05e43a6480b29425f087874136436cefe786" }, { "name": "systemrw", @@ -130,25 +130,25 @@ }, { "name": "xbl", - "url": "https://commadist.azureedge.net/agnosupdate/xbl-6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1.img.xz", - "hash": "6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1", - "hash_raw": "6710967ca9701f205d7ab19c3a9b0dd2f547e65b3d96048b7c2b03755aafa0f1", + "url": "https://commadist.azureedge.net/agnosupdate/xbl-effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b.img.xz", + "hash": "effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b", + "hash_raw": "effa23294138e2297b85a5b482a885184c437b5ab25d74f2a62d4fce4e68f63b", "size": 3282256, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "003a17ab1be68a696f7efe4c9938e8be511d4aacfc2f3211fc896bdc1681d089" + "ondevice_hash": "ed61a650bea0c56652dd0fc68465d8fc722a4e6489dc8f257630c42c6adcdc89" }, { "name": "xbl_config", - "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535.img.xz", - "hash": "63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535", - "hash_raw": "63922cfbfdf4ab87986c4ba8f3a4df5bf28414b3f71a29ec5947336722215535", + "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c.img.xz", + "hash": "63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c", + "hash_raw": "63d019efed684601f145ef37628e62c8da73f5053a8e51d7de09e72b8b11f97c", "size": 98124, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "2a855dd636cc94718b64bea83a44d0a31741ecaa8f72a63613ff348ec7404091" + "ondevice_hash": "b12801ffaa81e58e3cef914488d3b447e35483ba549b28c6cd9deb4814c3265f" }, { "name": "abl", @@ -339,62 +339,62 @@ }, { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-4de8f892dbac3fa3fee1efe68ca76e23e75812e81a6577d00d52e2da1ef624ef.img.xz", - "hash": "4de8f892dbac3fa3fee1efe68ca76e23e75812e81a6577d00d52e2da1ef624ef", - "hash_raw": "4de8f892dbac3fa3fee1efe68ca76e23e75812e81a6577d00d52e2da1ef624ef", - "size": 18479104, + "url": "https://commadist.azureedge.net/agnosupdate/boot-0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4.img.xz", + "hash": "0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4", + "hash_raw": "0191529aa97d90d1fa04b472d80230b777606459e1e1e9e2323c9519839827b4", + "size": 18515968, "sparse": false, "full_check": true, "has_ab": true, - "ondevice_hash": "8d7094d774faa4e801e36b403a31b53b913b31d086f4dc682d2f64710c557e8a" + "ondevice_hash": "492ae27f569e8db457c79d0e358a7a6297d1a1c685c2b1ae6deba7315d3a6cb0" }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-4bc3951f4aa3f70c53837dc2542d8b0666d37103b353fd81417cc7de1bbebe39.img.xz", - "hash": "cccd7073d067027396f2afd49874729757db0bbbc79853a0bf2938bd356fe164", - "hash_raw": "4bc3951f4aa3f70c53837dc2542d8b0666d37103b353fd81417cc7de1bbebe39", + "url": "https://commadist.azureedge.net/agnosupdate/system-e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087.img.xz", + "hash": "1468d50b7ad0fda0f04074755d21e786e3b1b6ca5dd5b17eb2608202025e6126", + "hash_raw": "e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087", "size": 5368709120, "sparse": true, "full_check": false, "has_ab": true, - "ondevice_hash": "c7707f16ce7d977748677cc354e250943b4ff6c21b9a19a492053d32397cf9ec", + "ondevice_hash": "242aa5adad1c04e1398e00e2440d1babf962022eb12b89adf2e60ee3068946e7", "alt": { - "hash": "4bc3951f4aa3f70c53837dc2542d8b0666d37103b353fd81417cc7de1bbebe39", - "url": "https://commadist.azureedge.net/agnosupdate/system-4bc3951f4aa3f70c53837dc2542d8b0666d37103b353fd81417cc7de1bbebe39.img", + "hash": "e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087", + "url": "https://commadist.azureedge.net/agnosupdate/system-e0007afa5d1026671c1943d44bb7f7ad26259f673392dd00a03073a2870df087.img", "size": 5368709120 } }, { "name": "userdata_90", - "url": "https://commadist.azureedge.net/agnosupdate/userdata_90-f0c675e0fae420870c9ba8979fa246b170f4f1a7a04b49609b55b6bdfa8c1b21.img.xz", - "hash": "3d8a007bae088c5959eb9b82454013f91868946d78380fecea2b1afdfb575c02", - "hash_raw": "f0c675e0fae420870c9ba8979fa246b170f4f1a7a04b49609b55b6bdfa8c1b21", + "url": "https://commadist.azureedge.net/agnosupdate/userdata_90-602d5103cba97e1b07f76508d5febb47cfc4463a7e31bd20e461b55c801feb0a.img.xz", + "hash": "6a11d448bac50467791809339051eed2894aae971c37bf6284b3b972a99ba3ac", + "hash_raw": "602d5103cba97e1b07f76508d5febb47cfc4463a7e31bd20e461b55c801feb0a", "size": 96636764160, "sparse": true, "full_check": true, "has_ab": false, - "ondevice_hash": "5bfbabb8ff96b149056aa75d5b7e66a7cdd9cb4bcefe23b922c292f7f3a43462" + "ondevice_hash": "e014d92940a696bf8582807259820ab73948b950656ed83a45da738f26083705" }, { "name": "userdata_89", - "url": "https://commadist.azureedge.net/agnosupdate/userdata_89-06fc52be37b42690ed7b4f8c66c4611309a2dea9fca37dd9d27d1eff302eb1bf.img.xz", - "hash": "443f136484294b210318842d09fb618d5411c8bdbab9f7421d8c89eb291a8d3f", - "hash_raw": "06fc52be37b42690ed7b4f8c66c4611309a2dea9fca37dd9d27d1eff302eb1bf", + "url": "https://commadist.azureedge.net/agnosupdate/userdata_89-4d7f6d12a5557eb6e3cbff9a4cd595677456fdfddcc879eddcea96a43a9d8b48.img.xz", + "hash": "748e31a5fc01fc256c012e359c3382d1f98cce98feafe8ecc0fca3e47caef116", + "hash_raw": "4d7f6d12a5557eb6e3cbff9a4cd595677456fdfddcc879eddcea96a43a9d8b48", "size": 95563022336, "sparse": true, "full_check": true, "has_ab": false, - "ondevice_hash": "67db02b29a7e4435951c64cc962a474d048ed444aa912f3494391417cd51a074" + "ondevice_hash": "c181b93050787adcfef730c086bcb780f28508d84e6376d9b80d37e5dc02b55e" }, { "name": "userdata_30", - "url": "https://commadist.azureedge.net/agnosupdate/userdata_30-06679488f0c5c3fcfd5f351133050751cd189f705e478a979c45fc4a166d18a6.img.xz", - "hash": "875b580cb786f290a842e9187fd945657561886123eb3075a26f7995a18068f6", - "hash_raw": "06679488f0c5c3fcfd5f351133050751cd189f705e478a979c45fc4a166d18a6", + "url": "https://commadist.azureedge.net/agnosupdate/userdata_30-80a76c8e56bbd7536fd5e87e8daa12984e2960db4edeb1f83229b2baeecc4668.img.xz", + "hash": "09ff390e639e4373d772e1688d05a5ac77a573463ed1deeff86390686fa686f9", + "hash_raw": "80a76c8e56bbd7536fd5e87e8daa12984e2960db4edeb1f83229b2baeecc4668", "size": 32212254720, "sparse": true, "full_check": true, "has_ab": false, - "ondevice_hash": "16e27ba3c5cf9f0394ce6235ba6021b8a2de293fdb08399f8ca832fa5e4d0b9d" + "ondevice_hash": "2c01ab470c02121c721ff6afc25582437e821686207f3afef659387afb69c507" } ] \ No newline at end of file diff --git a/system/loggerd/encoder/encoder.cc b/system/loggerd/encoder/encoder.cc index b8f2f274d2..06922b0cd0 100644 --- a/system/loggerd/encoder/encoder.cc +++ b/system/loggerd/encoder/encoder.cc @@ -21,7 +21,7 @@ void VideoEncoder::publisher_publish(int segment_num, uint32_t idx, VisionIpcBuf edata.setFrameId(extra.frame_id); edata.setTimestampSof(extra.timestamp_sof); edata.setTimestampEof(extra.timestamp_eof); - edata.setType(encoder_info.encode_type); + edata.setType(encoder_info.get_settings(in_width).encode_type); edata.setEncodeId(cnt++); edata.setSegmentNum(segment_num); edata.setSegmentId(idx); diff --git a/system/loggerd/encoder/ffmpeg_encoder.cc b/system/loggerd/encoder/ffmpeg_encoder.cc index 091c2fb2dd..4d6be47182 100644 --- a/system/loggerd/encoder/ffmpeg_encoder.cc +++ b/system/loggerd/encoder/ffmpeg_encoder.cc @@ -46,7 +46,7 @@ FfmpegEncoder::~FfmpegEncoder() { } void FfmpegEncoder::encoder_open() { - auto codec_id = encoder_info.encode_type == cereal::EncodeIndex::Type::QCAMERA_H264 + auto codec_id = encoder_info.get_settings(in_width).encode_type == cereal::EncodeIndex::Type::QCAMERA_H264 ? AV_CODEC_ID_H264 : AV_CODEC_ID_FFVHUFF; const AVCodec *codec = avcodec_find_encoder(codec_id); diff --git a/system/loggerd/encoder/v4l_encoder.cc b/system/loggerd/encoder/v4l_encoder.cc index e4b4c8a093..6ee3af13b0 100644 --- a/system/loggerd/encoder/v4l_encoder.cc +++ b/system/loggerd/encoder/v4l_encoder.cc @@ -155,6 +155,9 @@ V4LEncoder::V4LEncoder(const EncoderInfo &encoder_info, int in_width, int in_hei assert(strcmp((const char *)cap.driver, "msm_vidc_driver") == 0); assert(strcmp((const char *)cap.card, "msm_vidc_venc") == 0); + EncoderSettings encoder_settings = encoder_info.get_settings(in_width); + bool is_h265 = encoder_settings.encode_type == cereal::EncodeIndex::Type::FULL_H_E_V_C; + struct v4l2_format fmt_out = { .type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, .fmt = { @@ -162,7 +165,7 @@ V4LEncoder::V4LEncoder(const EncoderInfo &encoder_info, int in_width, int in_hei // downscales are free with v4l .width = (unsigned int)(out_width), .height = (unsigned int)(out_height), - .pixelformat = (encoder_info.encode_type == cereal::EncodeIndex::Type::FULL_H_E_V_C) ? V4L2_PIX_FMT_HEVC : V4L2_PIX_FMT_H264, + .pixelformat = is_h265 ? V4L2_PIX_FMT_HEVC : V4L2_PIX_FMT_H264, .field = V4L2_FIELD_ANY, .colorspace = V4L2_COLORSPACE_DEFAULT, } @@ -205,8 +208,10 @@ V4LEncoder::V4LEncoder(const EncoderInfo &encoder_info, int in_width, int in_hei // shared ctrls { struct v4l2_control ctrls[] = { + { .id = V4L2_CID_MPEG_VIDEO_BITRATE, .value = encoder_settings.bitrate}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = encoder_settings.gop_size - encoder_settings.b_frames - 1}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = encoder_settings.b_frames}, { .id = V4L2_CID_MPEG_VIDEO_HEADER_MODE, .value = V4L2_MPEG_VIDEO_HEADER_MODE_SEPARATE}, - { .id = V4L2_CID_MPEG_VIDEO_BITRATE, .value = encoder_info.bitrate}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL, .value = V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_CFR}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_PRIORITY, .value = V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_DISABLE}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_IDR_PERIOD, .value = 1}, @@ -216,13 +221,11 @@ V4LEncoder::V4LEncoder(const EncoderInfo &encoder_info, int in_width, int in_hei } } - if (encoder_info.encode_type == cereal::EncodeIndex::Type::FULL_H_E_V_C) { + if (is_h265) { struct v4l2_control ctrls[] = { { .id = V4L2_CID_MPEG_VIDC_VIDEO_HEVC_PROFILE, .value = V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_HEVC_TIER_LEVEL, .value = V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_VUI_TIMING_INFO, .value = V4L2_MPEG_VIDC_VIDEO_VUI_TIMING_INFO_ENABLED}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 29}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = 0}, }; for (auto ctrl : ctrls) { util::safe_ioctl(fd, VIDIOC_S_CTRL, &ctrl, "VIDIOC_S_CTRL failed"); @@ -231,8 +234,6 @@ V4LEncoder::V4LEncoder(const EncoderInfo &encoder_info, int in_width, int in_hei struct v4l2_control ctrls[] = { { .id = V4L2_CID_MPEG_VIDEO_H264_PROFILE, .value = V4L2_MPEG_VIDEO_H264_PROFILE_HIGH}, { .id = V4L2_CID_MPEG_VIDEO_H264_LEVEL, .value = V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 14}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = 0}, { .id = V4L2_CID_MPEG_VIDEO_H264_ENTROPY_MODE, .value = V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CABAC}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL, .value = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_0}, { .id = V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_MODE, .value = 0}, diff --git a/system/loggerd/loggerd.cc b/system/loggerd/loggerd.cc index 144ab9f349..21de1ff33f 100644 --- a/system/loggerd/loggerd.cc +++ b/system/loggerd/loggerd.cc @@ -194,7 +194,7 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct return bytes_count; } -void handle_user_flag(LoggerdState *s) { +void handle_preserve_segment(LoggerdState *s) { static int prev_segment = -1; if (s->logger.segment() == prev_segment) return; @@ -222,7 +222,7 @@ void loggerd_thread() { typedef struct ServiceState { std::string name; int counter, freq; - bool encoder, user_flag, record_audio; + bool encoder, preserve_segment, record_audio; } ServiceState; std::unordered_map service_state; std::unordered_map remote_encoders; @@ -246,7 +246,7 @@ void loggerd_thread() { .counter = 0, .freq = it.decimation, .encoder = encoder, - .user_flag = it.name == "userFlag", + .preserve_segment = (it.name == "userBookmark") || (it.name == "audioFeedback"), .record_audio = record_audio, }; } @@ -281,8 +281,8 @@ void loggerd_thread() { if (do_exit) break; ServiceState &service = service_state[sock]; - if (service.user_flag) { - handle_user_flag(&s); + if (service.preserve_segment) { + handle_preserve_segment(&s); } // drain socket diff --git a/system/loggerd/loggerd.h b/system/loggerd/loggerd.h index 5dfb178fd5..967caec867 100644 --- a/system/loggerd/loggerd.h +++ b/system/loggerd/loggerd.h @@ -13,10 +13,7 @@ #include "system/loggerd/logger.h" constexpr int MAIN_FPS = 20; -const int MAIN_BITRATE = 1e7; -const int LIVESTREAM_BITRATE = 1e6; -const int QCAM_BITRATE = 256000; - +const auto MAIN_ENCODE_TYPE = Hardware::PC() ? cereal::EncodeIndex::Type::BIG_BOX_LOSSLESS : cereal::EncodeIndex::Type::FULL_H_E_V_C; #define NO_CAMERA_PATIENCE 500 // fall back to time-based rotation if all cameras are dead #define INIT_ENCODE_FUNCTIONS(encode_type) \ @@ -29,6 +26,30 @@ const int SEGMENT_LENGTH = LOGGERD_TEST ? atoi(getenv("LOGGERD_SEGMENT_LENGTH")) constexpr char PRESERVE_ATTR_NAME[] = "user.preserve"; constexpr char PRESERVE_ATTR_VALUE = '1'; + +struct EncoderSettings { + cereal::EncodeIndex::Type encode_type; + int bitrate; + int gop_size; + int b_frames = 0; // we don't use b frames + + static EncoderSettings MainEncoderSettings(int in_width) { + if (in_width <= 1344) { + return EncoderSettings{.encode_type = MAIN_ENCODE_TYPE, .bitrate = 5'000'000, .gop_size = 20}; + } else { + return EncoderSettings{.encode_type = MAIN_ENCODE_TYPE, .bitrate = 10'000'000, .gop_size = 30}; + } + } + + static EncoderSettings QcamEncoderSettings() { + return EncoderSettings{.encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, .bitrate = 256'000, .gop_size = 15}; + } + + static EncoderSettings StreamEncoderSettings() { + return EncoderSettings{.encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, .bitrate = 1'000'000, .gop_size = 15}; + } +}; + class EncoderInfo { public: const char *publish_name; @@ -39,9 +60,8 @@ public: int frame_width = -1; int frame_height = -1; int fps = MAIN_FPS; - int bitrate = MAIN_BITRATE; - cereal::EncodeIndex::Type encode_type = Hardware::PC() ? cereal::EncodeIndex::Type::BIG_BOX_LOSSLESS - : cereal::EncodeIndex::Type::FULL_H_E_V_C; + std::function get_settings; + ::cereal::EncodeData::Reader (cereal::Event::Reader::*get_encode_data_func)() const; void (cereal::Event::Builder::*set_encode_idx_func)(::cereal::EncodeIndex::Reader); cereal::EncodeData::Builder (cereal::Event::Builder::*init_encode_data_func)(); @@ -59,12 +79,14 @@ const EncoderInfo main_road_encoder_info = { .publish_name = "roadEncodeData", .thumbnail_name = "thumbnail", .filename = "fcamera.hevc", + .get_settings = [](int in_width){return EncoderSettings::MainEncoderSettings(in_width);}, INIT_ENCODE_FUNCTIONS(RoadEncode), }; const EncoderInfo main_wide_road_encoder_info = { .publish_name = "wideRoadEncodeData", .filename = "ecamera.hevc", + .get_settings = [](int in_width){return EncoderSettings::MainEncoderSettings(in_width);}, INIT_ENCODE_FUNCTIONS(WideRoadEncode), }; @@ -72,39 +94,36 @@ const EncoderInfo main_driver_encoder_info = { .publish_name = "driverEncodeData", .filename = "dcamera.hevc", .record = Params().getBool("RecordFront"), + .get_settings = [](int in_width){return EncoderSettings::MainEncoderSettings(in_width);}, INIT_ENCODE_FUNCTIONS(DriverEncode), }; const EncoderInfo stream_road_encoder_info = { .publish_name = "livestreamRoadEncodeData", //.thumbnail_name = "thumbnail", - .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, .record = false, - .bitrate = LIVESTREAM_BITRATE, + .get_settings = [](int){return EncoderSettings::StreamEncoderSettings();}, INIT_ENCODE_FUNCTIONS(LivestreamRoadEncode), }; const EncoderInfo stream_wide_road_encoder_info = { .publish_name = "livestreamWideRoadEncodeData", - .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, .record = false, - .bitrate = LIVESTREAM_BITRATE, + .get_settings = [](int){return EncoderSettings::StreamEncoderSettings();}, INIT_ENCODE_FUNCTIONS(LivestreamWideRoadEncode), }; const EncoderInfo stream_driver_encoder_info = { .publish_name = "livestreamDriverEncodeData", - .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, .record = false, - .bitrate = LIVESTREAM_BITRATE, + .get_settings = [](int){return EncoderSettings::StreamEncoderSettings();}, INIT_ENCODE_FUNCTIONS(LivestreamDriverEncode), }; const EncoderInfo qcam_encoder_info = { .publish_name = "qRoadEncodeData", .filename = "qcamera.ts", - .bitrate = QCAM_BITRATE, - .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, + .get_settings = [](int){return EncoderSettings::QcamEncoderSettings();}, .frame_width = 526, .frame_height = 330, .include_audio = Params().getBool("RecordAudio"), diff --git a/system/loggerd/tests/test_encoder.py b/system/loggerd/tests/test_encoder.py index b24bfbe168..e4dabd3df9 100644 --- a/system/loggerd/tests/test_encoder.py +++ b/system/loggerd/tests/test_encoder.py @@ -19,11 +19,12 @@ from openpilot.system.hardware.hw import Paths SEGMENT_LENGTH = 2 FULL_SIZE = 2507572 +def hevc_size(w): return FULL_SIZE // 2 if w <= 1344 else FULL_SIZE CAMERAS = [ - ("fcamera.hevc", 20, FULL_SIZE, "roadEncodeIdx"), - ("dcamera.hevc", 20, FULL_SIZE, "driverEncodeIdx"), - ("ecamera.hevc", 20, FULL_SIZE, "wideRoadEncodeIdx"), - ("qcamera.ts", 20, 130000, None), + ("fcamera.hevc", 20, hevc_size, "roadEncodeIdx"), + ("dcamera.hevc", 20, hevc_size, "driverEncodeIdx"), + ("ecamera.hevc", 20, hevc_size, "wideRoadEncodeIdx"), + ("qcamera.ts", 20, lambda x: 130000, None), ] # we check frame count, so we don't have to be too strict on size @@ -76,7 +77,7 @@ class TestEncoder: # check each camera file size counts = [] first_frames = [] - for camera, fps, size, encode_idx_name in CAMERAS: + for camera, fps, size_lambda, encode_idx_name in CAMERAS: if not record_front and "dcamera" in camera: continue @@ -86,14 +87,14 @@ class TestEncoder: assert os.path.exists(file_path), f"segment #{i}: '{file_path}' missing" # TODO: this ffprobe call is really slow - # check frame count - cmd = f"ffprobe -v error -select_streams v:0 -count_packets -show_entries stream=nb_read_packets -of csv=p=0 {file_path}" + # get width and check frame count + cmd = f"ffprobe -v error -select_streams v:0 -count_packets -show_entries stream=nb_read_packets,width -of csv=p=0 {file_path}" if TICI: cmd = "LD_LIBRARY_PATH=/usr/local/lib " + cmd expected_frames = fps * SEGMENT_LENGTH - probe = subprocess.check_output(cmd, shell=True, encoding='utf8') - frame_count = int(probe.split('\n')[0].strip()) + probe = subprocess.check_output(cmd, shell=True, encoding='utf8').split('\n')[0].strip().split(',') + frame_width, frame_count = int(probe[0]), int(probe[1]) counts.append(frame_count) assert frame_count == expected_frames, \ @@ -101,8 +102,9 @@ class TestEncoder: # sanity check file size file_size = os.path.getsize(file_path) - assert math.isclose(file_size, size, rel_tol=FILE_SIZE_TOLERANCE), \ - f"{file_path} size {file_size} isn't close to target size {size}" + target_size = size_lambda(frame_width) + assert math.isclose(file_size, target_size, rel_tol=FILE_SIZE_TOLERANCE), \ + f"{file_path} size {file_size} isn't close to target size {target_size}" # Check encodeIdx if encode_idx_name is not None: diff --git a/system/loggerd/tests/test_loggerd.py b/system/loggerd/tests/test_loggerd.py index 8f9d92e104..c6a4b12e63 100644 --- a/system/loggerd/tests/test_loggerd.py +++ b/system/loggerd/tests/test_loggerd.py @@ -282,15 +282,15 @@ class TestLoggerd: sent.clear_write_flag() assert sent.to_bytes() == m.as_builder().to_bytes() - def test_preserving_flagged_segments(self): - services = set(random.sample(CEREAL_SERVICES, random.randint(5, 10))) | {"userFlag"} + def test_preserving_bookmarked_segments(self): + services = set(random.sample(CEREAL_SERVICES, random.randint(5, 10))) | {"userBookmark"} self._publish_random_messages(services) segment_dir = self._get_latest_log_dir() assert getxattr(segment_dir, PRESERVE_ATTR_NAME) == PRESERVE_ATTR_VALUE - def test_not_preserving_unflagged_segments(self): - services = set(random.sample(CEREAL_SERVICES, random.randint(5, 10))) - {"userFlag"} + def test_not_preserving_nonbookmarked_segments(self): + services = set(random.sample(CEREAL_SERVICES, random.randint(5, 10))) - {"userBookmark", "audioFeedback"} self._publish_random_messages(services) segment_dir = self._get_latest_log_dir() diff --git a/system/manager/manager.py b/system/manager/manager.py index bd8e552dd3..36055d8635 100755 --- a/system/manager/manager.py +++ b/system/manager/manager.py @@ -40,7 +40,7 @@ def manager_init() -> None: # set unset params to their default value for k in params.all_keys(): default_value = params.get_default_value(k) - if default_value and params.get(k) is None: + if default_value is not None and params.get(k) is None: params.put(k, default_value) # Create folders needed for msgq diff --git a/system/manager/process_config.py b/system/manager/process_config.py index ecd5b724cd..5758512f2b 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -81,6 +81,7 @@ procs = [ PythonProcess("sensord", "system.sensord.sensord", only_onroad, enabled=not PC), NativeProcess("ui", "selfdrive/ui", ["./ui"], always_run, watchdog_max_dt=(5 if not PC else None)), + PythonProcess("raylib_ui", "selfdrive.ui.ui", always_run, enabled=False, watchdog_max_dt=(5 if not PC else None)), PythonProcess("soundd", "selfdrive.ui.soundd", only_onroad), PythonProcess("locationd", "selfdrive.locationd.locationd", only_onroad), NativeProcess("_pandad", "selfdrive/pandad", ["./pandad"], always_run, enabled=False), @@ -106,6 +107,7 @@ procs = [ PythonProcess("updated", "system.updated.updated", only_offroad, enabled=not PC), PythonProcess("uploader", "system.loggerd.uploader", always_run), PythonProcess("statsd", "system.statsd", always_run), + PythonProcess("feedbackd", "selfdrive.ui.feedback.feedbackd", only_onroad), # debug procs NativeProcess("bridge", "cereal/messaging", ["./bridge"], notcar), diff --git a/system/manager/test/test_manager.py b/system/manager/test/test_manager.py index 5e55648283..34d07c6724 100644 --- a/system/manager/test/test_manager.py +++ b/system/manager/test/test_manager.py @@ -46,9 +46,10 @@ class TestManager: manager.main() for k in params.all_keys(): default_value = params.get_default_value(k) - if default_value: + if default_value is not None: assert params.get(k) == default_value assert params.get("OpenpilotEnabledToggle") + assert params.get("RouteCount") == 0 @pytest.mark.skip("this test is flaky the way it's currently written, should be moved to test_onroad") def test_clean_exit(self, subtests): diff --git a/system/ui/lib/application.py b/system/ui/lib/application.py index 30672fba06..3f433e1fcb 100644 --- a/system/ui/lib/application.py +++ b/system/ui/lib/application.py @@ -19,7 +19,7 @@ FPS_LOG_INTERVAL = 5 # Seconds between logging FPS drops FPS_DROP_THRESHOLD = 0.9 # FPS drop threshold for triggering a warning FPS_CRITICAL_THRESHOLD = 0.5 # Critical threshold for triggering strict actions MOUSE_THREAD_RATE = 140 # touch controller runs at 140Hz -MAX_TOUCH_SLOT = 2 +MAX_TOUCH_SLOTS = 2 ENABLE_VSYNC = os.getenv("ENABLE_VSYNC", "0") == "1" SHOW_FPS = os.getenv("SHOW_FPS") == "1" @@ -67,9 +67,10 @@ class MouseEvent(NamedTuple): class MouseState: - def __init__(self): + def __init__(self, scale: float = 1.0): + self._scale = scale self._events: deque[MouseEvent] = deque(maxlen=MOUSE_THREAD_RATE) # bound event list - self._prev_mouse_event: list[MouseEvent | None] = [None] * MAX_TOUCH_SLOT + self._prev_mouse_event: list[MouseEvent | None] = [None] * MAX_TOUCH_SLOTS self._rk = Ratekeeper(MOUSE_THREAD_RATE) self._lock = threading.Lock() @@ -100,10 +101,12 @@ class MouseState: self._rk.keep_time() def _handle_mouse_event(self): - for slot in range(MAX_TOUCH_SLOT): + for slot in range(MAX_TOUCH_SLOTS): mouse_pos = rl.get_touch_position(slot) + x = mouse_pos.x / self._scale if self._scale != 1.0 else mouse_pos.x + y = mouse_pos.y / self._scale if self._scale != 1.0 else mouse_pos.y ev = MouseEvent( - MousePos(mouse_pos.x, mouse_pos.y), + MousePos(x, y), slot, rl.is_mouse_button_pressed(slot), rl.is_mouse_button_released(slot), @@ -133,7 +136,7 @@ class GuiApplication: self._trace_log_callback = None self._modal_overlay = ModalOverlay() - self._mouse = MouseState() + self._mouse = MouseState(self._scale) self._mouse_events: list[MouseEvent] = [] # Debug variables diff --git a/system/ui/lib/emoji.py b/system/ui/lib/emoji.py new file mode 100644 index 0000000000..28139158a1 --- /dev/null +++ b/system/ui/lib/emoji.py @@ -0,0 +1,47 @@ +import io +import re + +from PIL import Image, ImageDraw, ImageFont +import pyray as rl + +_cache: dict[str, rl.Texture] = {} + +EMOJI_REGEX = re.compile( +"""[\U0001F600-\U0001F64F +\U0001F300-\U0001F5FF +\U0001F680-\U0001F6FF +\U0001F1E0-\U0001F1FF +\U00002700-\U000027BF +\U0001F900-\U0001F9FF +\U00002600-\U000026FF +\U00002300-\U000023FF +\U00002B00-\U00002BFF +\U0001FA70-\U0001FAFF +\U0001F700-\U0001F77F +\u2640-\u2642 +\u2600-\u2B55 +\u200d +\u23cf +\u23e9 +\u231a +\ufe0f +\u3030 +]+""", + flags=re.UNICODE +) + +def find_emoji(text): + return [(m.start(), m.end(), m.group()) for m in EMOJI_REGEX.finditer(text)] + +def emoji_tex(emoji): + if emoji not in _cache: + img = Image.new("RGBA", (128, 128), (0, 0, 0, 0)) + draw = ImageDraw.Draw(img) + font = ImageFont.truetype("NotoColorEmoji", 109) + draw.text((0, 0), emoji, font=font, embedded_color=True) + buffer = io.BytesIO() + img.save(buffer, format="PNG") + l = buffer.tell() + buffer.seek(0) + _cache[emoji] = rl.load_texture_from_image(rl.load_image_from_memory(".png", buffer.getvalue(), l)) + return _cache[emoji] diff --git a/system/ui/lib/shader_polygon.py b/system/ui/lib/shader_polygon.py index cfde81c554..39bc0d5aa4 100644 --- a/system/ui/lib/shader_polygon.py +++ b/system/ui/lib/shader_polygon.py @@ -39,6 +39,10 @@ vec4 getGradientColor(vec2 pos) { float t = clamp(dot(pos - gradientStart, normalizedDir) / gradientLength, 0.0, 1.0); if (gradientColorCount <= 1) return gradientColors[0]; + + // handle t before first / after last stop + if (t <= gradientStops[0]) return gradientColors[0]; + if (t >= gradientStops[gradientColorCount-1]) return gradientColors[gradientColorCount-1]; for (int i = 0; i < gradientColorCount - 1; i++) { if (t >= gradientStops[i] && t <= gradientStops[i+1]) { float segmentT = (t - gradientStops[i]) / (gradientStops[i+1] - gradientStops[i]); diff --git a/system/ui/lib/wifi_manager.py b/system/ui/lib/wifi_manager.py index acdab3b411..4cb741bc95 100644 --- a/system/ui/lib/wifi_manager.py +++ b/system/ui/lib/wifi_manager.py @@ -37,7 +37,7 @@ NM_DEVICE_IFACE = "org.freedesktop.NetworkManager.Device" NM_DEVICE_STATE_REASON_SUPPLICANT_DISCONNECT = 8 TETHERING_IP_ADDRESS = "192.168.43.1" -DEFAULT_TETHERING_PASSWORD = "12345678" +DEFAULT_TETHERING_PASSWORD = "swagswagcomma" # NetworkManager device states @@ -101,8 +101,8 @@ class WifiManager: """Connect to the DBus system bus.""" try: self.bus = await MessageBus(bus_type=BusType.SYSTEM).connect() - if not await self._find_wifi_device(): - raise ValueError("No Wi-Fi device found") + while not await self._find_wifi_device(): + await asyncio.sleep(1) await self._setup_signals(self.device_path) self.active_ap_path = await self.get_active_access_point() @@ -441,20 +441,19 @@ class WifiManager: settings_iface.on_connection_removed(self._on_connection_removed) def _on_properties_changed(self, interface: str, changed: dict, invalidated: list): - if 'LastScan' in changed: + if interface == NM_WIRELESS_IFACE and 'LastScan' in changed: asyncio.create_task(self._refresh_networks()) elif interface == NM_WIRELESS_IFACE and "ActiveAccessPoint" in changed: new_ap_path = changed["ActiveAccessPoint"].value if self.active_ap_path != new_ap_path: self.active_ap_path = new_ap_path - asyncio.create_task(self._refresh_networks()) def _on_state_changed(self, new_state: int, old_state: int, reason: int): if new_state == NMDeviceState.ACTIVATED: if self.callbacks.activated: self.callbacks.activated() - asyncio.create_task(self._refresh_networks()) self._current_connection_ssid = None + asyncio.create_task(self._refresh_networks()) elif new_state in (NMDeviceState.DISCONNECTED, NMDeviceState.NEED_AUTH): for network in self.networks: network.is_connected = False @@ -487,9 +486,6 @@ class WifiManager: if self.callbacks.forgotten: self.callbacks.forgotten(ssid) - - # Update network list to reflect the removed saved connection - asyncio.create_task(self._refresh_networks()) break async def _add_saved_connection(self, path: str) -> None: @@ -498,14 +494,13 @@ class WifiManager: settings = await self._get_connection_settings(path) if ssid := self._extract_ssid(settings): self.saved_connections[ssid] = path - await self._refresh_networks() except DBusError as e: cloudlog.error(f"Failed to add connection {path}: {e}") def _extract_ssid(self, settings: dict) -> str | None: """Extract SSID from connection settings.""" ssid_variant = settings.get('802-11-wireless', {}).get('ssid', Variant('ay', b'')).value - return ''.join(chr(b) for b in ssid_variant) if ssid_variant else None + return bytes(ssid_variant).decode('utf-8') if ssid_variant else None async def _add_match_rule(self, rule): """Add a match rule on the bus.""" diff --git a/system/ui/reset.py b/system/ui/reset.py index e3f9e7b2d5..b1bf5a6b6a 100755 --- a/system/ui/reset.py +++ b/system/ui/reset.py @@ -125,7 +125,7 @@ def main(): elif sys.argv[1] == "--format": mode = ResetMode.FORMAT - gui_app.init_window("System Reset") + gui_app.init_window("System Reset", 20) reset = Reset(mode) if mode == ResetMode.FORMAT: diff --git a/system/ui/setup.py b/system/ui/setup.py index 2392449f96..800ca7662c 100755 --- a/system/ui/setup.py +++ b/system/ui/setup.py @@ -4,16 +4,21 @@ import re import threading import time import urllib.request +from urllib.parse import urlparse from enum import IntEnum +import shutil + import pyray as rl from cereal import log +from openpilot.common.run import run_cmd from openpilot.system.hardware import HARDWARE +from openpilot.system.ui.lib.scroll_panel import GuiScrollPanel from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets.button import Button, ButtonStyle, ButtonRadio from openpilot.system.ui.widgets.keyboard import Keyboard -from openpilot.system.ui.widgets.label import gui_label, gui_text_box +from openpilot.system.ui.widgets.label import Label, TextAlignment from openpilot.system.ui.widgets.network import WifiManagerUI, WifiManagerWrapper NetworkType = log.DeviceState.NetworkType @@ -29,15 +34,29 @@ BUTTON_SPACING = 50 OPENPILOT_URL = "https://openpilot.comma.ai" USER_AGENT = f"AGNOSSetup-{HARDWARE.get_os_version()}" +CONTINUE_PATH = "/data/continue.sh" +TMP_CONTINUE_PATH = "/data/continue.sh.new" +INSTALL_PATH = "/data/openpilot" +VALID_CACHE_PATH = "/data/.openpilot_cache" +INSTALLER_SOURCE_PATH = "/usr/comma/installer" +INSTALLER_DESTINATION_PATH = "/tmp/installer" +INSTALLER_URL_PATH = "/tmp/installer_url" + +CONTINUE = """#!/usr/bin/env bash + +cd /data/openpilot +exec ./launch_openpilot.sh +""" class SetupState(IntEnum): LOW_VOLTAGE = 0 GETTING_STARTED = 1 NETWORK_SETUP = 2 SOFTWARE_SELECTION = 3 - CUSTOM_URL = 4 + CUSTOM_SOFTWARE = 4 DOWNLOADING = 5 DOWNLOAD_FAILED = 6 + CUSTOM_SOFTWARE_WARNING = 7 class Setup(Widget): @@ -59,20 +78,54 @@ class Setup(Widget): self.selected_radio = None self.warning = gui_app.texture("icons/warning.png", 150, 150) self.checkmark = gui_app.texture("icons/circled_check.png", 100, 100) + + self._low_voltage_title_label = Label("WARNING: Low Voltage", TITLE_FONT_SIZE, FontWeight.MEDIUM, TextAlignment.LEFT, text_color=rl.Color(255, 89, 79, 255)) + self._low_voltage_body_label = Label("Power your device in a car with a harness or proceed at your own risk.", BODY_FONT_SIZE, + text_alignment=TextAlignment.LEFT) self._low_voltage_continue_button = Button("Continue", self._low_voltage_continue_button_callback) self._low_voltage_poweroff_button = Button("Power Off", HARDWARE.shutdown) + self._getting_started_button = Button("", self._getting_started_button_callback, button_style=ButtonStyle.PRIMARY, border_radius=0) + self._getting_started_title_label = Label("Getting Started", TITLE_FONT_SIZE, FontWeight.BOLD, TextAlignment.LEFT) + self._getting_started_body_label = Label("Before we get on the road, let's finish installation and cover some details.", + BODY_FONT_SIZE, text_alignment=TextAlignment.LEFT) + self._software_selection_openpilot_button = ButtonRadio("openpilot", self.checkmark, font_size=BODY_FONT_SIZE, text_padding=80) self._software_selection_custom_software_button = ButtonRadio("Custom Software", self.checkmark, font_size=BODY_FONT_SIZE, text_padding=80) self._software_selection_continue_button = Button("Continue", self._software_selection_continue_button_callback, - button_style=ButtonStyle.PRIMARY, enabled=False) + button_style=ButtonStyle.PRIMARY) + self._software_selection_continue_button.set_enabled(False) self._software_selection_back_button = Button("Back", self._software_selection_back_button_callback) + self._software_selection_title_label = Label("Choose Software to Use", TITLE_FONT_SIZE, FontWeight.BOLD, TextAlignment.LEFT) + self._download_failed_reboot_button = Button("Reboot device", HARDWARE.reboot) self._download_failed_startover_button = Button("Start over", self._download_failed_startover_button_callback, button_style=ButtonStyle.PRIMARY) + self._download_failed_title_label = Label("Download Failed", TITLE_FONT_SIZE, FontWeight.BOLD, TextAlignment.LEFT) + self._download_failed_url_label = Label("", 64, FontWeight.NORMAL, TextAlignment.LEFT) + self._download_failed_body_label = Label("", BODY_FONT_SIZE, text_alignment=TextAlignment.LEFT) + self._network_setup_back_button = Button("Back", self._network_setup_back_button_callback) self._network_setup_continue_button = Button("Waiting for internet", self._network_setup_continue_button_callback, - button_style=ButtonStyle.PRIMARY, enabled=False) - + button_style=ButtonStyle.PRIMARY) + self._network_setup_continue_button.set_enabled(False) + self._network_setup_title_label = Label("Connect to Wi-Fi", TITLE_FONT_SIZE, FontWeight.BOLD, TextAlignment.LEFT) + + self._custom_software_warning_continue_button = Button("Scroll to continue", self._custom_software_warning_continue_button_callback, + button_style=ButtonStyle.PRIMARY) + self._custom_software_warning_continue_button.set_enabled(False) + self._custom_software_warning_back_button = Button("Back", self._custom_software_warning_back_button_callback) + self._custom_software_warning_title_label = Label("WARNING: Custom Software", 100, FontWeight.BOLD, TextAlignment.LEFT, text_color=rl.Color(255,89,79,255), + text_padding=60) + self._custom_software_warning_body_label = Label("Use caution when installing third-party software.\n\n" + + "⚠️ It has not been tested by comma.\n\n" + + "⚠️ It may not comply with relevant safety standards.\n\n" + + "⚠️ It may cause damage to your device and/or vehicle.\n\n" + + "If you'd like to proceed, use https://flash.comma.ai " + + "to restore your device to a factory state later.", + 85, text_alignment=TextAlignment.LEFT, text_padding=60) + self._custom_software_warning_body_scroll_panel = GuiScrollPanel() + + self._downloading_body_label = Label("Downloading...", TITLE_FONT_SIZE, FontWeight.MEDIUM) try: with open("/sys/class/hwmon/hwmon1/in1_input") as f: @@ -91,8 +144,10 @@ class Setup(Widget): self.render_network_setup(rect) elif self.state == SetupState.SOFTWARE_SELECTION: self.render_software_selection(rect) - elif self.state == SetupState.CUSTOM_URL: - self.render_custom_url() + elif self.state == SetupState.CUSTOM_SOFTWARE_WARNING: + self.render_custom_software_warning(rect) + elif self.state == SetupState.CUSTOM_SOFTWARE: + self.render_custom_software() elif self.state == SetupState.DOWNLOADING: self.render_downloading(rect) elif self.state == SetupState.DOWNLOAD_FAILED: @@ -101,56 +156,55 @@ class Setup(Widget): def _low_voltage_continue_button_callback(self): self.state = SetupState.GETTING_STARTED - def _getting_started_button_callback(self): + def _custom_software_warning_back_button_callback(self): + self.state = SetupState.SOFTWARE_SELECTION + + def _custom_software_warning_continue_button_callback(self): self.state = SetupState.NETWORK_SETUP self.stop_network_check_thread.clear() self.start_network_check() + def _getting_started_button_callback(self): + self.state = SetupState.SOFTWARE_SELECTION + def _software_selection_back_button_callback(self): - self.state = SetupState.NETWORK_SETUP - self.stop_network_check_thread.clear() - self.start_network_check() + self.state = SetupState.GETTING_STARTED def _software_selection_continue_button_callback(self): if self._software_selection_openpilot_button.selected: - self.download(OPENPILOT_URL) + self.use_openpilot() else: - self.state = SetupState.CUSTOM_URL + self.state = SetupState.CUSTOM_SOFTWARE_WARNING def _download_failed_startover_button_callback(self): self.state = SetupState.GETTING_STARTED def _network_setup_back_button_callback(self): - self.state = SetupState.GETTING_STARTED + self.state = SetupState.SOFTWARE_SELECTION def _network_setup_continue_button_callback(self): - self.state = SetupState.SOFTWARE_SELECTION self.stop_network_check_thread.set() + if self._software_selection_openpilot_button.selected: + self.download(OPENPILOT_URL) + else: + self.state = SetupState.CUSTOM_SOFTWARE def render_low_voltage(self, rect: rl.Rectangle): rl.draw_texture(self.warning, int(rect.x + 150), int(rect.y + 110), rl.WHITE) - title_rect = rl.Rectangle(rect.x + 150, rect.y + 110 + 150 + 100, rect.width - 500 - 150, TITLE_FONT_SIZE) - gui_label(title_rect, "WARNING: Low Voltage", TITLE_FONT_SIZE, rl.Color(255, 89, 79, 255), FontWeight.MEDIUM) - - body_rect = rl.Rectangle(rect.x + 150, rect.y + 110 + 150 + 100 + TITLE_FONT_SIZE + 25, rect.width - 500 - 150, BODY_FONT_SIZE * 3) - gui_text_box(body_rect, "Power your device in a car with a harness or proceed at your own risk.", BODY_FONT_SIZE) + self._low_voltage_title_label.render(rl.Rectangle(rect.x + 150, rect.y + 110 + 150 + 100, rect.width - 500 - 150, TITLE_FONT_SIZE)) + self._low_voltage_body_label.render(rl.Rectangle(rect.x + 150, rect.y + 110 + 150 + 150, rect.width - 500, BODY_FONT_SIZE * 3)) button_width = (rect.width - MARGIN * 3) / 2 button_y = rect.height - MARGIN - BUTTON_HEIGHT - self._low_voltage_poweroff_button.render(rl.Rectangle(rect.x + MARGIN, button_y, button_width, BUTTON_HEIGHT)) self._low_voltage_continue_button.render(rl.Rectangle(rect.x + MARGIN * 2 + button_width, button_y, button_width, BUTTON_HEIGHT)) def render_getting_started(self, rect: rl.Rectangle): - title_rect = rl.Rectangle(rect.x + 165, rect.y + 280, rect.width - 265, TITLE_FONT_SIZE) - gui_label(title_rect, "Getting Started", TITLE_FONT_SIZE, font_weight=FontWeight.MEDIUM) - - desc_rect = rl.Rectangle(rect.x + 165, rect.y + 280 + TITLE_FONT_SIZE + 90, rect.width - 500, BODY_FONT_SIZE * 3) - gui_text_box(desc_rect, "Before we get on the road, let's finish installation and cover some details.", BODY_FONT_SIZE) + self._getting_started_title_label.render(rl.Rectangle(rect.x + 165, rect.y + 280, rect.width - 265, TITLE_FONT_SIZE)) + self._getting_started_body_label.render(rl.Rectangle(rect.x + 165, rect.y + 280 + TITLE_FONT_SIZE, rect.width - 500, BODY_FONT_SIZE * 3)) btn_rect = rl.Rectangle(rect.width - NEXT_BUTTON_WIDTH, 0, NEXT_BUTTON_WIDTH, rect.height) - self._getting_started_button.render(btn_rect) triangle = gui_app.texture("images/button_continue_triangle.png", 54, int(btn_rect.height)) rl.draw_texture_v(triangle, rl.Vector2(btn_rect.x + btn_rect.width / 2 - triangle.width / 2, btn_rect.height / 2 - triangle.height / 2), rl.WHITE) @@ -180,8 +234,7 @@ class Setup(Widget): self.network_check_thread.join() def render_network_setup(self, rect: rl.Rectangle): - title_rect = rl.Rectangle(rect.x + MARGIN, rect.y + MARGIN, rect.width - MARGIN * 2, TITLE_FONT_SIZE) - gui_label(title_rect, "Connect to Wi-Fi", TITLE_FONT_SIZE, font_weight=FontWeight.MEDIUM) + self._network_setup_title_label.render(rl.Rectangle(rect.x + MARGIN, rect.y + MARGIN, rect.width - MARGIN * 2, TITLE_FONT_SIZE)) wifi_rect = rl.Rectangle(rect.x + MARGIN, rect.y + TITLE_FONT_SIZE + MARGIN + 25, rect.width - MARGIN * 2, rect.height - TITLE_FONT_SIZE - 25 - BUTTON_HEIGHT - MARGIN * 3) @@ -196,32 +249,31 @@ class Setup(Widget): # Check network connectivity status continue_enabled = self.network_connected.is_set() - self._network_setup_continue_button.enabled = continue_enabled + self._network_setup_continue_button.set_enabled(continue_enabled) continue_text = ("Continue" if self.wifi_connected.is_set() else "Continue without Wi-Fi") if continue_enabled else "Waiting for internet" self._network_setup_continue_button.set_text(continue_text) self._network_setup_continue_button.render(rl.Rectangle(rect.x + MARGIN + button_width + BUTTON_SPACING, button_y, button_width, BUTTON_HEIGHT)) def render_software_selection(self, rect: rl.Rectangle): - title_rect = rl.Rectangle(rect.x + MARGIN, rect.y + MARGIN, rect.width - MARGIN * 2, TITLE_FONT_SIZE) - gui_label(title_rect, "Choose Software to Use", TITLE_FONT_SIZE, font_weight=FontWeight.MEDIUM) + self._software_selection_title_label.render(rl.Rectangle(rect.x + MARGIN, rect.y + MARGIN, rect.width - MARGIN * 2, TITLE_FONT_SIZE)) radio_height = 230 radio_spacing = 30 - self._software_selection_continue_button.enabled = False + self._software_selection_continue_button.set_enabled(False) openpilot_rect = rl.Rectangle(rect.x + MARGIN, rect.y + TITLE_FONT_SIZE + MARGIN * 2, rect.width - MARGIN * 2, radio_height) self._software_selection_openpilot_button.render(openpilot_rect) if self._software_selection_openpilot_button.selected: - self._software_selection_continue_button.enabled = True + self._software_selection_continue_button.set_enabled(True) self._software_selection_custom_software_button.selected = False custom_rect = rl.Rectangle(rect.x + MARGIN, rect.y + TITLE_FONT_SIZE + MARGIN * 2 + radio_height + radio_spacing, rect.width - MARGIN * 2, radio_height) self._software_selection_custom_software_button.render(custom_rect) if self._software_selection_custom_software_button.selected: - self._software_selection_continue_button.enabled = True + self._software_selection_continue_button.set_enabled(True) self._software_selection_openpilot_button.selected = False button_width = (rect.width - BUTTON_SPACING - MARGIN * 2) / 2 @@ -231,26 +283,41 @@ class Setup(Widget): self._software_selection_continue_button.render(rl.Rectangle(rect.x + MARGIN + button_width + BUTTON_SPACING, button_y, button_width, BUTTON_HEIGHT)) def render_downloading(self, rect: rl.Rectangle): - title_rect = rl.Rectangle(rect.x, rect.y + rect.height / 2 - TITLE_FONT_SIZE / 2, rect.width, TITLE_FONT_SIZE) - gui_label(title_rect, "Downloading...", TITLE_FONT_SIZE, font_weight=FontWeight.MEDIUM, alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER) + self._downloading_body_label.render(rl.Rectangle(rect.x, rect.y + rect.height / 2 - TITLE_FONT_SIZE / 2, rect.width, TITLE_FONT_SIZE)) def render_download_failed(self, rect: rl.Rectangle): - title_rect = rl.Rectangle(rect.x + 117, rect.y + 185, rect.width - 117, TITLE_FONT_SIZE) - gui_label(title_rect, "Download Failed", TITLE_FONT_SIZE, font_weight=FontWeight.MEDIUM) - - url_rect = rl.Rectangle(rect.x + 117, rect.y + 185 + TITLE_FONT_SIZE + 67, rect.width - 117 - 100, 64) - gui_label(url_rect, self.failed_url, 64, font_weight=FontWeight.NORMAL) + self._download_failed_title_label.render(rl.Rectangle(rect.x + 117, rect.y + 185, rect.width - 117, TITLE_FONT_SIZE)) + self._download_failed_url_label.set_text(self.failed_url) + self._download_failed_url_label.render(rl.Rectangle(rect.x + 117, rect.y + 185 + TITLE_FONT_SIZE + 67, rect.width - 117 - 100, 64)) - error_rect = rl.Rectangle(rect.x + 117, rect.y + 185 + TITLE_FONT_SIZE + 67 + 64 + 48, - rect.width - 117 - 100, rect.height - 185 + TITLE_FONT_SIZE + 67 + 64 + 48 - BUTTON_HEIGHT - MARGIN * 2) - gui_text_box(error_rect, self.failed_reason, BODY_FONT_SIZE) + self._download_failed_body_label.set_text(self.failed_reason) + self._download_failed_body_label.render(rl.Rectangle(rect.x + 117, rect.y, rect.width - 117 - 100, rect.height)) button_width = (rect.width - BUTTON_SPACING - MARGIN * 2) / 2 button_y = rect.height - BUTTON_HEIGHT - MARGIN self._download_failed_reboot_button.render(rl.Rectangle(rect.x + MARGIN, button_y, button_width, BUTTON_HEIGHT)) self._download_failed_startover_button.render(rl.Rectangle(rect.x + MARGIN + button_width + BUTTON_SPACING, button_y, button_width, BUTTON_HEIGHT)) - def render_custom_url(self): + def render_custom_software_warning(self, rect: rl.Rectangle): + warn_rect = rl.Rectangle(rect.x, rect.y, rect.width, 1500) + offset = self._custom_software_warning_body_scroll_panel.handle_scroll(rect, warn_rect) + + button_width = (rect.width - MARGIN * 3) / 2 + button_y = rect.height - MARGIN - BUTTON_HEIGHT + + rl.begin_scissor_mode(int(rect.x), int(rect.y), int(rect.width), int(button_y - BODY_FONT_SIZE)) + y_offset = rect.y + offset.y + self._custom_software_warning_title_label.render(rl.Rectangle(rect.x + 50, y_offset + 150, rect.width - 265, TITLE_FONT_SIZE)) + self._custom_software_warning_body_label.render(rl.Rectangle(rect.x + 50, y_offset + 200 , rect.width - 50, BODY_FONT_SIZE * 3)) + rl.end_scissor_mode() + + self._custom_software_warning_back_button.render(rl.Rectangle(rect.x + MARGIN, button_y, button_width, BUTTON_HEIGHT)) + self._custom_software_warning_continue_button.render(rl.Rectangle(rect.x + MARGIN * 2 + button_width, button_y, button_width, BUTTON_HEIGHT)) + if offset.y < (rect.height - warn_rect.height): + self._custom_software_warning_continue_button.set_enabled(True) + self._custom_software_warning_continue_button.set_text("Continue") + + def render_custom_software(self): def handle_keyboard_result(result): # Enter pressed if result == 1: @@ -267,12 +334,31 @@ class Setup(Widget): self.keyboard.set_title("Enter URL", "for Custom Software") gui_app.set_modal_overlay(self.keyboard, callback=handle_keyboard_result) + def use_openpilot(self): + if os.path.isdir(INSTALL_PATH) and os.path.isfile(VALID_CACHE_PATH): + os.remove(VALID_CACHE_PATH) + with open(TMP_CONTINUE_PATH, "w") as f: + f.write(CONTINUE) + run_cmd(["chmod", "+x", TMP_CONTINUE_PATH]) + shutil.move(TMP_CONTINUE_PATH, CONTINUE_PATH) + shutil.copyfile(INSTALLER_SOURCE_PATH, INSTALLER_DESTINATION_PATH) + + # give time for installer UI to take over + time.sleep(1) + gui_app.request_close() + else: + self.state = SetupState.NETWORK_SETUP + self.stop_network_check_thread.clear() + self.start_network_check() + def download(self, url: str): # autocomplete incomplete URLs if re.match("^([^/.]+)/([^/]+)$", url): url = f"https://installer.comma.ai/{url}" - self.download_url = url + parsed = urlparse(url, scheme='https') + self.download_url = (urlparse(f"https://{url}") if not parsed.netloc else parsed).geturl() + self.state = SetupState.DOWNLOADING self.download_thread = threading.Thread(target=self._download_thread, daemon=True) @@ -282,7 +368,7 @@ class Setup(Widget): try: import tempfile - _, tmpfile = tempfile.mkstemp(prefix="installer_") + fd, tmpfile = tempfile.mkstemp(prefix="installer_") headers = {"User-Agent": USER_AGENT, "X-openpilot-serial": HARDWARE.get_serial()} req = urllib.request.Request(self.download_url, headers=headers) @@ -312,12 +398,16 @@ class Setup(Widget): self.download_failed(self.download_url, "No custom software found at this URL.") return - os.rename(tmpfile, "/tmp/installer") - os.chmod("/tmp/installer", 0o755) + # AGNOS might try to execute the installer before this process exits. + # Therefore, important to close the fd before renaming the installer. + os.close(fd) + os.rename(tmpfile, INSTALLER_DESTINATION_PATH) - with open("/tmp/installer_url", "w") as f: + with open(INSTALLER_URL_PATH, "w") as f: f.write(self.download_url) + # give time for installer UI to take over + time.sleep(5) gui_app.request_close() except Exception: @@ -332,7 +422,7 @@ class Setup(Widget): def main(): try: - gui_app.init_window("Setup") + gui_app.init_window("Setup", 20) setup = Setup() for _ in gui_app.render(): setup.render(rl.Rectangle(0, 0, gui_app.width, gui_app.height)) diff --git a/system/ui/widgets/__init__.py b/system/ui/widgets/__init__.py index 2d619cbd11..d45f48ac38 100644 --- a/system/ui/widgets/__init__.py +++ b/system/ui/widgets/__init__.py @@ -2,7 +2,7 @@ import abc import pyray as rl from enum import IntEnum from collections.abc import Callable -from openpilot.system.ui.lib.application import gui_app, MousePos, MAX_TOUCH_SLOT +from openpilot.system.ui.lib.application import gui_app, MousePos, MAX_TOUCH_SLOTS class DialogResult(IntEnum): @@ -15,34 +15,18 @@ class Widget(abc.ABC): def __init__(self): self._rect: rl.Rectangle = rl.Rectangle(0, 0, 0, 0) self._parent_rect: rl.Rectangle = rl.Rectangle(0, 0, 0, 0) - self._is_pressed = [False] * MAX_TOUCH_SLOT - self._multi_touch = False + self._is_pressed = [False] * MAX_TOUCH_SLOTS + # if current mouse/touch down started within the widget's rectangle + self._tracking_is_pressed = [False] * MAX_TOUCH_SLOTS + self._enabled: bool | Callable[[], bool] = True self._is_visible: bool | Callable[[], bool] = True self._touch_valid_callback: Callable[[], bool] | None = None - - def set_touch_valid_callback(self, touch_callback: Callable[[], bool]) -> None: - """Set a callback to determine if the widget can be clicked.""" - self._touch_valid_callback = touch_callback - - def _touch_valid(self) -> bool: - """Check if the widget can be touched.""" - return self._touch_valid_callback() if self._touch_valid_callback else True - - @property - def is_visible(self) -> bool: - return self._is_visible() if callable(self._is_visible) else self._is_visible - - @property - def is_pressed(self) -> bool: - return any(self._is_pressed) + self._multi_touch = False @property def rect(self) -> rl.Rectangle: return self._rect - def set_visible(self, visible: bool | Callable[[], bool]) -> None: - self._is_visible = visible - def set_rect(self, rect: rl.Rectangle) -> None: changed = (self._rect.x != rect.x or self._rect.y != rect.y or self._rect.width != rect.width or self._rect.height != rect.height) @@ -54,6 +38,32 @@ class Widget(abc.ABC): """Can be used like size hint in QT""" self._parent_rect = parent_rect + @property + def is_pressed(self) -> bool: + return any(self._is_pressed) + + @property + def enabled(self) -> bool: + return self._enabled() if callable(self._enabled) else self._enabled + + def set_enabled(self, enabled: bool | Callable[[], bool]) -> None: + self._enabled = enabled + + @property + def is_visible(self) -> bool: + return self._is_visible() if callable(self._is_visible) else self._is_visible + + def set_visible(self, visible: bool | Callable[[], bool]) -> None: + self._is_visible = visible + + def set_touch_valid_callback(self, touch_callback: Callable[[], bool]) -> None: + """Set a callback to determine if the widget can be clicked.""" + self._touch_valid_callback = touch_callback + + def _touch_valid(self) -> bool: + """Check if the widget can be touched.""" + return self._touch_valid_callback() if self._touch_valid_callback else True + def set_position(self, x: float, y: float) -> None: changed = (self._rect.x != x or self._rect.y != y) self._rect.x, self._rect.y = x, y @@ -72,20 +82,37 @@ class Widget(abc.ABC): ret = self._render(self._rect) # Keep track of whether mouse down started within the widget's rectangle - for mouse_event in gui_app.mouse_events: - if not self._multi_touch and mouse_event.slot != 0: - continue - if mouse_event.left_pressed and self._touch_valid(): - if rl.check_collision_point_rec(mouse_event.pos, self._rect): - self._is_pressed[mouse_event.slot] = True - - elif not self._touch_valid(): - self._is_pressed[mouse_event.slot] = False - - elif mouse_event.left_released: - if self._is_pressed[mouse_event.slot] and rl.check_collision_point_rec(mouse_event.pos, self._rect): - self._handle_mouse_release(mouse_event.pos) - self._is_pressed[mouse_event.slot] = False + if self.enabled: + for mouse_event in gui_app.mouse_events: + if not self._multi_touch and mouse_event.slot != 0: + continue + + # Ignores touches/presses that start outside our rect + # Allows touch to leave the rect and come back in focus if mouse did not release + if mouse_event.left_pressed and self._touch_valid(): + if rl.check_collision_point_rec(mouse_event.pos, self._rect): + self._is_pressed[mouse_event.slot] = True + self._tracking_is_pressed[mouse_event.slot] = True + + # Callback such as scroll panel signifies user is scrolling + elif not self._touch_valid(): + self._is_pressed[mouse_event.slot] = False + self._tracking_is_pressed[mouse_event.slot] = False + + elif mouse_event.left_released: + if self._is_pressed[mouse_event.slot] and rl.check_collision_point_rec(mouse_event.pos, self._rect): + self._handle_mouse_release(mouse_event.pos) + self._is_pressed[mouse_event.slot] = False + self._tracking_is_pressed[mouse_event.slot] = False + + # Mouse/touch is still within our rect + elif rl.check_collision_point_rec(mouse_event.pos, self._rect): + if self._tracking_is_pressed[mouse_event.slot]: + self._is_pressed[mouse_event.slot] = True + + # Mouse/touch left our rect but may come back into focus later + elif not rl.check_collision_point_rec(mouse_event.pos, self._rect): + self._is_pressed[mouse_event.slot] = False return ret diff --git a/system/ui/widgets/button.py b/system/ui/widgets/button.py index 04fed82b34..a5dab19789 100644 --- a/system/ui/widgets/button.py +++ b/system/ui/widgets/button.py @@ -6,6 +6,7 @@ import pyray as rl 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.widgets import Widget +from openpilot.system.ui.widgets.label import TextAlignment, Label class ButtonStyle(IntEnum): @@ -20,12 +21,6 @@ class ButtonStyle(IntEnum): FORGET_WIFI = 8 -class TextAlignment(IntEnum): - LEFT = 0 - CENTER = 1 - RIGHT = 2 - - ICON_PADDING = 15 DEFAULT_BUTTON_FONT_SIZE = 60 BUTTON_DISABLED_TEXT_COLOR = rl.Color(228, 228, 228, 51) @@ -37,7 +32,7 @@ BUTTON_TEXT_COLOR = { ButtonStyle.PRIMARY: rl.Color(228, 228, 228, 255), ButtonStyle.DANGER: rl.Color(228, 228, 228, 255), ButtonStyle.TRANSPARENT: rl.BLACK, - ButtonStyle.ACTION: rl.Color(0, 0, 0, 255), + ButtonStyle.ACTION: rl.BLACK, ButtonStyle.LIST_ACTION: rl.Color(228, 228, 228, 255), ButtonStyle.NO_EFFECT: rl.Color(228, 228, 228, 255), ButtonStyle.KEYBOARD: rl.Color(221, 221, 221, 255), @@ -177,31 +172,23 @@ class Button(Widget): border_radius: int = 10, text_alignment: TextAlignment = TextAlignment.CENTER, text_padding: int = 20, - enabled: bool = True, icon = None, multi_touch: bool = False, ): super().__init__() - self._text = text - self._click_callback = click_callback - self._label_font = gui_app.font(FontWeight.SEMI_BOLD) self._button_style = button_style self._border_radius = border_radius - self._font_size = font_size - self._font_weight = font_weight - self._text_color = BUTTON_TEXT_COLOR[button_style] - self._background_color = BUTTON_BACKGROUND_COLORS[button_style] - self._text_alignment = text_alignment - self._text_padding = text_padding - self._text_size = measure_text_cached(gui_app.font(self._font_weight), self._text, self._font_size) - self._icon = icon + self._background_color = BUTTON_BACKGROUND_COLORS[self._button_style] + + self._label = Label(text, font_size, font_weight, text_alignment, text_padding, + BUTTON_TEXT_COLOR[self._button_style], icon=icon) + + self._click_callback = click_callback self._multi_touch = multi_touch - self.enabled = enabled def set_text(self, text): - self._text = text - self._text_size = measure_text_cached(gui_app.font(self._font_weight), self._text, self._font_size) + self._label.set_text(text) def _handle_mouse_release(self, mouse_pos: MousePos): if self._click_callback and self.enabled: @@ -209,44 +196,20 @@ class Button(Widget): def _update_state(self): if self.enabled: - self._text_color = BUTTON_TEXT_COLOR[self._button_style] + self._label.set_text_color(BUTTON_TEXT_COLOR[self._button_style]) if self.is_pressed: self._background_color = BUTTON_PRESSED_BACKGROUND_COLORS[self._button_style] else: self._background_color = BUTTON_BACKGROUND_COLORS[self._button_style] elif self._button_style != ButtonStyle.NO_EFFECT: self._background_color = BUTTON_DISABLED_BACKGROUND_COLOR - self._text_color = BUTTON_DISABLED_TEXT_COLOR + self._label.set_text_color(BUTTON_DISABLED_TEXT_COLOR) def _render(self, _): roundness = self._border_radius / (min(self._rect.width, self._rect.height) / 2) rl.draw_rectangle_rounded(self._rect, roundness, 10, self._background_color) + self._label.render(self._rect) - text_pos = rl.Vector2(0, self._rect.y + (self._rect.height - self._text_size.y) // 2) - if self._icon: - icon_y = self._rect.y + (self._rect.height - self._icon.height) / 2 - if self._text: - if self._text_alignment == TextAlignment.LEFT: - icon_x = self._rect.x + self._text_padding - text_pos.x = icon_x + self._icon.width + ICON_PADDING - elif self._text_alignment == TextAlignment.CENTER: - total_width = self._icon.width + ICON_PADDING + self._text_size.x - icon_x = self._rect.x + (self._rect.width - total_width) / 2 - text_pos.x = icon_x + self._icon.width + ICON_PADDING - else: - text_pos.x = self._rect.x + self._rect.width - self._text_size.x - self._text_padding - icon_x = text_pos.x - ICON_PADDING - self._icon.width - else: - icon_x = self._rect.x + (self._rect.width - self._icon.width) / 2 - rl.draw_texture_v(self._icon, rl.Vector2(icon_x, icon_y), rl.WHITE if self.enabled else rl.Color(255, 255, 255, 100)) - else: - if self._text_alignment == TextAlignment.LEFT: - text_pos.x = self._rect.x + self._text_padding - elif self._text_alignment == TextAlignment.CENTER: - text_pos.x = self._rect.x + (self._rect.width - self._text_size.x) // 2 - elif self._text_alignment == TextAlignment.RIGHT: - text_pos.x = self._rect.x + self._rect.width - self._text_size.x - self._text_padding - rl.draw_text_ex(self._label_font, self._text, text_pos, self._font_size, 0, self._text_color) class ButtonRadio(Button): def __init__(self, @@ -254,11 +217,16 @@ class ButtonRadio(Button): icon, click_callback: Callable[[], None] = None, font_size: int = DEFAULT_BUTTON_FONT_SIZE, + text_alignment: TextAlignment = TextAlignment.LEFT, border_radius: int = 10, text_padding: int = 20, ): - super().__init__(text, click_callback=click_callback, font_size=font_size, border_radius=border_radius, text_padding=text_padding, icon=icon) + super().__init__(text, click_callback=click_callback, font_size=font_size, + border_radius=border_radius, text_padding=text_padding, + text_alignment=text_alignment) + self._text_padding = text_padding + self._icon = icon self.selected = False def _handle_mouse_release(self, mouse_pos: MousePos): @@ -275,10 +243,7 @@ class ButtonRadio(Button): def _render(self, _): roundness = self._border_radius / (min(self._rect.width, self._rect.height) / 2) rl.draw_rectangle_rounded(self._rect, roundness, 10, self._background_color) - - text_pos = rl.Vector2(0, self._rect.y + (self._rect.height - self._text_size.y) // 2) - text_pos.x = self._rect.x + self._text_padding - rl.draw_text_ex(self._label_font, self._text, text_pos, self._font_size, 0, self._text_color) + self._label.render(self._rect) if self._icon and self.selected: icon_y = self._rect.y + (self._rect.height - self._icon.height) / 2 diff --git a/system/ui/widgets/confirm_dialog.py b/system/ui/widgets/confirm_dialog.py index f0d638131d..1021b5452b 100644 --- a/system/ui/widgets/confirm_dialog.py +++ b/system/ui/widgets/confirm_dialog.py @@ -2,7 +2,7 @@ import pyray as rl from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.widgets import DialogResult from openpilot.system.ui.widgets.button import gui_button, ButtonStyle, Button -from openpilot.system.ui.widgets.label import gui_text_box +from openpilot.system.ui.widgets.label import gui_text_box, Label from openpilot.system.ui.widgets import Widget DIALOG_WIDTH = 1520 @@ -15,12 +15,15 @@ BACKGROUND_COLOR = rl.Color(27, 27, 27, 255) class ConfirmDialog(Widget): def __init__(self, text: str, confirm_text: str, cancel_text: str = "Cancel"): super().__init__() - self.text = text + self._label = Label(text, 70, FontWeight.BOLD) self._cancel_button = Button(cancel_text, self._cancel_button_callback) self._confirm_button = Button(confirm_text, self._confirm_button_callback, button_style=ButtonStyle.PRIMARY) self._dialog_result = DialogResult.NO_ACTION self._cancel_text = cancel_text + def set_text(self, text): + self._label.set_text(text) + def reset(self): self._dialog_result = DialogResult.NO_ACTION @@ -46,14 +49,7 @@ class ConfirmDialog(Widget): rl.draw_rectangle_rec(dialog_rect, BACKGROUND_COLOR) text_rect = rl.Rectangle(dialog_rect.x + MARGIN, dialog_rect.y, dialog_rect.width - 2 * MARGIN, dialog_rect.height - TEXT_AREA_HEIGHT_REDUCTION) - gui_text_box( - text_rect, - self.text, - font_size=70, - alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER, - alignment_vertical=rl.GuiTextAlignmentVertical.TEXT_ALIGN_MIDDLE, - font_weight=FontWeight.BOLD, - ) + self._label.render(text_rect) if rl.is_key_pressed(rl.KeyboardKey.KEY_ENTER): self._dialog_result = DialogResult.CONFIRM diff --git a/system/ui/widgets/inputbox.py b/system/ui/widgets/inputbox.py index 65428479bf..239d63037e 100644 --- a/system/ui/widgets/inputbox.py +++ b/system/ui/widgets/inputbox.py @@ -1,6 +1,6 @@ import pyray as rl import time -from openpilot.system.ui.lib.application import gui_app +from openpilot.system.ui.lib.application import gui_app, MousePos from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.widgets import Widget @@ -107,9 +107,6 @@ class InputBox(Widget): self._visible_width = rect.width self._font_size = font_size - # Handle mouse input - self._handle_mouse_input(rect, font_size) - # Draw input box rl.draw_rectangle_rec(rect, color) @@ -169,30 +166,27 @@ class InputBox(Widget): return masked_text - def _handle_mouse_input(self, rect, font_size): - """Handle mouse clicks to position cursor.""" - mouse_pos = rl.get_mouse_position() - if rl.is_mouse_button_pressed(rl.MouseButton.MOUSE_BUTTON_LEFT) and rl.check_collision_point_rec(mouse_pos, rect): - # Calculate cursor position from click - if len(self._input_text) > 0: - font = gui_app.font() - display_text = self._get_display_text() - - # Find the closest character position to the click - relative_x = mouse_pos.x - (rect.x + 10) + self._text_offset - best_pos = 0 - min_distance = float('inf') - - for i in range(len(self._input_text) + 1): - char_width = measure_text_cached(font, display_text[:i], font_size).x - distance = abs(relative_x - char_width) - if distance < min_distance: - min_distance = distance - best_pos = i - - self.set_cursor_position(best_pos) - else: - self.set_cursor_position(0) + def _handle_mouse_release(self, mouse_pos: MousePos): + # Calculate cursor position from click + if len(self._input_text) > 0: + font = gui_app.font() + display_text = self._get_display_text() + + # Find the closest character position to the click + relative_x = mouse_pos.x - (self._rect.x + 10) + self._text_offset + best_pos = 0 + min_distance = float('inf') + + for i in range(len(self._input_text) + 1): + char_width = measure_text_cached(font, display_text[:i], self._font_size).x + distance = abs(relative_x - char_width) + if distance < min_distance: + min_distance = distance + best_pos = i + + self.set_cursor_position(best_pos) + else: + self.set_cursor_position(0) def _handle_keyboard_input(self): # Handle navigation keys diff --git a/system/ui/widgets/keyboard.py b/system/ui/widgets/keyboard.py index 388d7e2664..25843d1ce8 100644 --- a/system/ui/widgets/keyboard.py +++ b/system/ui/widgets/keyboard.py @@ -8,7 +8,7 @@ from openpilot.system.ui.lib.application import gui_app, FontWeight from openpilot.system.ui.widgets import Widget from openpilot.system.ui.widgets.button import ButtonStyle, Button from openpilot.system.ui.widgets.inputbox import InputBox -from openpilot.system.ui.widgets.label import gui_label +from openpilot.system.ui.widgets.label import Label, TextAlignment KEY_FONT_SIZE = 96 DOUBLE_CLICK_THRESHOLD = 0.5 # seconds @@ -62,8 +62,8 @@ class Keyboard(Widget): self._layout_name: Literal["lowercase", "uppercase", "numbers", "specials"] = "lowercase" self._caps_lock = False self._last_shift_press_time = 0 - self._title = "" - self._sub_title = "" + self._title = Label("", 90, FontWeight.BOLD, TextAlignment.LEFT) + self._sub_title = Label("", 55, FontWeight.NORMAL, TextAlignment.LEFT) self._max_text_size = max_text_size self._min_text_size = min_text_size @@ -115,8 +115,8 @@ class Keyboard(Widget): self._backspace_pressed = False def set_title(self, title: str, sub_title: str = ""): - self._title = title - self._sub_title = sub_title + self._title.set_text(title) + self._sub_title.set_text(sub_title) def _eye_button_callback(self): self._password_mode = not self._password_mode @@ -133,8 +133,8 @@ class Keyboard(Widget): def _render(self, rect: rl.Rectangle): rect = rl.Rectangle(rect.x + CONTENT_MARGIN, rect.y + CONTENT_MARGIN, rect.width - 2 * CONTENT_MARGIN, rect.height - 2 * CONTENT_MARGIN) - gui_label(rl.Rectangle(rect.x, rect.y, rect.width, 95), self._title, 90, font_weight=FontWeight.BOLD) - gui_label(rl.Rectangle(rect.x, rect.y + 95, rect.width, 60), self._sub_title, 55, font_weight=FontWeight.NORMAL) + self._title.render(rl.Rectangle(rect.x, rect.y, rect.width, 95)) + self._sub_title.render(rl.Rectangle(rect.x, rect.y + 95, rect.width, 60)) self._cancel_button.render(rl.Rectangle(rect.x + rect.width - 386, rect.y, 386, 125)) # Draw input box and password toggle @@ -187,10 +187,10 @@ class Keyboard(Widget): if key in self._key_icons: if key == SHIFT_ACTIVE_KEY and self._caps_lock: key = CAPS_LOCK_KEY - self._all_keys[key].enabled = is_enabled + self._all_keys[key].set_enabled(is_enabled) self._all_keys[key].render(key_rect) else: - self._all_keys[key].enabled = is_enabled + self._all_keys[key].set_enabled(is_enabled) self._all_keys[key].render(key_rect) return self._render_return_status diff --git a/system/ui/widgets/label.py b/system/ui/widgets/label.py index e840e8586a..2da9a9f8df 100644 --- a/system/ui/widgets/label.py +++ b/system/ui/widgets/label.py @@ -1,11 +1,23 @@ +from enum import IntEnum +from itertools import zip_longest + import pyray as rl + from openpilot.system.ui.lib.application import gui_app, FontWeight, DEFAULT_TEXT_SIZE, DEFAULT_TEXT_COLOR from openpilot.system.ui.lib.text_measure import measure_text_cached from openpilot.system.ui.lib.utils import GuiStyleContext +from openpilot.system.ui.lib.emoji import find_emoji, emoji_tex +from openpilot.system.ui.lib.wrap_text import wrap_text +from openpilot.system.ui.widgets import Widget +ICON_PADDING = 15 -# TODO: This should be a Widget class +class TextAlignment(IntEnum): + LEFT = 0 + CENTER = 1 + RIGHT = 2 +# TODO: This should be a Widget class def gui_label( rect: rl.Rectangle, text: str, @@ -78,3 +90,88 @@ def gui_text_box( if font_weight != FontWeight.NORMAL: rl.gui_set_font(gui_app.font(FontWeight.NORMAL)) + + +# Non-interactive text area. Can render emojis and an optional specified icon. +class Label(Widget): + def __init__(self, + text: str, + font_size: int = DEFAULT_TEXT_SIZE, + font_weight: FontWeight = FontWeight.NORMAL, + text_alignment: TextAlignment = TextAlignment.CENTER, + text_padding: int = 20, + text_color: rl.Color = DEFAULT_TEXT_COLOR, + icon = None, + ): + + super().__init__() + self._font_weight = font_weight + self._font = gui_app.font(self._font_weight) + self._font_size = font_size + self._text_alignment = text_alignment + self._text_padding = text_padding + self._text_color = text_color + self._icon = icon + self.set_text(text) + + def set_text(self, text): + self._text_raw = text + self._update_text(self._text_raw) + + def set_text_color(self, color): + self._text_color = color + + def _update_layout_rects(self): + self._update_text(self._text_raw) + + def _update_text(self, text): + self._emojis = [] + self._text_size = [] + self._text = wrap_text(self._font, text, self._font_size, self._rect.width - (self._text_padding*2)) + for t in self._text: + self._emojis.append(find_emoji(t)) + self._text_size.append(measure_text_cached(self._font, t, self._font_size)) + + def _render(self, _): + text = self._text[0] if self._text else None + text_size = self._text_size[0] if self._text_size else rl.Vector2(0.0, 0.0) + text_pos = rl.Vector2(0, (self._rect.y + (self._rect.height - (text_size.y)) // 2)) + + if self._icon: + icon_y = self._rect.y + (self._rect.height - self._icon.height) / 2 + if text: + if self._text_alignment == TextAlignment.LEFT: + icon_x = self._rect.x + self._text_padding + text_pos.x = self._icon.width + ICON_PADDING + elif self._text_alignment == TextAlignment.CENTER: + total_width = self._icon.width + ICON_PADDING + text_size.x + icon_x = self._rect.x + (self._rect.width - total_width) / 2 + text_pos.x = self._icon.width + ICON_PADDING + else: + icon_x = (self._rect.x + self._rect.width - text_size.x - self._text_padding) - ICON_PADDING - self._icon.width + else: + icon_x = self._rect.x + (self._rect.width - self._icon.width) / 2 + rl.draw_texture_v(self._icon, rl.Vector2(icon_x, icon_y), rl.WHITE) + + for text, text_size, emojis in zip_longest(self._text, self._text_size, self._emojis, fillvalue=[]): + line_pos = rl.Vector2(text_pos.x, text_pos.y) + if self._text_alignment == TextAlignment.LEFT: + line_pos.x += self._rect.x + self._text_padding + elif self._text_alignment == TextAlignment.CENTER: + line_pos.x += self._rect.x + (self._rect.width - text_size.x) // 2 + elif self._text_alignment == TextAlignment.RIGHT: + line_pos.x += self._rect.x + self._rect.width - text_size.x - self._text_padding + + prev_index = 0 + for start, end, emoji in emojis: + text_before = text[prev_index:start] + width_before = measure_text_cached(self._font, text_before, self._font_size) + rl.draw_text_ex(self._font, text_before, line_pos, self._font_size, 0, self._text_color) + line_pos.x += width_before.x + + tex = emoji_tex(emoji) + rl.draw_texture_ex(tex, line_pos, 0.0, self._font_size / tex.height, self._text_color) + line_pos.x += self._font_size + prev_index = end + rl.draw_text_ex(self._font, text[prev_index:], line_pos, self._font_size, 0, self._text_color) + text_pos.y += text_size.y or self._font_size diff --git a/system/ui/widgets/network.py b/system/ui/widgets/network.py index 0eda418c17..0bb759a919 100644 --- a/system/ui/widgets/network.py +++ b/system/ui/widgets/network.py @@ -1,17 +1,17 @@ -from dataclasses import dataclass +from enum import IntEnum from functools import partial from threading import Lock -from typing import Literal +from typing import cast import pyray as rl from openpilot.system.ui.lib.application import gui_app 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.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.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 MIN_PASSWORD_LENGTH = 8 @@ -27,43 +27,20 @@ STRENGTH_ICONS = [ ] -@dataclass -class StateIdle: - action: Literal["idle"] = "idle" - - -@dataclass -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 UIState(IntEnum): + IDLE = 0 + CONNECTING = 1 + NEEDS_AUTH = 2 + SHOW_FORGET_CONFIRM = 3 + FORGETTING = 4 class WifiManagerUI(Widget): def __init__(self, wifi_manager: WifiManagerWrapper): super().__init__() - self.state: UIState = StateIdle() + self.state: UIState = UIState.IDLE + self._state_network: NetworkInfo | None = None # for CONNECTING / NEEDS_AUTH / SHOW_FORGET_CONFIRM / FORGETTING + self._password_retry: bool = False # for NEEDS_AUTH self.btn_width: int = 200 self.scroll_panel = GuiScrollPanel() self.keyboard = Keyboard(max_text_size=MAX_PASSWORD_LENGTH, min_text_size=MIN_PASSWORD_LENGTH, show_password_toggle=True) @@ -93,17 +70,16 @@ class WifiManagerUI(Widget): gui_label(rect, "Scanning Wi-Fi networks...", 72, alignment=rl.GuiTextAlignment.TEXT_ALIGN_CENTER) return - match self.state: - case StateNeedsAuth(network, retry): - self.keyboard.set_title("Wrong password" if retry else "Enter password", f"for {network.ssid}") - self.keyboard.reset() - gui_app.set_modal_overlay(self.keyboard, lambda result: self._on_password_entered(network, result)) - case StateShowForgetConfirm(network): - self._confirm_dialog.text = f'Forget Wi-Fi Network "{network.ssid}"?' - self._confirm_dialog.reset() - gui_app.set_modal_overlay(self._confirm_dialog, callback=lambda result: self.on_forgot_confirm_finished(network, result)) - case _: - self._draw_network_list(rect) + if self.state == UIState.NEEDS_AUTH and self._state_network: + self.keyboard.set_title("Wrong password" if self._password_retry else "Enter password", f"for {self._state_network.ssid}") + self.keyboard.reset() + gui_app.set_modal_overlay(self.keyboard, lambda result: self._on_password_entered(cast(NetworkInfo, self._state_network), result)) + elif self.state == UIState.SHOW_FORGET_CONFIRM and self._state_network: + self._confirm_dialog.set_text(f'Forget Wi-Fi Network "{self._state_network.ssid}"?') + self._confirm_dialog.reset() + gui_app.set_modal_overlay(self._confirm_dialog, callback=lambda result: self.on_forgot_confirm_finished(self._state_network, result)) + else: + self._draw_network_list(rect) def _on_password_entered(self, network: NetworkInfo, result: int): if result == 1: @@ -113,13 +89,13 @@ class WifiManagerUI(Widget): if len(password) >= MIN_PASSWORD_LENGTH: self.connect_to_network(network, password) elif result == 0: - self.state = StateIdle() + self.state = UIState.IDLE def on_forgot_confirm_finished(self, network, result: int): if result == 1: self.forget_network(network) elif result == 0: - self.state = StateIdle() + self.state = UIState.IDLE def _draw_network_list(self, rect: rl.Rectangle): content_rect = rl.Rectangle(rect.x, rect.y, rect.width, len(self._networks) * ITEM_HEIGHT) @@ -147,17 +123,18 @@ class WifiManagerUI(Widget): 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 = "" - match self.state: - case StateConnecting(network=connecting): - if connecting.ssid == network.ssid: - self._networks_buttons[network.ssid].enabled = False - status_text = "CONNECTING..." - case StateForgetting(network=forgetting): - if forgetting.ssid == network.ssid: - self._networks_buttons[network.ssid].enabled = False - status_text = "FORGETTING..." - case _: - self._networks_buttons[network.ssid].enabled = True + if self.state == UIState.CONNECTING and self._state_network: + if self._state_network.ssid == network.ssid: + self._networks_buttons[network.ssid].set_enabled(False) + status_text = "CONNECTING..." + elif self.state == UIState.FORGETTING and self._state_network: + if self._state_network.ssid == network.ssid: + self._networks_buttons[network.ssid].set_enabled(False) + status_text = "FORGETTING..." + elif network.security_type == SecurityType.UNSUPPORTED: + self._networks_buttons[network.ssid].set_enabled(False) + else: + self._networks_buttons[network.ssid].set_enabled(True) self._networks_buttons[network.ssid].render(ssid_rect) @@ -181,14 +158,16 @@ class WifiManagerUI(Widget): def _networks_buttons_callback(self, network): if self.scroll_panel.is_touch_valid(): 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: self.connect_to_network(network) def _forget_networks_buttons_callback(self, network): if self.scroll_panel.is_touch_valid(): - if isinstance(self.state, StateIdle): - self.state = StateShowForgetConfirm(network) + self.state = UIState.SHOW_FORGET_CONFIRM + self._state_network = network def _draw_status_icon(self, rect, network: NetworkInfo): """Draw the status icon based on network's connection state""" @@ -213,14 +192,16 @@ class WifiManagerUI(Widget): 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=''): - self.state = StateConnecting(network) + self.state = UIState.CONNECTING + self._state_network = network if network.is_saved and not password: self.wifi_manager.activate_connection(network.ssid) else: self.wifi_manager.connect_to_network(network.ssid, password) def forget_network(self, network: NetworkInfo): - self.state = StateForgetting(network) + self.state = UIState.FORGETTING + self._state_network = network network.is_saved = False self.wifi_manager.forget_connection(network.ssid) @@ -237,22 +218,24 @@ class WifiManagerUI(Widget): with self._lock: network = next((n for n in self._networks if n.ssid == ssid), None) if network: - self.state = StateNeedsAuth(network, True) + self.state = UIState.NEEDS_AUTH + self._state_network = network + self._password_retry = True def _on_activated(self): with self._lock: - if isinstance(self.state, StateConnecting): - self.state = StateIdle() + if self.state == UIState.CONNECTING: + self.state = UIState.IDLE def _on_forgotten(self, ssid): with self._lock: - if isinstance(self.state, StateForgetting): - self.state = StateIdle() + if self.state == UIState.FORGETTING: + self.state = UIState.IDLE def _on_connection_failed(self, ssid: str, error: str): with self._lock: - if isinstance(self.state, StateConnecting): - self.state = StateIdle() + if self.state == UIState.CONNECTING: + self.state = UIState.IDLE def main(): diff --git a/system/ui/widgets/toggle.py b/system/ui/widgets/toggle.py index 3f7f463916..eba5ef9e58 100644 --- a/system/ui/widgets/toggle.py +++ b/system/ui/widgets/toggle.py @@ -38,9 +38,6 @@ class Toggle(Widget): self._state = state self._target = 1.0 if state else 0.0 - def set_enabled(self, enabled: bool): - self._enabled = enabled - def is_enabled(self): return self._enabled diff --git a/system/updated/updated.py b/system/updated/updated.py index 1fd9e8b717..11928bc24c 100755 --- a/system/updated/updated.py +++ b/system/updated/updated.py @@ -242,6 +242,9 @@ class Updater: b: str | None = self.params.get("UpdaterTargetBranch") if b is None: b = self.get_branch(BASEDIR) + b = { + ("tici", "release3"): "release-tici" + }.get((HARDWARE.get_device_type(), b), b) return b @property @@ -283,8 +286,8 @@ class Updater: self.params.put("LastUpdateUptimeOnroad", last_uptime_onroad) self.params.put("LastUpdateRouteCount", last_route_count) else: - last_uptime_onroad = self.params.get("LastUpdateUptimeOnroad") or last_uptime_onroad - last_route_count = self.params.get("LastUpdateRouteCount") or last_route_count + last_uptime_onroad = self.params.get("LastUpdateUptimeOnroad", return_default=True) + last_route_count = self.params.get("LastUpdateRouteCount", return_default=True) if exception is None: self.params.remove("LastUpdateException") diff --git a/system/version.py b/system/version.py index cd0e2d7f38..5e4fcf5c33 100755 --- a/system/version.py +++ b/system/version.py @@ -10,7 +10,7 @@ from openpilot.common.basedir import BASEDIR from openpilot.common.swaglog import cloudlog from openpilot.common.git import get_commit, get_origin, get_branch, get_short_branch, get_commit_date -RELEASE_BRANCHES = ['release3-staging', 'release3', 'nightly'] +RELEASE_BRANCHES = ['release3-staging', 'release3', 'release-tici', 'nightly'] TESTED_BRANCHES = RELEASE_BRANCHES + ['devel', 'devel-staging', 'nightly-dev'] BUILD_METADATA_FILENAME = "build.json" diff --git a/tinygrad_repo b/tinygrad_repo index 06af9f9236..c30a113b2a 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit 06af9f9236b33419f89ef3b3a5ba4cce0adecc2d +Subproject commit c30a113b2a876cabaea1049601fea3a0b758c5b1 diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index b817ae1208..c857c9ffbe 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -19,7 +19,7 @@ const int THUMBNAIL_MARGIN = 3; static const QColor timeline_colors[] = { [(int)TimelineType::None] = QColor(111, 143, 175), [(int)TimelineType::Engaged] = QColor(0, 163, 108), - [(int)TimelineType::UserFlag] = Qt::magenta, + [(int)TimelineType::UserBookmark] = Qt::magenta, [(int)TimelineType::AlertInfo] = Qt::green, [(int)TimelineType::AlertWarning] = QColor(255, 195, 0), [(int)TimelineType::AlertCritical] = QColor(199, 0, 57), @@ -64,7 +64,7 @@ VideoWidget::VideoWidget(QWidget *parent) : QFrame(parent) { Pause/Resume:  space  )").arg(timeline_colors[(int)TimelineType::None].name(), timeline_colors[(int)TimelineType::Engaged].name(), - timeline_colors[(int)TimelineType::UserFlag].name(), + timeline_colors[(int)TimelineType::UserBookmark].name(), timeline_colors[(int)TimelineType::AlertInfo].name(), timeline_colors[(int)TimelineType::AlertWarning].name(), timeline_colors[(int)TimelineType::AlertCritical].name())); diff --git a/tools/camerastream/compressed_vipc.py b/tools/camerastream/compressed_vipc.py index b25b8b0cb7..4dc74272ea 100755 --- a/tools/camerastream/compressed_vipc.py +++ b/tools/camerastream/compressed_vipc.py @@ -107,7 +107,7 @@ def decoder(addr, vipc_server, vst, nvidia, W, H, debug=False): class CompressedVipc: - def __init__(self, addr, vision_streams, nvidia=False, debug=False): + def __init__(self, addr, vision_streams, server_name, nvidia=False, debug=False): print("getting frame sizes") os.environ["ZMQ"] = "1" messaging.reset_context() @@ -117,7 +117,7 @@ class CompressedVipc: os.environ.pop("ZMQ") messaging.reset_context() - self.vipc_server = VisionIpcServer("camerad") + self.vipc_server = VisionIpcServer(server_name) for vst in vision_streams: ed = sm[ENCODE_SOCKETS[vst]] self.vipc_server.create_buffers(vst, 4, ed.width, ed.height) @@ -144,6 +144,7 @@ if __name__ == "__main__": parser.add_argument("addr", help="Address of comma three") parser.add_argument("--nvidia", action="store_true", help="Use nvidia instead of ffmpeg") parser.add_argument("--cams", default="0,1,2", help="Cameras to decode") + parser.add_argument("--server", default="camerad", help="choose vipc server name") parser.add_argument("--silent", action="store_true", help="Suppress debug output") args = parser.parse_args() @@ -154,7 +155,7 @@ if __name__ == "__main__": ] vsts = [vision_streams[int(x)] for x in args.cams.split(",")] - cvipc = CompressedVipc(args.addr, vsts, args.nvidia, debug=(not args.silent)) + cvipc = CompressedVipc(args.addr, vsts, args.server, args.nvidia, debug=(not args.silent)) # register exit handler signal.signal(signal.SIGINT, lambda sig, frame: cvipc.kill()) diff --git a/tools/clip/run.py b/tools/clip/run.py index a84290f9c4..8fa0e8eda3 100755 --- a/tools/clip/run.py +++ b/tools/clip/run.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 -import atexit import logging import os import platform @@ -11,13 +10,14 @@ from argparse import ArgumentParser, ArgumentTypeError from collections.abc import Sequence from pathlib import Path from random import randint -from subprocess import Popen, PIPE +from subprocess import Popen from typing import Literal from cereal.messaging import SubMaster from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params, UnknownKeyName from openpilot.common.prefix import OpenpilotPrefix +from openpilot.common.run import managed_proc from openpilot.tools.lib.route import Route from openpilot.tools.lib.logreader import LogReader @@ -29,7 +29,7 @@ FRAMERATE = 20 PIXEL_DEPTH = '24' RESOLUTION = '2160x1080' SECONDS_TO_WARM = 2 -PROC_WAIT_SECONDS = 30 +PROC_WAIT_SECONDS = 30*10 OPENPILOT_FONT = str(Path(BASEDIR, 'selfdrive/assets/fonts/Inter-Regular.ttf').resolve()) REPLAY = str(Path(BASEDIR, 'tools/replay/replay').resolve()) @@ -38,22 +38,23 @@ UI = str(Path(BASEDIR, 'selfdrive/ui/ui').resolve()) logger = logging.getLogger('clip.py') -def check_for_failure(proc: Popen): - exit_code = proc.poll() - if exit_code is not None and exit_code != 0: - cmd = str(proc.args) - if isinstance(proc.args, str): - cmd = proc.args - elif isinstance(proc.args, Sequence): - cmd = str(proc.args[0]) - msg = f'{cmd} failed, exit code {exit_code}' - logger.error(msg) - stdout, stderr = proc.communicate() - if stdout: - logger.error(stdout.decode()) - if stderr: - logger.error(stderr.decode()) - raise ChildProcessError(msg) +def check_for_failure(procs: list[Popen]): + for proc in procs: + exit_code = proc.poll() + if exit_code is not None and exit_code != 0: + cmd = str(proc.args) + if isinstance(proc.args, str): + cmd = proc.args + elif isinstance(proc.args, Sequence): + cmd = str(proc.args[0]) + msg = f'{cmd} failed, exit code {exit_code}' + logger.error(msg) + stdout, stderr = proc.communicate() + if stdout: + logger.error(stdout.decode()) + if stderr: + logger.error(stderr.decode()) + raise ChildProcessError(msg) def escape_ffmpeg_text(value: str): @@ -130,17 +131,13 @@ def populate_car_params(lr: LogReader): for cp in entries: key, value = cp.key, cp.value try: - params.put(key, value) + params.put(key, params.cpp2python(key, value)) except UnknownKeyName: # forks of openpilot may have other Params keys configured. ignore these logger.warning(f"unknown Params key '{key}', skipping") logger.debug('persisted CarParams') -def start_proc(args: list[str], env: dict[str, str]): - return Popen(args, env=env, stdout=PIPE, stderr=PIPE) - - def validate_env(parser: ArgumentParser): if platform.system() not in ['Linux']: parser.exit(1, f'clip.py: error: {platform.system()} is not a supported operating system\n') @@ -176,8 +173,7 @@ def wait_for_frames(procs: list[Popen]): while no_frames_drawn: sm.update() no_frames_drawn = sm['uiDebug'].drawTimeMillis == 0. - for proc in procs: - check_for_failure(proc) + check_for_failure(procs) def clip( @@ -188,6 +184,7 @@ def clip( out: str, start: int, end: int, + speed: int, target_mb: int, title: str | None, ): @@ -212,6 +209,12 @@ def clip( if title: overlays.append(f"drawtext=text='{escape_ffmpeg_text(title)}':fontfile={OPENPILOT_FONT}:fontcolor=white:fontsize=32:{box_style}:x=(w-text_w)/2:y=53") + if speed > 1: + overlays += [ + f"setpts=PTS/{speed}", + "fps=60", + ] + ffmpeg_cmd = [ 'ffmpeg', '-y', '-video_size', RESOLUTION, @@ -246,35 +249,22 @@ def clip( with OpenpilotPrefix(prefix, shared_download_cache=True): populate_car_params(lr) - env = os.environ.copy() env['DISPLAY'] = display - xvfb_proc = start_proc(xvfb_cmd, env) - atexit.register(lambda: xvfb_proc.terminate()) - ui_proc = start_proc(ui_cmd, env) - atexit.register(lambda: ui_proc.terminate()) - replay_proc = start_proc(replay_cmd, env) - atexit.register(lambda: replay_proc.terminate()) - procs = [replay_proc, ui_proc, xvfb_proc] - - logger.info('waiting for replay to begin (loading segments, may take a while)...') - wait_for_frames(procs) - - logger.debug(f'letting UI warm up ({SECONDS_TO_WARM}s)...') - time.sleep(SECONDS_TO_WARM) - for proc in procs: - check_for_failure(proc) - - ffmpeg_proc = start_proc(ffmpeg_cmd, env) - procs.append(ffmpeg_proc) - atexit.register(lambda: ffmpeg_proc.terminate()) - - logger.info(f'recording in progress ({duration}s)...') - ffmpeg_proc.wait(duration + PROC_WAIT_SECONDS) - for proc in procs: - check_for_failure(proc) - logger.info(f'recording complete: {Path(out).resolve()}') + with managed_proc(xvfb_cmd, env) as xvfb_proc, managed_proc(ui_cmd, env) as ui_proc, managed_proc(replay_cmd, env) as replay_proc: + procs = [xvfb_proc, ui_proc, replay_proc] + logger.info('waiting for replay to begin (loading segments, may take a while)...') + wait_for_frames(procs) + logger.debug(f'letting UI warm up ({SECONDS_TO_WARM}s)...') + time.sleep(SECONDS_TO_WARM) + check_for_failure(procs) + with managed_proc(ffmpeg_cmd, env) as ffmpeg_proc: + procs.append(ffmpeg_proc) + logger.info(f'recording in progress ({duration}s)...') + ffmpeg_proc.wait(duration + PROC_WAIT_SECONDS) + check_for_failure(procs) + logger.info(f'recording complete: {Path(out).resolve()}') def main(): @@ -289,6 +279,7 @@ def main(): p.add_argument('-o', '--output', help='output clip to (.mp4)', type=validate_output_file, default=DEFAULT_OUTPUT) p.add_argument('-p', '--prefix', help='openpilot prefix', default=f'clip_{randint(100, 99999)}') p.add_argument('-q', '--quality', help='quality of camera (low = qcam, high = hevc)', choices=['low', 'high'], default='high') + p.add_argument('-x', '--speed', help='record the clip at this speed multiple', type=int, default=1) p.add_argument('-s', '--start', help='start clipping at seconds', type=int) p.add_argument('-t', '--title', help='overlay this title on the video (e.g. "Chill driving across the Golden Gate Bridge")', type=validate_title) args = parse_args(p) @@ -302,6 +293,7 @@ def main(): out=args.output, start=args.start, end=args.end, + speed=args.speed, target_mb=args.file_size, title=args.title, ) @@ -310,9 +302,7 @@ def main(): logger.exception('interrupted by user', exc_info=e) except Exception as e: logger.exception('encountered error', exc_info=e) - finally: - atexit._run_exitfuncs() - sys.exit(exit_code) + sys.exit(exit_code) if __name__ == '__main__': diff --git a/tools/lib/file_sources.py b/tools/lib/file_sources.py new file mode 100755 index 0000000000..cb7bf15114 --- /dev/null +++ b/tools/lib/file_sources.py @@ -0,0 +1,57 @@ +from collections.abc import Callable + +from openpilot.tools.lib.comma_car_segments import get_url as get_comma_segments_url +from openpilot.tools.lib.openpilotci import get_url +from openpilot.tools.lib.filereader import DATA_ENDPOINT, file_exists, internal_source_available +from openpilot.tools.lib.route import Route, SegmentRange, FileName + +# When passed a tuple of file names, each source will return the first that exists (rlog.zst, rlog.bz2) +FileNames = tuple[str, ...] +Source = Callable[[SegmentRange, list[int], FileNames], dict[int, str]] + +InternalUnavailableException = Exception("Internal source not available") + + +def comma_api_source(sr: SegmentRange, seg_idxs: list[int], fns: FileNames) -> dict[int, str]: + route = Route(sr.route_name) + + # comma api will have already checked if the file exists + if fns == FileName.RLOG: + return {seg: route.log_paths()[seg] for seg in seg_idxs if route.log_paths()[seg] is not None} + else: + return {seg: route.qlog_paths()[seg] for seg in seg_idxs if route.qlog_paths()[seg] is not None} + + +def internal_source(sr: SegmentRange, seg_idxs: list[int], fns: FileNames, endpoint_url: str = DATA_ENDPOINT) -> dict[int, str]: + if not internal_source_available(endpoint_url): + raise InternalUnavailableException + + def get_internal_url(sr: SegmentRange, seg, file): + return f"{endpoint_url.rstrip('/')}/{sr.dongle_id}/{sr.log_id}/{seg}/{file}" + + return eval_source({seg: [get_internal_url(sr, seg, fn) for fn in fns] for seg in seg_idxs}) + + +def openpilotci_source(sr: SegmentRange, seg_idxs: list[int], fns: FileNames) -> dict[int, str]: + return eval_source({seg: [get_url(sr.route_name, seg, fn) for fn in fns] for seg in seg_idxs}) + + +def comma_car_segments_source(sr: SegmentRange, seg_idxs: list[int], fns: FileNames) -> dict[int, str]: + return eval_source({seg: get_comma_segments_url(sr.route_name, seg) for seg in seg_idxs}) + + +def eval_source(files: dict[int, list[str] | str]) -> dict[int, str]: + # Returns valid file URLs given a list of possible file URLs for each segment (e.g. rlog.bz2, rlog.zst) + valid_files: dict[int, str] = {} + + for seg_idx, urls in files.items(): + if isinstance(urls, str): + urls = [urls] + + # Add first valid file URL + for url in urls: + if file_exists(url): + valid_files[seg_idx] = url + break + + return valid_files diff --git a/tools/lib/logreader.py b/tools/lib/logreader.py index 1075bd2f08..8d84cdbd5d 100755 --- a/tools/lib/logreader.py +++ b/tools/lib/logreader.py @@ -12,17 +12,15 @@ import urllib.parse import warnings import zstandard as zstd -from collections.abc import Callable, Iterable, Iterator +from collections.abc import Iterable, Iterator from typing import cast from urllib.parse import parse_qs, urlparse from cereal import log as capnp_log from openpilot.common.swaglog import cloudlog -from openpilot.tools.lib.comma_car_segments import get_url as get_comma_segments_url -from openpilot.tools.lib.openpilotci import get_url -from openpilot.tools.lib.filereader import DATA_ENDPOINT, FileReader, file_exists, internal_source_available -from openpilot.tools.lib.route import QCAMERA_FILENAMES, CAMERA_FILENAMES, DCAMERA_FILENAMES, \ - ECAMERA_FILENAMES, BOOTLOG_FILENAMES, Route, SegmentRange +from openpilot.tools.lib.filereader import FileReader +from openpilot.tools.lib.file_sources import comma_api_source, internal_source, openpilotci_source, comma_car_segments_source, Source +from openpilot.tools.lib.route import SegmentRange, FileName from openpilot.tools.lib.log_time_series import msgs_to_time_series LogMessage = type[capnp._DynamicStructReader] @@ -41,6 +39,7 @@ def save_log(dest, log_msgs, compress=True): with open(dest, "wb") as f: f.write(dat) + def decompress_stream(data: bytes): dctx = zstd.ZstdDecompressor() decompressed_data = b"" @@ -50,8 +49,46 @@ def decompress_stream(data: bytes): return decompressed_data + +class CachedEventReader: + __slots__ = ('_evt', '_enum') + + def __init__(self, evt: capnp._DynamicStructReader, _enum: str | None = None): + """All capnp attribute accesses are expensive, and which() is often called multiple times""" + self._evt = evt + self._enum: str | None = _enum + + # fast pickle support + def __reduce__(self): + return CachedEventReader._reducer, (self._evt.as_builder().to_bytes(), self._enum) + + @staticmethod + def _reducer(data: bytes, _enum: str | None = None): + with capnp_log.Event.from_bytes(data) as evt: + return CachedEventReader(evt, _enum) + + def __repr__(self): + return self._evt.__repr__() + + def __str__(self): + return self._evt.__str__() + + def __dir__(self): + return dir(self._evt) + + def which(self) -> str: + if self._enum is None: + self._enum = self._evt.which() + return self._enum + + def __getattr__(self, name: str): + if name.startswith("__") and name.endswith("__"): + return getattr(self, name) + return getattr(self._evt, name) + + class _LogFileReader: - def __init__(self, fn, canonicalize=True, only_union_types=False, sort_by_time=False, dat=None): + def __init__(self, fn, only_union_types=False, sort_by_time=False, dat=None): self.data_version = None self._only_union_types = only_union_types @@ -76,7 +113,7 @@ class _LogFileReader: self._ents = [] try: for e in ents: - self._ents.append(e) + self._ents.append(CachedEventReader(e)) except capnp.KjException: warnings.warn("Corrupted events detected", RuntimeWarning, stacklevel=1) @@ -102,83 +139,22 @@ class ReadMode(enum.StrEnum): AUTO_INTERACTIVE = "i" # default to rlogs, fallback to qlogs with a prompt from the user -class FileName(enum.Enum): - #TODO use the ones from route.py - RLOG = ("rlog.zst", "rlog.bz2") - QLOG = ("qlog.zst", "qlog.bz2") - QCAMERA = QCAMERA_FILENAMES - FCAMERA = CAMERA_FILENAMES - ECAMERA = ECAMERA_FILENAMES - DCAMERA = DCAMERA_FILENAMES - BOOTLOG = BOOTLOG_FILENAMES - - -LogPath = str | None -Source = Callable[[SegmentRange, FileName], list[LogPath]] - -InternalUnavailableException = Exception("Internal source not available") - - class LogsUnavailable(Exception): pass -def comma_api_source(sr: SegmentRange, fns: FileName) -> list[LogPath]: - route = Route(sr.route_name) - - # comma api will have already checked if the file exists - if fns == FileName.RLOG: - return [route.log_paths()[seg] for seg in sr.seg_idxs] - else: - return [route.qlog_paths()[seg] for seg in sr.seg_idxs] - - -def internal_source(sr: SegmentRange, fns: FileName, endpoint_url: str = DATA_ENDPOINT) -> list[LogPath]: - if not internal_source_available(endpoint_url): - raise InternalUnavailableException - - def get_internal_url(sr: SegmentRange, seg, file): - return f"{endpoint_url.rstrip('/')}/{sr.dongle_id}/{sr.log_id}/{seg}/{file}" - - return eval_source([[get_internal_url(sr, seg, fn) for fn in fns.value] for seg in sr.seg_idxs]) - - -def openpilotci_source(sr: SegmentRange, fns: FileName) -> list[LogPath]: - return eval_source([[get_url(sr.route_name, seg, fn) for fn in fns.value] for seg in sr.seg_idxs]) - - -def comma_car_segments_source(sr: SegmentRange, fns: FileName) -> list[LogPath]: - return eval_source([get_comma_segments_url(sr.route_name, seg) for seg in sr.seg_idxs]) - - def direct_source(file_or_url: str) -> list[str]: return [file_or_url] -def eval_source(files: list[list[str] | str]) -> list[LogPath]: - # Returns valid file URLs given a list of possible file URLs for each segment (e.g. rlog.bz2, rlog.zst) - valid_files: list[LogPath] = [] - - for urls in files: - if isinstance(urls, str): - urls = [urls] - - for url in urls: - if file_exists(url): - valid_files.append(url) - break - else: - valid_files.append(None) - - return valid_files - - +# TODO this should apply to camera files as well def auto_source(identifier: str, sources: list[Source], default_mode: ReadMode) -> list[str]: exceptions = {} sr = SegmentRange(identifier) - mode = default_mode if sr.selector is None else ReadMode(sr.selector) + needed_seg_idxs = sr.seg_idxs + mode = default_mode if sr.selector is None else ReadMode(sr.selector) if mode == ReadMode.QLOG: try_fns = [FileName.QLOG] else: @@ -190,37 +166,35 @@ def auto_source(identifier: str, sources: list[Source], default_mode: ReadMode) # Build a dict of valid files as we evaluate each source. May contain mix of rlogs, qlogs, and None. # This function only returns when we've sourced all files, or throws an exception - valid_files: dict[int, LogPath] = {} + valid_files: dict[int, str] = {} for fn in try_fns: for source in sources: try: - files = source(sr, fn) - - # Check every source returns an expected number of files - assert len(files) == len(valid_files) or len(valid_files) == 0, f"Source {source.__name__} returned unexpected number of files" + files = source(sr, needed_seg_idxs, fn) # Build a dict of valid files - for idx, f in enumerate(files): - if valid_files.get(idx) is None: - valid_files[idx] = f + valid_files |= files + + # Don't check for segment files that have already been found + needed_seg_idxs = [idx for idx in needed_seg_idxs if idx not in valid_files] # We've found all files, return them - if all(f is not None for f in valid_files.values()): + if len(needed_seg_idxs) == 0: return cast(list[str], list(valid_files.values())) except Exception as e: exceptions[source.__name__] = e if fn == try_fns[0]: - missing_logs = list(valid_files.values()).count(None) + missing_logs = len(needed_seg_idxs) if mode == ReadMode.AUTO: - cloudlog.warning(f"{missing_logs}/{len(valid_files)} rlogs were not found, falling back to qlogs for those segments...") + cloudlog.warning(f"{missing_logs}/{len(sr.seg_idxs)} rlogs were not found, falling back to qlogs for those segments...") elif mode == ReadMode.AUTO_INTERACTIVE: - if input(f"{missing_logs}/{len(valid_files)} rlogs were not found, would you like to fallback to qlogs for those segments? (y/N) ").lower() != "y": + if input(f"{missing_logs}/{len(sr.seg_idxs)} rlogs were not found, would you like to fallback to qlogs for those segments? (y/N) ").lower() != "y": break - missing_logs = list(valid_files.values()).count(None) - raise LogsUnavailable(f"{missing_logs}/{len(valid_files)} logs were not found, please ensure all logs " + + missing_logs = len(needed_seg_idxs) + raise LogsUnavailable(f"{missing_logs}/{len(sr.seg_idxs)} logs were not found, please ensure all logs " + "are uploaded. You can fall back to qlogs with '/a' selector at the end of the route name.\n\n" + "Exceptions for sources:\n - " + "\n - ".join([f"{k}: {repr(v)}" for k, v in exceptions.items()])) @@ -271,7 +245,7 @@ class LogReader: def __init__(self, identifier: str | list[str], default_mode: ReadMode = ReadMode.RLOG, sources: list[Source] = None, sort_by_time=False, only_union_types=False): if sources is None: - sources = [internal_source, openpilotci_source, comma_api_source, comma_car_segments_source] + sources = [internal_source, comma_api_source, openpilotci_source, comma_car_segments_source] self.default_mode = default_mode self.sources = sources @@ -324,6 +298,7 @@ class LogReader: def time_series(self): return msgs_to_time_series(self) + if __name__ == "__main__": import codecs diff --git a/tools/lib/route.py b/tools/lib/route.py index 55ea956c5f..1fc26fb996 100644 --- a/tools/lib/route.py +++ b/tools/lib/route.py @@ -10,13 +10,15 @@ from openpilot.tools.lib.auth_config import get_token from openpilot.tools.lib.api import APIError, CommaApi from openpilot.tools.lib.helpers import RE -QLOG_FILENAMES = ('qlog.bz2', 'qlog.zst', 'qlog') -QCAMERA_FILENAMES = ('qcamera.ts',) -LOG_FILENAMES = ('rlog.bz2', 'raw_log.bz2', 'rlog.zst', 'rlog') -CAMERA_FILENAMES = ('fcamera.hevc', 'video.hevc') -DCAMERA_FILENAMES = ('dcamera.hevc',) -ECAMERA_FILENAMES = ('ecamera.hevc',) -BOOTLOG_FILENAMES = ('bootlog.zst', 'bootlog.bz2', 'bootlog') + +class FileName: + RLOG = ("rlog.zst", "rlog.bz2") + QLOG = ("qlog.zst", "qlog.bz2") + QCAMERA = ('qcamera.ts',) + FCAMERA = ('fcamera.hevc',) + ECAMERA = ('ecamera.hevc',) + DCAMERA = ('dcamera.hevc',) + BOOTLOG = ('bootlog.zst', 'bootlog.bz2') class Route: @@ -82,23 +84,23 @@ class Route: if segments.get(segment_name): segments[segment_name] = Segment( segment_name, - url if fn in LOG_FILENAMES else segments[segment_name].log_path, - url if fn in QLOG_FILENAMES else segments[segment_name].qlog_path, - url if fn in CAMERA_FILENAMES else segments[segment_name].camera_path, - url if fn in DCAMERA_FILENAMES else segments[segment_name].dcamera_path, - url if fn in ECAMERA_FILENAMES else segments[segment_name].ecamera_path, - url if fn in QCAMERA_FILENAMES else segments[segment_name].qcamera_path, + url if fn in FileName.RLOG else segments[segment_name].log_path, + url if fn in FileName.QLOG else segments[segment_name].qlog_path, + url if fn in FileName.FCAMERA else segments[segment_name].camera_path, + url if fn in FileName.DCAMERA else segments[segment_name].dcamera_path, + url if fn in FileName.ECAMERA else segments[segment_name].ecamera_path, + url if fn in FileName.QCAMERA else segments[segment_name].qcamera_path, self.metadata['url'], ) else: segments[segment_name] = Segment( segment_name, - url if fn in LOG_FILENAMES else None, - url if fn in QLOG_FILENAMES else None, - url if fn in CAMERA_FILENAMES else None, - url if fn in DCAMERA_FILENAMES else None, - url if fn in ECAMERA_FILENAMES else None, - url if fn in QCAMERA_FILENAMES else None, + url if fn in FileName.RLOG else None, + url if fn in FileName.QLOG else None, + url if fn in FileName.FCAMERA else None, + url if fn in FileName.DCAMERA else None, + url if fn in FileName.ECAMERA else None, + url if fn in FileName.QCAMERA else None, self.metadata['url'], ) @@ -136,32 +138,32 @@ class Route: for segment, files in segment_files.items(): try: - log_path = next(path for path, filename in files if filename in LOG_FILENAMES) + log_path = next(path for path, filename in files if filename in FileName.RLOG) except StopIteration: log_path = None try: - qlog_path = next(path for path, filename in files if filename in QLOG_FILENAMES) + qlog_path = next(path for path, filename in files if filename in FileName.QLOG) except StopIteration: qlog_path = None try: - camera_path = next(path for path, filename in files if filename in CAMERA_FILENAMES) + camera_path = next(path for path, filename in files if filename in FileName.FCAMERA) except StopIteration: camera_path = None try: - dcamera_path = next(path for path, filename in files if filename in DCAMERA_FILENAMES) + dcamera_path = next(path for path, filename in files if filename in FileName.DCAMERA) except StopIteration: dcamera_path = None try: - ecamera_path = next(path for path, filename in files if filename in ECAMERA_FILENAMES) + ecamera_path = next(path for path, filename in files if filename in FileName.ECAMERA) except StopIteration: ecamera_path = None try: - qcamera_path = next(path for path, filename in files if filename in QCAMERA_FILENAMES) + qcamera_path = next(path for path, filename in files if filename in FileName.QCAMERA) except StopIteration: qcamera_path = None @@ -229,7 +231,6 @@ class RouteName: def __str__(self) -> str: return self._canonical_name - class SegmentName: # TODO: add constructor that takes dongle_id, time_str, segment_num and then create instances # of this class instead of manually constructing a segment name (use canonical_name prop instead) @@ -250,7 +251,7 @@ class SegmentName: @property def canonical_name(self) -> str: return self._canonical_name - #TODO should only use one name + # TODO should only use one name @property def data_name(self) -> str: return f"{self._route_name.canonical_name}/{self._num}" @@ -281,7 +282,7 @@ class SegmentName: @staticmethod def from_file_name(file_name): # ??????/xxxxxxxxxxxxxxxx|1111-11-11-11--11-11-11/1/rlog.bz2 - dongle_id, route_name, segment_num = file_name.replace('|','/').split('/')[-4:-1] + dongle_id, route_name, segment_num = file_name.replace('|', '/').split('/')[-4:-1] return SegmentName(dongle_id + "|" + route_name + "--" + segment_num) @staticmethod @@ -302,6 +303,7 @@ class SegmentName: dongle_id, route_name, segment_num = prefix.split("/") return SegmentName(dongle_id + "|" + route_name + "--" + segment_num) + @cache def get_max_seg_number_cached(sr: 'SegmentRange') -> int: try: @@ -363,4 +365,3 @@ class SegmentRange: def __repr__(self) -> str: return self.__str__() - diff --git a/tools/lib/tests/test_logreader.py b/tools/lib/tests/test_logreader.py index 11bdd33ccf..8d0870171f 100644 --- a/tools/lib/tests/test_logreader.py +++ b/tools/lib/tests/test_logreader.py @@ -10,7 +10,8 @@ import requests from parameterized import parameterized from cereal import log as capnp_log -from openpilot.tools.lib.logreader import LogsUnavailable, LogIterable, LogReader, comma_api_source, parse_indirect, ReadMode, InternalUnavailableException +from openpilot.tools.lib.logreader import LogsUnavailable, LogIterable, LogReader, parse_indirect, ReadMode +from openpilot.tools.lib.file_sources import comma_api_source, InternalUnavailableException from openpilot.tools.lib.route import SegmentRange from openpilot.tools.lib.url_file import URLFileException @@ -36,12 +37,12 @@ def setup_source_scenario(mocker, is_internal=False): comma_api_source_mock.__name__ = comma_api_source_mock._mock_name if is_internal: - internal_source_mock.return_value = [QLOG_FILE] + internal_source_mock.return_value = {3: QLOG_FILE} else: internal_source_mock.side_effect = InternalUnavailableException - openpilotci_source_mock.return_value = [None] - comma_api_source_mock.return_value = [QLOG_FILE] + openpilotci_source_mock.return_value = {} + comma_api_source_mock.return_value = {3: QLOG_FILE} yield @@ -90,7 +91,7 @@ class TestLogReader: @pytest.mark.parametrize("cache_enabled", [True, False]) def test_direct_parsing(self, mocker, cache_enabled): - file_exists_mock = mocker.patch("openpilot.tools.lib.logreader.file_exists") + file_exists_mock = mocker.patch("openpilot.tools.lib.filereader.file_exists") os.environ["FILEREADER_CACHE"] = "1" if cache_enabled else "0" qlog = tempfile.NamedTemporaryFile(mode='wb', delete=False) @@ -208,13 +209,12 @@ class TestLogReader: assert qlog_len == log_len @pytest.mark.parametrize("is_internal", [True, False]) - @pytest.mark.slow def test_auto_source_scenarios(self, mocker, is_internal): lr = LogReader(QLOG_FILE) qlog_len = len(list(lr)) with setup_source_scenario(mocker, is_internal=is_internal): - lr = LogReader(f"{TEST_ROUTE}/0/q") + lr = LogReader(f"{TEST_ROUTE}/3/q") log_len = len(list(lr)) assert qlog_len == log_len diff --git a/tools/lib/url_file.py b/tools/lib/url_file.py index 204726363d..e80ba1399d 100644 --- a/tools/lib/url_file.py +++ b/tools/lib/url_file.py @@ -9,12 +9,14 @@ from urllib3.util import Timeout from openpilot.common.file_helpers import atomic_write_in_dir from openpilot.system.hardware.hw import Paths + # Cache chunk size K = 1000 CHUNK_SIZE = 1000 * K logging.getLogger("urllib3").setLevel(logging.WARNING) + def hash_256(link: str) -> str: return sha256((link.split("?")[0]).encode('utf-8')).hexdigest() @@ -24,7 +26,7 @@ class URLFileException(Exception): class URLFile: - _pool_manager: PoolManager|None = None + _pool_manager: PoolManager | None = None @staticmethod def reset() -> None: @@ -33,16 +35,16 @@ class URLFile: @staticmethod def pool_manager() -> PoolManager: if URLFile._pool_manager is None: - socket_options = [(socket.SOL_SOCKET, socket.SO_KEEPALIVE, 1),] + socket_options = [(socket.SOL_SOCKET, socket.SO_KEEPALIVE, 1)] retries = Retry(total=5, backoff_factor=0.5, status_forcelist=[409, 429, 503, 504]) URLFile._pool_manager = PoolManager(num_pools=10, maxsize=100, socket_options=socket_options, retries=retries) return URLFile._pool_manager - def __init__(self, url: str, timeout: int=10, debug: bool=False, cache: bool|None=None): + def __init__(self, url: str, timeout: int = 10, debug: bool = False, cache: bool | None = None): self._url = url self._timeout = Timeout(connect=timeout, read=timeout) self._pos = 0 - self._length: int|None = None + self._length: int | None = None self._debug = debug # True by default, false if FILEREADER_CACHE is defined, but can be overwritten by the cache input self._force_download = not int(os.environ.get("FILEREADER_CACHE", "0")) @@ -58,7 +60,7 @@ class URLFile: def __exit__(self, exc_type, exc_value, traceback) -> None: pass - def _request(self, method: str, url: str, headers: dict[str, str]|None=None) -> BaseHTTPResponse: + def _request(self, method: str, url: str, headers: dict[str, str] | None = None) -> BaseHTTPResponse: return URLFile.pool_manager().request(method, url, timeout=self._timeout, headers=headers) def get_length_online(self) -> int: @@ -85,7 +87,7 @@ class URLFile: file_length.write(str(self._length)) return self._length - def read(self, ll: int|None=None) -> bytes: + def read(self, ll: int | None = None) -> bytes: if self._force_download: return self.read_aux(ll=ll) @@ -117,7 +119,7 @@ class URLFile: self._pos = file_end return response - def read_aux(self, ll: int|None=None) -> bytes: + def read_aux(self, ll: int | None = None) -> bytes: download_range = False headers = {} if self._pos != 0 or ll is not None: @@ -152,7 +154,7 @@ class URLFile: self._pos += len(ret) return ret - def seek(self, pos:int) -> None: + def seek(self, pos: int) -> None: self._pos = pos @property diff --git a/tools/mac_setup.sh b/tools/mac_setup.sh index d23052d0f0..19ef77e01c 100755 --- a/tools/mac_setup.sh +++ b/tools/mac_setup.sh @@ -50,6 +50,7 @@ brew "zeromq" cask "gcc-arm-embedded" brew "portaudio" brew "gcc@13" +cask "font-noto-color-emoji" EOS echo "[ ] finished brew install t=$SECONDS" diff --git a/tools/plotjuggler/README.md b/tools/plotjuggler/README.md index 794c292e68..62905a252d 100644 --- a/tools/plotjuggler/README.md +++ b/tools/plotjuggler/README.md @@ -13,14 +13,13 @@ Once you've [set up the openpilot environment](../README.md), this command will ``` $ ./juggle.py -h usage: juggle.py [-h] [--demo] [--can] [--stream] [--layout [LAYOUT]] [--install] [--dbc DBC] - [route_or_segment_name] [segment_count] + [route_or_segment_name] A helper to run PlotJuggler on openpilot routes positional arguments: route_or_segment_name The route or segment name to plot (cabana share URL accepted) (default: None) - segment_count The number of segments to plot (default: None) optional arguments: -h, --help show this help message and exit @@ -34,16 +33,20 @@ optional arguments: ``` -Examples using route name: +Example using route name: `./juggle.py "a2a0ccea32023010/2023-07-27--13-01-19"` -Examples using segment range: +Examples using segment: `./juggle.py "a2a0ccea32023010/2023-07-27--13-01-19/1"` `./juggle.py "a2a0ccea32023010/2023-07-27--13-01-19/1/q" # use qlogs` +Example using segment range: + +`./juggle.py "a2a0ccea32023010/2023-07-27--13-01-19/0:1"` + ## Streaming Explore live data from your car! Follow these steps to stream from your comma device to your laptop: diff --git a/tools/replay/README.md b/tools/replay/README.md index 8b4afb0acc..72216e2cc8 100644 --- a/tools/replay/README.md +++ b/tools/replay/README.md @@ -75,7 +75,7 @@ Options: --qcam load qcamera --no-hw-decoder disable HW video decoding --no-vipc do not output video - --all do output all messages including uiDebug, userFlag. + --all do output all messages including uiDebug, userBookmark. this may causes issues when used along with UI Arguments: @@ -91,14 +91,6 @@ tools/replay/replay cd selfdrive/ui && ./ui ``` -## Try Radar Point Visualization with Rerun -To visualize radar points, run rp_visualization.py while tools/replay/replay is active. - -```bash -tools/replay/replay -python3 replay/rp_visualization.py -``` - ## Work with plotjuggler If you want to use replay with plotjuggler, you can stream messages by running: diff --git a/tools/replay/consoleui.cc b/tools/replay/consoleui.cc index 503902622c..a4f3677ff3 100644 --- a/tools/replay/consoleui.cc +++ b/tools/replay/consoleui.cc @@ -257,7 +257,7 @@ void ConsoleUI::updateTimeline() { if (entry.type == TimelineType::Engaged) { mvwchgat(win, 1, start_pos, end_pos - start_pos + 1, A_COLOR, Color::Engaged, NULL); mvwchgat(win, 2, start_pos, end_pos - start_pos + 1, A_COLOR, Color::Engaged, NULL); - } else if (entry.type == TimelineType::UserFlag) { + } else if (entry.type == TimelineType::UserBookmark) { mvwchgat(win, 3, start_pos, end_pos - start_pos + 1, ACS_S3, Color::Cyan, NULL); } else { auto color_id = Color::Green; @@ -329,7 +329,7 @@ void ConsoleUI::handleKey(char c) { } else if (c == 'd') { replay->seekToFlag(FindFlag::nextDisEngagement); } else if (c == 't') { - replay->seekToFlag(FindFlag::nextUserFlag); + replay->seekToFlag(FindFlag::nextUserBookmark); } else if (c == 'i') { replay->seekToFlag(FindFlag::nextInfo); } else if (c == 'w') { diff --git a/tools/replay/lib/rp_helpers.py b/tools/replay/lib/rp_helpers.py deleted file mode 100644 index aa20ab8e32..0000000000 --- a/tools/replay/lib/rp_helpers.py +++ /dev/null @@ -1,109 +0,0 @@ -import numpy as np -from openpilot.selfdrive.controls.radard import RADAR_TO_CAMERA - -# Color palette used for rerun AnnotationContext -rerunColorPalette = [(96, "red", (255, 0, 0)), - (100, "pink", (255, 36, 0)), - (124, "yellow", (255, 255, 0)), - (230, "vibrantpink", (255, 36, 170)), - (240, "orange", (255, 146, 0)), - (255, "white", (255, 255, 255)), - (110, "carColor", (255,0,127)), - (0, "background", (0, 0, 0))] - - -class UIParams: - lidar_x, lidar_y, lidar_zoom = 384, 960, 6 - lidar_car_x, lidar_car_y = lidar_x / 2., lidar_y / 1.1 - car_hwidth = 1.7272 / 2 * lidar_zoom - car_front = 2.6924 * lidar_zoom - car_back = 1.8796 * lidar_zoom - car_color = rerunColorPalette[6][0] -UP = UIParams - - -def to_topdown_pt(y, x): - px, py = x * UP.lidar_zoom + UP.lidar_car_x, -y * UP.lidar_zoom + UP.lidar_car_y - if px > 0 and py > 0 and px < UP.lidar_x and py < UP.lidar_y: - return int(px), int(py) - return -1, -1 - - -def draw_path(path, lid_overlay, lid_color=None): - x, y = np.asarray(path.x), np.asarray(path.y) - # draw lidar path point on lidar - if lid_color is not None and lid_overlay is not None: - for i in range(len(x)): - px, py = to_topdown_pt(x[i], y[i]) - if px != -1: - lid_overlay[px, py] = lid_color - - -def plot_model(m, lid_overlay): - if lid_overlay is None: - return - for lead in m.leadsV3: - if lead.prob < 0.5: - continue - x, y = lead.x[0], lead.y[0] - x_std = lead.xStd[0] - x -= RADAR_TO_CAMERA - _, py_top = to_topdown_pt(x + x_std, y) - px, py_bottom = to_topdown_pt(x - x_std, y) - lid_overlay[int(round(px - 4)):int(round(px + 4)), py_top:py_bottom] = rerunColorPalette[2][0] - - for path in m.laneLines: - draw_path(path, lid_overlay, rerunColorPalette[2][0]) - for edge in m.roadEdges: - draw_path(edge, lid_overlay, rerunColorPalette[0][0]) - draw_path(m.position, lid_overlay, rerunColorPalette[0][0]) - - -def plot_lead(rs, lid_overlay): - for lead in [rs.leadOne, rs.leadTwo]: - if not lead.status: - continue - x = lead.dRel - px_left, py = to_topdown_pt(x, -10) - px_right, _ = to_topdown_pt(x, 10) - lid_overlay[px_left:px_right, py] = rerunColorPalette[0][0] - - -def update_radar_points(lt, lid_overlay): - ar_pts = [] - if lt is not None: - ar_pts = {} - for track in lt: - ar_pts[track.trackId] = [track.dRel, track.yRel, track.vRel, track.aRel, track.oncoming, track.stationary] - for ids, pt in ar_pts.items(): - # negative here since radar is left positive - px, py = to_topdown_pt(pt[0], -pt[1]) - if px != -1: - if pt[-1]: - color = rerunColorPalette[4][0] - elif pt[-2]: - color = rerunColorPalette[3][0] - else: - color = rerunColorPalette[5][0] - if int(ids) == 1: - lid_overlay[px - 2:px + 2, py - 10:py + 10] = rerunColorPalette[1][0] - else: - lid_overlay[px - 2:px + 2, py - 2:py + 2] = color - - -def get_blank_lid_overlay(UP): - lid_overlay = np.zeros((UP.lidar_x, UP.lidar_y), 'uint8') - # Draw the car. - lid_overlay[int(round(UP.lidar_car_x - UP.car_hwidth)):int( - round(UP.lidar_car_x + UP.car_hwidth)), int(round(UP.lidar_car_y - - UP.car_front))] = UP.car_color - lid_overlay[int(round(UP.lidar_car_x - UP.car_hwidth)):int( - round(UP.lidar_car_x + UP.car_hwidth)), int(round(UP.lidar_car_y + - UP.car_back))] = UP.car_color - lid_overlay[int(round(UP.lidar_car_x - UP.car_hwidth)), int( - round(UP.lidar_car_y - UP.car_front)):int(round( - UP.lidar_car_y + UP.car_back))] = UP.car_color - lid_overlay[int(round(UP.lidar_car_x + UP.car_hwidth)), int( - round(UP.lidar_car_y - UP.car_front)):int(round( - UP.lidar_car_y + UP.car_back))] = UP.car_color - return lid_overlay diff --git a/tools/replay/main.cc b/tools/replay/main.cc index 38a1da292a..f950985075 100644 --- a/tools/replay/main.cc +++ b/tools/replay/main.cc @@ -30,7 +30,7 @@ Options: --qcam Load qcamera --no-hw-decoder Disable HW video decoding --no-vipc Do not output video - --all Output all messages including uiDebug, userFlag + --all Output all messages including uiDebug, userBookmark -h, --help Show this help message )"; diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc index a8e5cd9d43..7ecad82873 100644 --- a/tools/replay/replay.cc +++ b/tools/replay/replay.cc @@ -20,7 +20,7 @@ Replay::Replay(const std::string &route, std::vector allow, std::ve std::signal(SIGUSR1, interrupt_sleep_handler); if (!(flags_ & REPLAY_FLAG_ALL_SERVICES)) { - block.insert(block.end(), {"uiDebug", "userFlag"}); + block.insert(block.end(), {"uiDebug", "userBookmark"}); } setupServices(allow, block); setupSegmentManager(!allow.empty() || !block.empty()); diff --git a/tools/replay/rp_visualization.py b/tools/replay/rp_visualization.py deleted file mode 100755 index 25169b72ae..0000000000 --- a/tools/replay/rp_visualization.py +++ /dev/null @@ -1,60 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import os -import sys -import numpy as np -import rerun as rr -import cereal.messaging as messaging -from openpilot.common.basedir import BASEDIR -from openpilot.tools.replay.lib.rp_helpers import (UP, rerunColorPalette, - get_blank_lid_overlay, - update_radar_points, plot_lead, - plot_model) -from msgq.visionipc import VisionIpcClient, VisionStreamType - -os.environ['BASEDIR'] = BASEDIR - -UP.lidar_zoom = 6 - -def visualize(addr): - sm = messaging.SubMaster(['radarState', 'liveTracks', 'modelV2'], addr=addr) - vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_ROAD, True) - while True: - if not vipc_client.is_connected(): - vipc_client.connect(True) - new_data = vipc_client.recv() - if new_data is None or not new_data.data.any(): - continue - - sm.update(0) - lid_overlay = get_blank_lid_overlay(UP) - if sm.recv_frame['modelV2']: - plot_model(sm['modelV2'], lid_overlay) - if sm.recv_frame['radarState']: - plot_lead(sm['radarState'], lid_overlay) - liveTracksTime = sm.logMonoTime['liveTracks'] - if sm.updated['liveTracks']: - update_radar_points(sm['liveTracks'], lid_overlay) - rr.set_time_nanos("TIMELINE", liveTracksTime) - rr.log("tracks", rr.SegmentationImage(np.flip(np.rot90(lid_overlay, k=-1), axis=1))) - - -def get_arg_parser(): - parser = argparse.ArgumentParser( - description="Show replay data in a UI.", - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument("ip_address", nargs="?", default="127.0.0.1", - help="The ip address on which to receive zmq messages.") - parser.add_argument("--frame-address", default=None, - help="The frame address (fully qualified ZMQ endpoint for frames) on which to receive zmq messages.") - return parser - - -if __name__ == "__main__": - args = get_arg_parser().parse_args(sys.argv[1:]) - if args.ip_address != "127.0.0.1": - os.environ["ZMQ"] = "1" - messaging.reset_context() - rr.init("RadarPoints", spawn= True) - rr.log("tracks", rr.AnnotationContext(rerunColorPalette), static=True) - visualize(args.ip_address) diff --git a/tools/replay/timeline.cc b/tools/replay/timeline.cc index a4c2ffb700..39ea8b1bed 100644 --- a/tools/replay/timeline.cc +++ b/tools/replay/timeline.cc @@ -26,7 +26,7 @@ std::optional Timeline::find(double cur_ts, FindFlag flag) const { return entry.end_time; } } else if (entry.start_time > cur_ts) { - if ((flag == FindFlag::nextUserFlag && entry.type == TimelineType::UserFlag) || + if ((flag == FindFlag::nextUserBookmark && entry.type == TimelineType::UserBookmark) || (flag == FindFlag::nextInfo && entry.type == TimelineType::AlertInfo) || (flag == FindFlag::nextWarning && entry.type == TimelineType::AlertWarning) || (flag == FindFlag::nextCritical && entry.type == TimelineType::AlertCritical)) { @@ -66,8 +66,8 @@ void Timeline::buildTimeline(const Route &route, uint64_t route_start_ts, bool l auto cs = reader.getRoot().getSelfdriveState(); updateEngagementStatus(cs, current_engaged_idx, seconds); updateAlertStatus(cs, current_alert_idx, seconds); - } else if (e.which == cereal::Event::Which::USER_FLAG) { - staging_entries_.emplace_back(Entry{seconds, seconds, TimelineType::UserFlag}); + } else if (e.which == cereal::Event::Which::USER_BOOKMARK) { + staging_entries_.emplace_back(Entry{seconds, seconds, TimelineType::UserBookmark}); } } diff --git a/tools/replay/timeline.h b/tools/replay/timeline.h index 74add9e5cc..9688b6b95e 100644 --- a/tools/replay/timeline.h +++ b/tools/replay/timeline.h @@ -7,8 +7,8 @@ #include "tools/replay/route.h" -enum class TimelineType { None, Engaged, AlertInfo, AlertWarning, AlertCritical, UserFlag }; -enum class FindFlag { nextEngagement, nextDisEngagement, nextUserFlag, nextInfo, nextWarning, nextCritical }; +enum class TimelineType { None, Engaged, AlertInfo, AlertWarning, AlertCritical, UserBookmark }; +enum class FindFlag { nextEngagement, nextDisEngagement, nextUserBookmark, nextInfo, nextWarning, nextCritical }; class Timeline { public: diff --git a/tools/rerun/README.md b/tools/rerun/README.md deleted file mode 100644 index 11a8d33ee1..0000000000 --- a/tools/rerun/README.md +++ /dev/null @@ -1,37 +0,0 @@ -# Rerun -Rerun is a tool to quickly visualize time series data. It supports all openpilot logs , both the `logMessages` and video logs. - -[Instructions](https://rerun.io/docs/reference/viewer/overview) for navigation within the Rerun Viewer. - -## Usage -``` -usage: run.py [-h] [--demo] [--qcam] [--fcam] [--ecam] [--dcam] [route_or_segment_name] - -A helper to run rerun on openpilot routes - -positional arguments: - route_or_segment_name - The route or segment name to plot (default: None) - -options: - -h, --help show this help message and exit - --demo Use the demo route instead of providing one (default: False) - --qcam Show low-res road camera (default: False) - --fcam Show driving camera (default: False) - --ecam Show wide camera (default: False) - --dcam Show driver monitoring camera (default: False) -``` - -Examples using route name to observe accelerometer and qcamera: - -`./run.py --qcam "a2a0ccea32023010/2023-07-27--13-01-19"` - -Examples using segment range (more on [SegmentRange](https://github.com/commaai/openpilot/tree/master/tools/lib)): - -`./run.py --qcam "a2a0ccea32023010/2023-07-27--13-01-19/2:4"` - -## Cautions: -- Showing hevc videos (`--fcam`, `--ecam`, and `--dcam`) are expensive, and it's recommended to use `--qcam` for optimized performance. If possible, limiting your route to a few segments using `SegmentRange` will speed up logging and reduce memory usage - -## Demo -`./run.py --qcam --demo` diff --git a/tools/rerun/camera_reader.py b/tools/rerun/camera_reader.py deleted file mode 100644 index 8366a3c1cf..0000000000 --- a/tools/rerun/camera_reader.py +++ /dev/null @@ -1,93 +0,0 @@ -import tqdm -import subprocess -import multiprocessing -from enum import StrEnum -from functools import partial -from collections import namedtuple - -from openpilot.tools.lib.framereader import ffprobe - -CameraConfig = namedtuple("CameraConfig", ["qcam", "fcam", "ecam", "dcam"]) - -class CameraType(StrEnum): - qcam = "qcamera" - fcam = "fcamera" - ecam = "ecamera" - dcam = "dcamera" - - -def probe_packet_info(camera_path): - args = ["ffprobe", "-v", "quiet", "-show_packets", "-probesize", "10M", camera_path] - dat = subprocess.check_output(args) - dat = dat.decode().split() - return dat - - -class _FrameReader: - def __init__(self, camera_path, segment, h, w, start_time): - self.camera_path = camera_path - self.segment = segment - self.h = h - self.w = w - self.start_time = start_time - - self.ts = self._get_ts() - - def _read_stream_nv12(self): - frame_sz = self.w * self.h * 3 // 2 - proc = subprocess.Popen( - ["ffmpeg", "-v", "quiet", "-i", self.camera_path, "-f", "rawvideo", "-pix_fmt", "nv12", "-"], - stdin=subprocess.PIPE, - stdout=subprocess.PIPE, - stderr=subprocess.DEVNULL - ) - try: - while True: - dat = proc.stdout.read(frame_sz) - if len(dat) == 0: - break - yield dat - finally: - proc.kill() - - def _get_ts(self): - dat = probe_packet_info(self.camera_path) - try: - ret = [float(d.split('=')[1]) for d in dat if d.startswith("pts_time=")] - except ValueError: - # pts_times aren't available. Infer timestamps from duration_times - ret = [d for d in dat if d.startswith("duration_time")] - ret = [float(d.split('=')[1])*(i+1)+(self.segment*60)+self.start_time for i, d in enumerate(ret)] - return ret - - def __iter__(self): - for i, frame in enumerate(self._read_stream_nv12()): - yield self.ts[i], frame - - -class CameraReader: - def __init__(self, camera_paths, start_time, seg_idxs): - self.seg_idxs = seg_idxs - self.camera_paths = camera_paths - self.start_time = start_time - - probe = ffprobe(camera_paths[0])["streams"][0] - self.h = probe["height"] - self.w = probe["width"] - - self.__frs = {} - - def _get_fr(self, i): - if i not in self.__frs: - self.__frs[i] = _FrameReader(self.camera_paths[i], segment=i, h=self.h, w=self.w, start_time=self.start_time) - return self.__frs[i] - - def _run_on_segment(self, func, i): - return func(self._get_fr(i)) - - def run_across_segments(self, num_processes, func, desc=None): - with multiprocessing.Pool(num_processes) as pool: - num_segs = len(self.seg_idxs) - for _ in tqdm.tqdm(pool.imap_unordered(partial(self._run_on_segment, func), self.seg_idxs), total=num_segs, desc=desc): - continue - diff --git a/tools/rerun/run.py b/tools/rerun/run.py deleted file mode 100755 index 6ce8a37937..0000000000 --- a/tools/rerun/run.py +++ /dev/null @@ -1,180 +0,0 @@ -#!/usr/bin/env python3 - -import sys -import argparse -import multiprocessing -import rerun as rr -import rerun.blueprint as rrb -from functools import partial -from collections import defaultdict - -from cereal.services import SERVICE_LIST -from openpilot.tools.rerun.camera_reader import probe_packet_info, CameraReader, CameraConfig, CameraType -from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.route import Route, SegmentRange - - -NUM_CPUS = multiprocessing.cpu_count() -DEMO_ROUTE = "a2a0ccea32023010|2023-07-27--13-01-19" -RR_TIMELINE_NAME = "Timeline" -RR_WIN = "openpilot logs" - - -""" -Relevant upstream Rerun issues: -- loading videos directly: https://github.com/rerun-io/rerun/issues/6532 -""" - -class Rerunner: - def __init__(self, route, segment_range, camera_config): - self.lr = LogReader(route_or_segment_name) - - # hevc files don't have start_time. We get it from qcamera.ts - start_time = 0 - dat = probe_packet_info(route.qcamera_paths()[0]) - for d in dat: - if d.startswith("pts_time="): - start_time = float(d.split('=')[1]) - break - - qcam, fcam, ecam, dcam = camera_config - self.camera_readers = {} - if qcam: - self.camera_readers[CameraType.qcam] = CameraReader(route.qcamera_paths(), start_time, segment_range.seg_idxs) - if fcam: - self.camera_readers[CameraType.fcam] = CameraReader(route.camera_paths(), start_time, segment_range.seg_idxs) - if ecam: - self.camera_readers[CameraType.ecam] = CameraReader(route.ecamera_paths(), start_time, segment_range.seg_idxs) - if dcam: - self.camera_readers[CameraType.dcam] = CameraReader(route.dcamera_paths(), start_time, segment_range.seg_idxs) - - def _create_blueprint(self): - blueprint = None - service_views = [] - - for topic in sorted(SERVICE_LIST.keys()): - View = rrb.TimeSeriesView if topic != "thumbnail" else rrb.Spatial2DView - service_views.append(View(name=topic, origin=f"/{topic}/", visible=False)) - rr.log(topic, rr.SeriesLine(name=topic), timeless=True) - - center_view = [rrb.Vertical(*service_views, name="streams")] - if len(self.camera_readers): - center_view.append(rrb.Vertical(*[rrb.Spatial2DView(name=cam_type, origin=cam_type) for cam_type in self.camera_readers.keys()], name="cameras")) - - blueprint = rrb.Blueprint( - rrb.Horizontal( - *center_view - ), - rrb.SelectionPanel(expanded=False), - rrb.TimePanel(expanded=False), - ) - return blueprint - - @staticmethod - def _parse_msg(msg, parent_key=''): - stack = [(msg, parent_key)] - while stack: - current_msg, current_parent_key = stack.pop() - if isinstance(current_msg, list): - for index, item in enumerate(current_msg): - new_key = f"{current_parent_key}/{index}" - if isinstance(item, (int, float)): - yield new_key, item - elif isinstance(item, dict): - stack.append((item, new_key)) - elif isinstance(current_msg, dict): - for key, value in current_msg.items(): - new_key = f"{current_parent_key}/{key}" - if isinstance(value, (int, float)): - yield new_key, value - elif isinstance(value, dict): - stack.append((value, new_key)) - elif isinstance(value, list): - for index, item in enumerate(value): - if isinstance(item, (int, float)): - yield f"{new_key}/{index}", item - else: - pass # Not a plottable value - - @staticmethod - @rr.shutdown_at_exit - def _process_log_msgs(blueprint, lr): - rr.init(RR_WIN) - rr.connect() - rr.send_blueprint(blueprint) - - log_msgs = defaultdict(lambda: defaultdict(list)) - for msg in lr: - msg_type = msg.which() - - if msg_type == "thumbnail": - continue - - for entity_path, dat in Rerunner._parse_msg(msg.to_dict()[msg_type], msg_type): - log_msgs[entity_path]["times"].append(msg.logMonoTime) - log_msgs[entity_path]["data"].append(dat) - - for entity_path, log_msg in log_msgs.items(): - rr.send_columns( - entity_path, - times=[rr.TimeNanosColumn(RR_TIMELINE_NAME, log_msg["times"])], - components=[rr.components.ScalarBatch(log_msg["data"])] - ) - - return [] - - @staticmethod - @rr.shutdown_at_exit - def _process_cam_readers(blueprint, cam_type, h, w, fr): - rr.init(RR_WIN) - rr.connect() - rr.send_blueprint(blueprint) - - for ts, frame in fr: - rr.set_time_nanos(RR_TIMELINE_NAME, int(ts * 1e9)) - rr.log(cam_type, rr.Image(bytes=frame, width=w, height=h, pixel_format=rr.PixelFormat.NV12)) - - def load_data(self): - rr.init(RR_WIN, spawn=True) - - startup_blueprint = self._create_blueprint() - self.lr.run_across_segments(NUM_CPUS, partial(self._process_log_msgs, startup_blueprint), desc="Log messages") - for cam_type, cr in self.camera_readers.items(): - cr.run_across_segments(NUM_CPUS, partial(self._process_cam_readers, startup_blueprint, cam_type, cr.h, cr.w), desc=cam_type) - - rr.send_blueprint(self._create_blueprint()) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser(description="A helper to run rerun on openpilot routes", - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument("--demo", action="store_true", help="Use the demo route instead of providing one") - parser.add_argument("--qcam", action="store_true", help="Show low-res road camera") - parser.add_argument("--fcam", action="store_true", help="Show driving camera") - parser.add_argument("--ecam", action="store_true", help="Show wide camera") - parser.add_argument("--dcam", action="store_true", help="Show driver monitoring camera") - parser.add_argument("route_or_segment_name", nargs='?', help="The route or segment name to plot") - args = parser.parse_args() - - if not args.demo and not args.route_or_segment_name: - parser.print_help() - sys.exit() - - camera_config = CameraConfig(args.qcam, args.fcam, args.ecam, args.dcam) - route_or_segment_name = DEMO_ROUTE if args.demo else args.route_or_segment_name.strip() - - sr = SegmentRange(route_or_segment_name) - r = Route(sr.route_name) - - hevc_requested = any(camera_config[1:]) - if len(sr.seg_idxs) > 1 and hevc_requested: - print("You're requesting more than 1 segment with hevc videos, " + \ - "please be aware that might take a lot of memory " + \ - "since rerun isn't yet well supported for high resolution video logging") - response = input("Do you wish to continue? (Y/n): ") - if response.strip().lower() != "y": - sys.exit() - - rerunner = Rerunner(r, sr, camera_config) - rerunner.load_data() - diff --git a/tools/tuning/measure_steering_accuracy.py b/tools/tuning/measure_steering_accuracy.py index a2f437819f..7e4e975742 100755 --- a/tools/tuning/measure_steering_accuracy.py +++ b/tools/tuning/measure_steering_accuracy.py @@ -49,7 +49,7 @@ class SteeringAccuracyTool: active = sm['controlsState'].active steer = sm['carOutput'].actuatorsOutput.torque standstill = sm['carState'].standstill - steer_limited_by_controls = abs(sm['carControl'].actuators.torque - sm['carControl'].actuatorsOutput.torque) > 1e-2 + steer_limited_by_safety = abs(sm['carControl'].actuators.torque - sm['carControl'].actuatorsOutput.torque) > 1e-2 overriding = sm['carState'].steeringPressed changing_lanes = sm['modelV2'].meta.laneChangeState != 0 model_points = sm['modelV2'].position.y @@ -77,7 +77,7 @@ class SteeringAccuracyTool: self.speed_group_stats[group][angle_abs]["steer"] += abs(steer) if len(model_points): self.speed_group_stats[group][angle_abs]["dpp"] += abs(model_points[0]) - if steer_limited_by_controls: + if steer_limited_by_safety: self.speed_group_stats[group][angle_abs]["limited"] += 1 if control_state.saturated: self.speed_group_stats[group][angle_abs]["saturated"] += 1 diff --git a/uv.lock b/uv.lock index dc016a0d3f..7cfaceed97 100644 --- a/uv.lock +++ b/uv.lock @@ -166,7 +166,7 @@ wheels = [ [[package]] name = "azure-identity" -version = "1.23.1" +version = "1.24.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "azure-core" }, @@ -175,9 +175,9 @@ dependencies = [ { name = "msal-extensions" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b5/29/1201ffbb6a57a16524dd91f3e741b4c828a70aaba436578bdcb3fbcb438c/azure_identity-1.23.1.tar.gz", hash = "sha256:226c1ef982a9f8d5dcf6e0f9ed35eaef2a4d971e7dd86317e9b9d52e70a035e4", size = 266185, upload-time = "2025-07-15T19:16:38.077Z" } +sdist = { url = "https://files.pythonhosted.org/packages/b5/44/f3ee20bacb220b6b4a2b0a6cf7e742eecb383a5ccf604dd79ec27c286b7e/azure_identity-1.24.0.tar.gz", hash = "sha256:6c3a40b2a70af831e920b89e6421e8dcd4af78a0cb38b9642d86c67643d4930c", size = 271630, upload-time = "2025-08-07T22:27:36.258Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/99/b3/e2d7ab810eb68575a5c7569b03c0228b8f4ce927ffa6211471b526f270c9/azure_identity-1.23.1-py3-none-any.whl", hash = "sha256:7eed28baa0097a47e3fb53bd35a63b769e6b085bb3cb616dfce2b67f28a004a1", size = 186810, upload-time = "2025-07-15T19:16:40.184Z" }, + { url = "https://files.pythonhosted.org/packages/a9/74/17428cb429e8d52f6d0d69ed685f4760a545cb0156594963a9337b53b6c9/azure_identity-1.24.0-py3-none-any.whl", hash = "sha256:9e04997cde0ab02ed66422c74748548e620b7b29361c72ce622acab0267ff7c4", size = 187890, upload-time = "2025-08-07T22:27:38.033Z" }, ] [[package]] @@ -263,37 +263,33 @@ wheels = [ [[package]] name = "charset-normalizer" -version = "3.4.2" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e4/33/89c2ced2b67d1c2a61c19c6751aa8902d46ce3dacb23600a283619f5a12d/charset_normalizer-3.4.2.tar.gz", hash = "sha256:5baececa9ecba31eff645232d59845c07aa030f0c81ee70184a90d35099a0e63", size = 126367, upload-time = "2025-05-02T08:34:42.01Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/05/85/4c40d00dcc6284a1c1ad5de5e0996b06f39d8232f1031cd23c2f5c07ee86/charset_normalizer-3.4.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:be1e352acbe3c78727a16a455126d9ff83ea2dfdcbc83148d2982305a04714c2", size = 198794, upload-time = "2025-05-02T08:32:11.945Z" }, - { url = "https://files.pythonhosted.org/packages/41/d9/7a6c0b9db952598e97e93cbdfcb91bacd89b9b88c7c983250a77c008703c/charset_normalizer-3.4.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:aa88ca0b1932e93f2d961bf3addbb2db902198dca337d88c89e1559e066e7645", size = 142846, upload-time = "2025-05-02T08:32:13.946Z" }, - { url = "https://files.pythonhosted.org/packages/66/82/a37989cda2ace7e37f36c1a8ed16c58cf48965a79c2142713244bf945c89/charset_normalizer-3.4.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d524ba3f1581b35c03cb42beebab4a13e6cdad7b36246bd22541fa585a56cccd", size = 153350, upload-time = "2025-05-02T08:32:15.873Z" }, - { url = "https://files.pythonhosted.org/packages/df/68/a576b31b694d07b53807269d05ec3f6f1093e9545e8607121995ba7a8313/charset_normalizer-3.4.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:28a1005facc94196e1fb3e82a3d442a9d9110b8434fc1ded7a24a2983c9888d8", size = 145657, upload-time = "2025-05-02T08:32:17.283Z" }, - { url = "https://files.pythonhosted.org/packages/92/9b/ad67f03d74554bed3aefd56fe836e1623a50780f7c998d00ca128924a499/charset_normalizer-3.4.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fdb20a30fe1175ecabed17cbf7812f7b804b8a315a25f24678bcdf120a90077f", size = 147260, upload-time = "2025-05-02T08:32:18.807Z" }, - { url = "https://files.pythonhosted.org/packages/a6/e6/8aebae25e328160b20e31a7e9929b1578bbdc7f42e66f46595a432f8539e/charset_normalizer-3.4.2-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:0f5d9ed7f254402c9e7d35d2f5972c9bbea9040e99cd2861bd77dc68263277c7", size = 149164, upload-time = "2025-05-02T08:32:20.333Z" }, - { url = "https://files.pythonhosted.org/packages/8b/f2/b3c2f07dbcc248805f10e67a0262c93308cfa149a4cd3d1fe01f593e5fd2/charset_normalizer-3.4.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:efd387a49825780ff861998cd959767800d54f8308936b21025326de4b5a42b9", size = 144571, upload-time = "2025-05-02T08:32:21.86Z" }, - { url = "https://files.pythonhosted.org/packages/60/5b/c3f3a94bc345bc211622ea59b4bed9ae63c00920e2e8f11824aa5708e8b7/charset_normalizer-3.4.2-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:f0aa37f3c979cf2546b73e8222bbfa3dc07a641585340179d768068e3455e544", size = 151952, upload-time = "2025-05-02T08:32:23.434Z" }, - { url = "https://files.pythonhosted.org/packages/e2/4d/ff460c8b474122334c2fa394a3f99a04cf11c646da895f81402ae54f5c42/charset_normalizer-3.4.2-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:e70e990b2137b29dc5564715de1e12701815dacc1d056308e2b17e9095372a82", size = 155959, upload-time = "2025-05-02T08:32:24.993Z" }, - { url = "https://files.pythonhosted.org/packages/a2/2b/b964c6a2fda88611a1fe3d4c400d39c66a42d6c169c924818c848f922415/charset_normalizer-3.4.2-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:0c8c57f84ccfc871a48a47321cfa49ae1df56cd1d965a09abe84066f6853b9c0", size = 153030, upload-time = "2025-05-02T08:32:26.435Z" }, - { url = "https://files.pythonhosted.org/packages/59/2e/d3b9811db26a5ebf444bc0fa4f4be5aa6d76fc6e1c0fd537b16c14e849b6/charset_normalizer-3.4.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:6b66f92b17849b85cad91259efc341dce9c1af48e2173bf38a85c6329f1033e5", size = 148015, upload-time = "2025-05-02T08:32:28.376Z" }, - { url = "https://files.pythonhosted.org/packages/90/07/c5fd7c11eafd561bb51220d600a788f1c8d77c5eef37ee49454cc5c35575/charset_normalizer-3.4.2-cp311-cp311-win32.whl", hash = "sha256:daac4765328a919a805fa5e2720f3e94767abd632ae410a9062dff5412bae65a", size = 98106, upload-time = "2025-05-02T08:32:30.281Z" }, - { url = "https://files.pythonhosted.org/packages/a8/05/5e33dbef7e2f773d672b6d79f10ec633d4a71cd96db6673625838a4fd532/charset_normalizer-3.4.2-cp311-cp311-win_amd64.whl", hash = "sha256:e53efc7c7cee4c1e70661e2e112ca46a575f90ed9ae3fef200f2a25e954f4b28", size = 105402, upload-time = "2025-05-02T08:32:32.191Z" }, - { url = "https://files.pythonhosted.org/packages/d7/a4/37f4d6035c89cac7930395a35cc0f1b872e652eaafb76a6075943754f095/charset_normalizer-3.4.2-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0c29de6a1a95f24b9a1aa7aefd27d2487263f00dfd55a77719b530788f75cff7", size = 199936, upload-time = "2025-05-02T08:32:33.712Z" }, - { url = "https://files.pythonhosted.org/packages/ee/8a/1a5e33b73e0d9287274f899d967907cd0bf9c343e651755d9307e0dbf2b3/charset_normalizer-3.4.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cddf7bd982eaa998934a91f69d182aec997c6c468898efe6679af88283b498d3", size = 143790, upload-time = "2025-05-02T08:32:35.768Z" }, - { url = "https://files.pythonhosted.org/packages/66/52/59521f1d8e6ab1482164fa21409c5ef44da3e9f653c13ba71becdd98dec3/charset_normalizer-3.4.2-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fcbe676a55d7445b22c10967bceaaf0ee69407fbe0ece4d032b6eb8d4565982a", size = 153924, upload-time = "2025-05-02T08:32:37.284Z" }, - { url = "https://files.pythonhosted.org/packages/86/2d/fb55fdf41964ec782febbf33cb64be480a6b8f16ded2dbe8db27a405c09f/charset_normalizer-3.4.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d41c4d287cfc69060fa91cae9683eacffad989f1a10811995fa309df656ec214", size = 146626, upload-time = "2025-05-02T08:32:38.803Z" }, - { url = "https://files.pythonhosted.org/packages/8c/73/6ede2ec59bce19b3edf4209d70004253ec5f4e319f9a2e3f2f15601ed5f7/charset_normalizer-3.4.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4e594135de17ab3866138f496755f302b72157d115086d100c3f19370839dd3a", size = 148567, upload-time = "2025-05-02T08:32:40.251Z" }, - { url = "https://files.pythonhosted.org/packages/09/14/957d03c6dc343c04904530b6bef4e5efae5ec7d7990a7cbb868e4595ee30/charset_normalizer-3.4.2-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:cf713fe9a71ef6fd5adf7a79670135081cd4431c2943864757f0fa3a65b1fafd", size = 150957, upload-time = "2025-05-02T08:32:41.705Z" }, - { url = "https://files.pythonhosted.org/packages/0d/c8/8174d0e5c10ccebdcb1b53cc959591c4c722a3ad92461a273e86b9f5a302/charset_normalizer-3.4.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:a370b3e078e418187da8c3674eddb9d983ec09445c99a3a263c2011993522981", size = 145408, upload-time = "2025-05-02T08:32:43.709Z" }, - { url = "https://files.pythonhosted.org/packages/58/aa/8904b84bc8084ac19dc52feb4f5952c6df03ffb460a887b42615ee1382e8/charset_normalizer-3.4.2-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:a955b438e62efdf7e0b7b52a64dc5c3396e2634baa62471768a64bc2adb73d5c", size = 153399, upload-time = "2025-05-02T08:32:46.197Z" }, - { url = "https://files.pythonhosted.org/packages/c2/26/89ee1f0e264d201cb65cf054aca6038c03b1a0c6b4ae998070392a3ce605/charset_normalizer-3.4.2-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:7222ffd5e4de8e57e03ce2cef95a4c43c98fcb72ad86909abdfc2c17d227fc1b", size = 156815, upload-time = "2025-05-02T08:32:48.105Z" }, - { url = "https://files.pythonhosted.org/packages/fd/07/68e95b4b345bad3dbbd3a8681737b4338ff2c9df29856a6d6d23ac4c73cb/charset_normalizer-3.4.2-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:bee093bf902e1d8fc0ac143c88902c3dfc8941f7ea1d6a8dd2bcb786d33db03d", size = 154537, upload-time = "2025-05-02T08:32:49.719Z" }, - { url = "https://files.pythonhosted.org/packages/77/1a/5eefc0ce04affb98af07bc05f3bac9094513c0e23b0562d64af46a06aae4/charset_normalizer-3.4.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:dedb8adb91d11846ee08bec4c8236c8549ac721c245678282dcb06b221aab59f", size = 149565, upload-time = "2025-05-02T08:32:51.404Z" }, - { url = "https://files.pythonhosted.org/packages/37/a0/2410e5e6032a174c95e0806b1a6585eb21e12f445ebe239fac441995226a/charset_normalizer-3.4.2-cp312-cp312-win32.whl", hash = "sha256:db4c7bf0e07fc3b7d89ac2a5880a6a8062056801b83ff56d8464b70f65482b6c", size = 98357, upload-time = "2025-05-02T08:32:53.079Z" }, - { url = "https://files.pythonhosted.org/packages/6c/4f/c02d5c493967af3eda9c771ad4d2bbc8df6f99ddbeb37ceea6e8716a32bc/charset_normalizer-3.4.2-cp312-cp312-win_amd64.whl", hash = "sha256:5a9979887252a82fefd3d3ed2a8e3b937a7a809f65dcb1e068b090e165bbe99e", size = 105776, upload-time = "2025-05-02T08:32:54.573Z" }, - { url = "https://files.pythonhosted.org/packages/20/94/c5790835a017658cbfabd07f3bfb549140c3ac458cfc196323996b10095a/charset_normalizer-3.4.2-py3-none-any.whl", hash = "sha256:7f56930ab0abd1c45cd15be65cc741c28b1c9a34876ce8c17a2fa107810c0af0", size = 52626, upload-time = "2025-05-02T08:34:40.053Z" }, +version = "3.4.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/83/2d/5fd176ceb9b2fc619e63405525573493ca23441330fcdaee6bef9460e924/charset_normalizer-3.4.3.tar.gz", hash = "sha256:6fce4b8500244f6fcb71465d4a4930d132ba9ab8e71a7859e6a5d59851068d14", size = 122371, upload-time = "2025-08-09T07:57:28.46Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/7f/b5/991245018615474a60965a7c9cd2b4efbaabd16d582a5547c47ee1c7730b/charset_normalizer-3.4.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:b256ee2e749283ef3ddcff51a675ff43798d92d746d1a6e4631bf8c707d22d0b", size = 204483, upload-time = "2025-08-09T07:55:53.12Z" }, + { url = "https://files.pythonhosted.org/packages/c7/2a/ae245c41c06299ec18262825c1569c5d3298fc920e4ddf56ab011b417efd/charset_normalizer-3.4.3-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:13faeacfe61784e2559e690fc53fa4c5ae97c6fcedb8eb6fb8d0a15b475d2c64", size = 145520, upload-time = "2025-08-09T07:55:54.712Z" }, + { url = "https://files.pythonhosted.org/packages/3a/a4/b3b6c76e7a635748c4421d2b92c7b8f90a432f98bda5082049af37ffc8e3/charset_normalizer-3.4.3-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:00237675befef519d9af72169d8604a067d92755e84fe76492fef5441db05b91", size = 158876, upload-time = "2025-08-09T07:55:56.024Z" }, + { url = "https://files.pythonhosted.org/packages/e2/e6/63bb0e10f90a8243c5def74b5b105b3bbbfb3e7bb753915fe333fb0c11ea/charset_normalizer-3.4.3-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:585f3b2a80fbd26b048a0be90c5aae8f06605d3c92615911c3a2b03a8a3b796f", size = 156083, upload-time = "2025-08-09T07:55:57.582Z" }, + { url = "https://files.pythonhosted.org/packages/87/df/b7737ff046c974b183ea9aa111b74185ac8c3a326c6262d413bd5a1b8c69/charset_normalizer-3.4.3-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0e78314bdc32fa80696f72fa16dc61168fda4d6a0c014e0380f9d02f0e5d8a07", size = 150295, upload-time = "2025-08-09T07:55:59.147Z" }, + { url = "https://files.pythonhosted.org/packages/61/f1/190d9977e0084d3f1dc169acd060d479bbbc71b90bf3e7bf7b9927dec3eb/charset_normalizer-3.4.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:96b2b3d1a83ad55310de8c7b4a2d04d9277d5591f40761274856635acc5fcb30", size = 148379, upload-time = "2025-08-09T07:56:00.364Z" }, + { url = "https://files.pythonhosted.org/packages/4c/92/27dbe365d34c68cfe0ca76f1edd70e8705d82b378cb54ebbaeabc2e3029d/charset_normalizer-3.4.3-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:939578d9d8fd4299220161fdd76e86c6a251987476f5243e8864a7844476ba14", size = 160018, upload-time = "2025-08-09T07:56:01.678Z" }, + { url = "https://files.pythonhosted.org/packages/99/04/baae2a1ea1893a01635d475b9261c889a18fd48393634b6270827869fa34/charset_normalizer-3.4.3-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:fd10de089bcdcd1be95a2f73dbe6254798ec1bda9f450d5828c96f93e2536b9c", size = 157430, upload-time = "2025-08-09T07:56:02.87Z" }, + { url = "https://files.pythonhosted.org/packages/2f/36/77da9c6a328c54d17b960c89eccacfab8271fdaaa228305330915b88afa9/charset_normalizer-3.4.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1e8ac75d72fa3775e0b7cb7e4629cec13b7514d928d15ef8ea06bca03ef01cae", size = 151600, upload-time = "2025-08-09T07:56:04.089Z" }, + { url = "https://files.pythonhosted.org/packages/64/d4/9eb4ff2c167edbbf08cdd28e19078bf195762e9bd63371689cab5ecd3d0d/charset_normalizer-3.4.3-cp311-cp311-win32.whl", hash = "sha256:6cf8fd4c04756b6b60146d98cd8a77d0cdae0e1ca20329da2ac85eed779b6849", size = 99616, upload-time = "2025-08-09T07:56:05.658Z" }, + { url = "https://files.pythonhosted.org/packages/f4/9c/996a4a028222e7761a96634d1820de8a744ff4327a00ada9c8942033089b/charset_normalizer-3.4.3-cp311-cp311-win_amd64.whl", hash = "sha256:31a9a6f775f9bcd865d88ee350f0ffb0e25936a7f930ca98995c05abf1faf21c", size = 107108, upload-time = "2025-08-09T07:56:07.176Z" }, + { url = "https://files.pythonhosted.org/packages/e9/5e/14c94999e418d9b87682734589404a25854d5f5d0408df68bc15b6ff54bb/charset_normalizer-3.4.3-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e28e334d3ff134e88989d90ba04b47d84382a828c061d0d1027b1b12a62b39b1", size = 205655, upload-time = "2025-08-09T07:56:08.475Z" }, + { url = "https://files.pythonhosted.org/packages/7d/a8/c6ec5d389672521f644505a257f50544c074cf5fc292d5390331cd6fc9c3/charset_normalizer-3.4.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0cacf8f7297b0c4fcb74227692ca46b4a5852f8f4f24b3c766dd94a1075c4884", size = 146223, upload-time = "2025-08-09T07:56:09.708Z" }, + { url = "https://files.pythonhosted.org/packages/fc/eb/a2ffb08547f4e1e5415fb69eb7db25932c52a52bed371429648db4d84fb1/charset_normalizer-3.4.3-cp312-cp312-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:c6fd51128a41297f5409deab284fecbe5305ebd7e5a1f959bee1c054622b7018", size = 159366, upload-time = "2025-08-09T07:56:11.326Z" }, + { url = "https://files.pythonhosted.org/packages/82/10/0fd19f20c624b278dddaf83b8464dcddc2456cb4b02bb902a6da126b87a1/charset_normalizer-3.4.3-cp312-cp312-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:3cfb2aad70f2c6debfbcb717f23b7eb55febc0bb23dcffc0f076009da10c6392", size = 157104, upload-time = "2025-08-09T07:56:13.014Z" }, + { url = "https://files.pythonhosted.org/packages/16/ab/0233c3231af734f5dfcf0844aa9582d5a1466c985bbed6cedab85af9bfe3/charset_normalizer-3.4.3-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1606f4a55c0fd363d754049cdf400175ee96c992b1f8018b993941f221221c5f", size = 151830, upload-time = "2025-08-09T07:56:14.428Z" }, + { url = "https://files.pythonhosted.org/packages/ae/02/e29e22b4e02839a0e4a06557b1999d0a47db3567e82989b5bb21f3fbbd9f/charset_normalizer-3.4.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:027b776c26d38b7f15b26a5da1044f376455fb3766df8fc38563b4efbc515154", size = 148854, upload-time = "2025-08-09T07:56:16.051Z" }, + { url = "https://files.pythonhosted.org/packages/05/6b/e2539a0a4be302b481e8cafb5af8792da8093b486885a1ae4d15d452bcec/charset_normalizer-3.4.3-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:42e5088973e56e31e4fa58eb6bd709e42fc03799c11c42929592889a2e54c491", size = 160670, upload-time = "2025-08-09T07:56:17.314Z" }, + { url = "https://files.pythonhosted.org/packages/31/e7/883ee5676a2ef217a40ce0bffcc3d0dfbf9e64cbcfbdf822c52981c3304b/charset_normalizer-3.4.3-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:cc34f233c9e71701040d772aa7490318673aa7164a0efe3172b2981218c26d93", size = 158501, upload-time = "2025-08-09T07:56:18.641Z" }, + { url = "https://files.pythonhosted.org/packages/c1/35/6525b21aa0db614cf8b5792d232021dca3df7f90a1944db934efa5d20bb1/charset_normalizer-3.4.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:320e8e66157cc4e247d9ddca8e21f427efc7a04bbd0ac8a9faf56583fa543f9f", size = 153173, upload-time = "2025-08-09T07:56:20.289Z" }, + { url = "https://files.pythonhosted.org/packages/50/ee/f4704bad8201de513fdc8aac1cabc87e38c5818c93857140e06e772b5892/charset_normalizer-3.4.3-cp312-cp312-win32.whl", hash = "sha256:fb6fecfd65564f208cbf0fba07f107fb661bcd1a7c389edbced3f7a493f70e37", size = 99822, upload-time = "2025-08-09T07:56:21.551Z" }, + { url = "https://files.pythonhosted.org/packages/39/f5/3b3836ca6064d0992c58c7561c6b6eee1b3892e9665d650c803bd5614522/charset_normalizer-3.4.3-cp312-cp312-win_amd64.whl", hash = "sha256:86df271bf921c2ee3818f0522e9a5b8092ca2ad8b065ece5d7d9d0e9f4849bcc", size = 107543, upload-time = "2025-08-09T07:56:23.115Z" }, + { url = "https://files.pythonhosted.org/packages/8a/1f/f041989e93b001bc4e44bb1669ccdcf54d3f00e628229a85b08d330615c5/charset_normalizer-3.4.3-py3-none-any.whl", hash = "sha256:ce571ab16d890d23b5c278547ba694193a45011ff86a9162a71307ed9f86759a", size = 53175, upload-time = "2025-08-09T07:57:26.864Z" }, ] [[package]] @@ -419,31 +415,31 @@ wheels = [ [[package]] name = "cython" -version = "3.1.2" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/18/40/7b17cd866158238db704965da1b5849af261dbad393ea3ac966f934b2d39/cython-3.1.2.tar.gz", hash = "sha256:6bbf7a953fa6762dfecdec015e3b054ba51c0121a45ad851fa130f63f5331381", size = 3184825, upload-time = "2025-06-09T07:08:48.465Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/1f/de/502ddebaf5fe78f13cd6361acdd74710d3a5b15c22a9edc0ea4c873a59a5/cython-3.1.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:5548573e0912d7dc80579827493315384c462e2f15797b91a8ed177686d31eb9", size = 3007792, upload-time = "2025-06-09T07:09:28.777Z" }, - { url = "https://files.pythonhosted.org/packages/bb/c8/91b00bc68effba9ba1ff5b33988052ac4d98fc1ac3021ade7261661299c6/cython-3.1.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:4bf3ea5bc50d80762c490f42846820a868a6406fdb5878ae9e4cc2f11b50228a", size = 2870798, upload-time = "2025-06-09T07:09:30.745Z" }, - { url = "https://files.pythonhosted.org/packages/f4/4b/29d290f14607785112c00a5e1685d766f433531bbd6a11ad229ab61b7a70/cython-3.1.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:20ce53951d06ab2bca39f153d9c5add1d631c2a44d58bf67288c9d631be9724e", size = 3131280, upload-time = "2025-06-09T07:09:32.785Z" }, - { url = "https://files.pythonhosted.org/packages/38/3c/7c61e9ce25377ec7c4aa0b7ceeed34559ebca7b5cfd384672ba64eeaa4ba/cython-3.1.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e05a36224e3002d48c7c1c695b3771343bd16bc57eab60d6c5d5e08f3cbbafd8", size = 3223898, upload-time = "2025-06-09T07:09:35.345Z" }, - { url = "https://files.pythonhosted.org/packages/10/96/2d3fbe7e50e98b53ac86fefb48b64262b2e1304b3495e8e25b3cd1c3473e/cython-3.1.2-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:dbc0fc0777c7ab82297c01c61a1161093a22a41714f62e8c35188a309bd5db8e", size = 3291527, upload-time = "2025-06-09T07:09:37.502Z" }, - { url = "https://files.pythonhosted.org/packages/bd/e4/4cd3624e250d86f05bdb121a567865b9cca75cdc6dce4eedd68e626ea4f8/cython-3.1.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:18161ef3dd0e90a944daa2be468dd27696712a5f792d6289e97d2a31298ad688", size = 3184034, upload-time = "2025-06-09T07:09:40.225Z" }, - { url = "https://files.pythonhosted.org/packages/24/de/f8c1243c3e50ec95cb81f3a7936c8cf162f28050db8683e291c3861b46a0/cython-3.1.2-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:ca45020950cd52d82189d6dfb6225737586be6fe7b0b9d3fadd7daca62eff531", size = 3386084, upload-time = "2025-06-09T07:09:42.206Z" }, - { url = "https://files.pythonhosted.org/packages/c8/95/2365937da44741ef0781bb9ecc1f8f52b38b65acb7293b5fc7c3eaee5346/cython-3.1.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:aaae97d6d07610224be2b73a93e9e3dd85c09aedfd8e47054e3ef5a863387dae", size = 3309974, upload-time = "2025-06-09T07:09:44.801Z" }, - { url = "https://files.pythonhosted.org/packages/9b/b8/280eed114110a1a3aa9e2e76bcd06cdd5ef0df7ab77c0be9d5378ca28c57/cython-3.1.2-cp311-cp311-win32.whl", hash = "sha256:3d439d9b19e7e70f6ff745602906d282a853dd5219d8e7abbf355de680c9d120", size = 2482942, upload-time = "2025-06-09T07:09:46.583Z" }, - { url = "https://files.pythonhosted.org/packages/a2/50/0aa65be5a4ab65bde3224b8fd23ed795f699d1e724ac109bb0a32036b82d/cython-3.1.2-cp311-cp311-win_amd64.whl", hash = "sha256:8efa44ee2f1876e40eb5e45f6513a19758077c56bf140623ccab43d31f873b61", size = 2686535, upload-time = "2025-06-09T07:09:48.345Z" }, - { url = "https://files.pythonhosted.org/packages/22/86/9393ab7204d5bb65f415dd271b658c18f57b9345d06002cae069376a5a7a/cython-3.1.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:9c2c4b6f9a941c857b40168b3f3c81d514e509d985c2dcd12e1a4fea9734192e", size = 3015898, upload-time = "2025-06-09T07:09:50.79Z" }, - { url = "https://files.pythonhosted.org/packages/f9/b8/3d10ac37ab7b7ee60bc6bfb48f6682ebee7fddaccf56e1e135f0d46ca79f/cython-3.1.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:bdbc115bbe1b8c1dcbcd1b03748ea87fa967eb8dfc3a1a9bb243d4a382efcff4", size = 2846204, upload-time = "2025-06-09T07:09:52.832Z" }, - { url = "https://files.pythonhosted.org/packages/f8/34/637771d8e10ebabc34a34cdd0d63fe797b66c334e150189955bf6442d710/cython-3.1.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c05111f89db1ca98edc0675cfaa62be47b3ff519a29876eb095532a9f9e052b8", size = 3080671, upload-time = "2025-06-09T07:09:54.924Z" }, - { url = "https://files.pythonhosted.org/packages/6b/c8/383ad1851fb272920a152c5a30bb6f08c3471b5438079d9488fc3074a170/cython-3.1.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f6e7188df8709be32cfdfadc7c3782e361c929df9132f95e1bbc90a340dca3c7", size = 3199022, upload-time = "2025-06-09T07:09:56.978Z" }, - { url = "https://files.pythonhosted.org/packages/e6/11/20adc8f2db37a29f245e8fd4b8b8a8245fce4bbbd128185cc9a7b1065e4c/cython-3.1.2-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1c0ecc71e60a051732c2607b8eb8f2a03a5dac09b28e52b8af323c329db9987b", size = 3241337, upload-time = "2025-06-09T07:09:59.156Z" }, - { url = "https://files.pythonhosted.org/packages/6f/0b/491f1fd3e177cccb6bb6d52f9609f78d395edde83ac47ebb06d21717ca29/cython-3.1.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:f27143cf88835c8bcc9bf3304953f23f377d1d991e8942982fe7be344c7cfce3", size = 3131808, upload-time = "2025-06-09T07:10:01.31Z" }, - { url = "https://files.pythonhosted.org/packages/db/d2/5e7053a3214c9baa7ad72940555eb87cf4750e597f10b2bb43db62c3f39f/cython-3.1.2-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:d8c43566701133f53bf13485839d8f3f309095fe0d3b9d0cd5873073394d2edc", size = 3340319, upload-time = "2025-06-09T07:10:03.485Z" }, - { url = "https://files.pythonhosted.org/packages/95/42/4842f8ddac9b36c94ae08b23c7fcde3f930c1dd49ac8992bb5320a4d96b5/cython-3.1.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:a3bb893e85f027a929c1764bb14db4c31cbdf8a96f59a78f608f2ba7cfbbce95", size = 3287370, upload-time = "2025-06-09T07:10:05.637Z" }, - { url = "https://files.pythonhosted.org/packages/03/0d/417745ed75d414176e50310087b43299a3e611e75c379ff998f60f2ca1a8/cython-3.1.2-cp312-cp312-win32.whl", hash = "sha256:12c5902f105e43ca9af7874cdf87a23627f98c15d5a4f6d38bc9d334845145c0", size = 2487734, upload-time = "2025-06-09T07:10:07.591Z" }, - { url = "https://files.pythonhosted.org/packages/8e/82/df61d09ab81979ba171a8252af8fb8a3b26a0f19d1330c2679c11fe41667/cython-3.1.2-cp312-cp312-win_amd64.whl", hash = "sha256:06789eb7bd2e55b38b9dd349e9309f794aee0fed99c26ea5c9562d463877763f", size = 2695542, upload-time = "2025-06-09T07:10:09.545Z" }, - { url = "https://files.pythonhosted.org/packages/25/d6/ef8557d5e75cc57d55df579af4976935ee111a85bbee4a5b72354e257066/cython-3.1.2-py3-none-any.whl", hash = "sha256:d23fd7ffd7457205f08571a42b108a3cf993e83a59fe4d72b42e6fc592cf2639", size = 1224753, upload-time = "2025-06-09T07:08:44.849Z" }, +version = "3.1.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/18/ab/915337fb39ab4f4539a313df38fc69938df3bf14141b90d61dfd5c2919de/cython-3.1.3.tar.gz", hash = "sha256:10ee785e42328924b78f75a74f66a813cb956b4a9bc91c44816d089d5934c089", size = 3186689, upload-time = "2025-08-13T06:19:13.619Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/b5/51/54f5d1bed7b7d003d0584996a030542497aeb05b9241782c217ea71061f5/cython-3.1.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:4b3b2f6587b42efdece2d174a2aa4234da4524cc6673f3955c2e62b60c6d11fd", size = 3002973, upload-time = "2025-08-13T06:19:50.777Z" }, + { url = "https://files.pythonhosted.org/packages/05/07/b4043fed60070ee21b0d9ff3a877d2ecdc79231e55119ce852b79b690306/cython-3.1.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:963cf640d049fcca1cefd62d1653f859892d6dc8e4d958eb49a5babc491de6a1", size = 2865389, upload-time = "2025-08-13T06:19:52.675Z" }, + { url = "https://files.pythonhosted.org/packages/b4/e3/67d349b5310a40f281e153e826ca24d9f7ba2997c06800eda781253dccfd/cython-3.1.3-cp311-cp311-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:2ab05d1bf2d5522ecff35d94ca233b77db2300413597c3ca0b6448377fa4bd7c", size = 3410316, upload-time = "2025-08-13T06:19:55.217Z" }, + { url = "https://files.pythonhosted.org/packages/49/c4/84aae921135174111091547fa726ea5f8bba718cd12b2589a70c2aab8d5c/cython-3.1.3-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:cd517e3be052fb49443585b01f02f46080b3408e32c1108a0fdc4cc25b3c9d30", size = 3189568, upload-time = "2025-08-13T06:19:57.503Z" }, + { url = "https://files.pythonhosted.org/packages/e2/85/1bf18883f1a1f656ad83a671e54553caedb1ee2f39a3e792a14aa82557a2/cython-3.1.3-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a48e2180d74e3c528561d85b48f9a939a429537f9ea8aac7fb16180e7bff47e2", size = 3312649, upload-time = "2025-08-13T06:19:59.894Z" }, + { url = "https://files.pythonhosted.org/packages/68/da/cc1373decc0d14a25f1b434f47de5e27696f3092319aa5e19fcf84157415/cython-3.1.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:e7c9daa90b15f59aa2a0d638ac1b36777a7e80122099952a0295c71190ce14bc", size = 3203821, upload-time = "2025-08-13T06:20:02.124Z" }, + { url = "https://files.pythonhosted.org/packages/0a/32/e10582d6f7b02ee63607f388dbbd34e329c54559c85961ddc5c655266519/cython-3.1.3-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:08ac646ff42781827f23b7a9b61669cdb92055f52724cd8cbe0e1defc56fce2e", size = 3426853, upload-time = "2025-08-13T06:20:04.474Z" }, + { url = "https://files.pythonhosted.org/packages/e0/da/5b0d1b5a4c7622ec812ad9374c9c6b426d69818f13f51e36f4f25ca01c86/cython-3.1.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:bb0e0e7fceaffa22e4dc9600f7f75998eef5cc6ac5a8c0733b482851ba765ef2", size = 3328872, upload-time = "2025-08-13T06:20:06.834Z" }, + { url = "https://files.pythonhosted.org/packages/b0/5f/f102f6c8d27338f0baf094754c67f920828a19612053abc903e66f84506f/cython-3.1.3-cp311-cp311-win32.whl", hash = "sha256:42b1c3ebe36a52e2a8e939c0651e9ca5d30b81d03f800bbf0499deb0503ab565", size = 2480850, upload-time = "2025-08-13T06:20:08.988Z" }, + { url = "https://files.pythonhosted.org/packages/b7/60/415d0f0f7c2e227707baec11c968387d33507d2eb7f26a2950a323c705e5/cython-3.1.3-cp311-cp311-win_amd64.whl", hash = "sha256:34a973844998281951bf54cdd0b6a9946ba03ba94580820738583a00da167d8f", size = 2712560, upload-time = "2025-08-13T06:20:11.877Z" }, + { url = "https://files.pythonhosted.org/packages/79/26/f433fdfd5182b9231819a99acc49a1f856669532306e7a38dce63ba7297e/cython-3.1.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:849ef3d15d4354e5f74cdb6d3c80d80b03209b3bf1f4ff93315890b19da18944", size = 3014237, upload-time = "2025-08-13T06:20:13.77Z" }, + { url = "https://files.pythonhosted.org/packages/e5/6c/1bebf44f5f177f8c750e608f82c08cd699b8f28cc233e799379bfcf2a2c2/cython-3.1.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:93dd0f62a3f8e93166d8584f8b243180d681ba8fed1f530b55d5f70c348c5797", size = 2844261, upload-time = "2025-08-13T06:20:15.619Z" }, + { url = "https://files.pythonhosted.org/packages/c7/74/983005ce5954f6dc8360b105a561e51a60ea619c53296afac98253d1c9d7/cython-3.1.3-cp312-cp312-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:ff4a2cb84798faffb3988bd94636c3ad31a95ff44ef017f09121abffc56f84cf", size = 3388846, upload-time = "2025-08-13T06:20:17.679Z" }, + { url = "https://files.pythonhosted.org/packages/68/50/dbe7edefe9b652bc72d49da07785173e89197b9a2d64a2ac45da9795eccf/cython-3.1.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:4b05319e36f34d5388deea5cc2bcfd65f9ebf76f4ea050829421a69625dbba4a", size = 3167022, upload-time = "2025-08-13T06:20:19.863Z" }, + { url = "https://files.pythonhosted.org/packages/4a/55/b50548b77203e22262002feae23a172f95282b4b8deb5ad104f08e3dc20d/cython-3.1.3-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:7ac902a17934a6da46f80755f49413bc4c03a569ae3c834f5d66da7288ba7e6c", size = 3317782, upload-time = "2025-08-13T06:20:21.962Z" }, + { url = "https://files.pythonhosted.org/packages/f6/1b/20a97507d528dc330d67be4fbad6bc767c681d56192bce8f7117a187b2ad/cython-3.1.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:7d7a555a864b1b08576f9e8a67f3789796a065837544f9f683ebf3188012fdbd", size = 3179818, upload-time = "2025-08-13T06:20:24.419Z" }, + { url = "https://files.pythonhosted.org/packages/43/a5/7b32a19c4c6bb0e2cc7ae52269b6b23a42f67f730e4abd4f8dca63660f7a/cython-3.1.3-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:b827ce7d97ef8624adcf2bdda594b3dcb6c9b4f124d8f72001d8aea27d69dc1c", size = 3403206, upload-time = "2025-08-13T06:20:26.846Z" }, + { url = "https://files.pythonhosted.org/packages/ba/e1/08cfd4c5e99f79e62d4a7b0009bbd906748633270935c8a55eee51fead76/cython-3.1.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:7851107204085f4f02d0eb6b660ddcad2ce4846e8b7a1eaba724a0bd3cd68a6b", size = 3327837, upload-time = "2025-08-13T06:20:28.946Z" }, + { url = "https://files.pythonhosted.org/packages/23/1b/f3d384be86fa2a6e110b42f42bf97295a513197aaa5532f451c73bf5b48e/cython-3.1.3-cp312-cp312-win32.whl", hash = "sha256:ed20f1b45b2da5a4f8e71a80025bca1cdc96ba35820b0b17658a4a025be920b0", size = 2485990, upload-time = "2025-08-13T06:20:31.517Z" }, + { url = "https://files.pythonhosted.org/packages/de/f0/17cff75e3c141bda73d770f7412632f53e55778d3bfdadfeec4dd3a7d1d6/cython-3.1.3-cp312-cp312-win_amd64.whl", hash = "sha256:dc4ca0f4dec55124cd79ddcfc555be1cbe0092cc99bcf1403621d17b9c6218bb", size = 2704002, upload-time = "2025-08-13T06:20:33.773Z" }, + { url = "https://files.pythonhosted.org/packages/56/c8/46ac27096684f33e27dab749ef43c6b0119c6a0d852971eaefb73256dc4c/cython-3.1.3-py3-none-any.whl", hash = "sha256:d13025b34f72f77bf7f65c1cd628914763e6c285f4deb934314c922b91e6be5a", size = 1225725, upload-time = "2025-08-13T06:19:09.593Z" }, ] [[package]] @@ -505,36 +501,36 @@ wheels = [ [[package]] name = "filelock" -version = "3.18.0" +version = "3.19.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/0a/10/c23352565a6544bdc5353e0b15fc1c563352101f30e24bf500207a54df9a/filelock-3.18.0.tar.gz", hash = "sha256:adbc88eabb99d2fec8c9c1b229b171f18afa655400173ddc653d5d01501fb9f2", size = 18075, upload-time = "2025-03-14T07:11:40.47Z" } +sdist = { url = "https://files.pythonhosted.org/packages/40/bb/0ab3e58d22305b6f5440629d20683af28959bf793d98d11950e305c1c326/filelock-3.19.1.tar.gz", hash = "sha256:66eda1888b0171c998b35be2bcc0f6d75c388a7ce20c3f3f37aa8e96c2dddf58", size = 17687, upload-time = "2025-08-14T16:56:03.016Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/4d/36/2a115987e2d8c300a974597416d9de88f2444426de9571f4b59b2cca3acc/filelock-3.18.0-py3-none-any.whl", hash = "sha256:c401f4f8377c4464e6db25fff06205fd89bdd83b65eb0488ed1b160f780e21de", size = 16215, upload-time = "2025-03-14T07:11:39.145Z" }, + { url = "https://files.pythonhosted.org/packages/42/14/42b2651a2f46b022ccd948bca9f2d5af0fd8929c4eec235b8d6d844fbe67/filelock-3.19.1-py3-none-any.whl", hash = "sha256:d38e30481def20772f5baf097c122c3babc4fcdb7e14e57049eb9d88c6dc017d", size = 15988, upload-time = "2025-08-14T16:56:01.633Z" }, ] [[package]] name = "fonttools" -version = "4.59.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/8a/27/ec3c723bfdf86f34c5c82bf6305df3e0f0d8ea798d2d3a7cb0c0a866d286/fonttools-4.59.0.tar.gz", hash = "sha256:be392ec3529e2f57faa28709d60723a763904f71a2b63aabe14fee6648fe3b14", size = 3532521, upload-time = "2025-07-16T12:04:54.613Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/06/96/520733d9602fa1bf6592e5354c6721ac6fc9ea72bc98d112d0c38b967199/fonttools-4.59.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:841b2186adce48903c0fef235421ae21549020eca942c1da773ac380b056ab3c", size = 2782387, upload-time = "2025-07-16T12:03:51.424Z" }, - { url = "https://files.pythonhosted.org/packages/87/6a/170fce30b9bce69077d8eec9bea2cfd9f7995e8911c71be905e2eba6368b/fonttools-4.59.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:9bcc1e77fbd1609198966ded6b2a9897bd6c6bcbd2287a2fc7d75f1a254179c5", size = 2342194, upload-time = "2025-07-16T12:03:53.295Z" }, - { url = "https://files.pythonhosted.org/packages/b0/b6/7c8166c0066856f1408092f7968ac744060cf72ca53aec9036106f57eeca/fonttools-4.59.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:37c377f7cb2ab2eca8a0b319c68146d34a339792f9420fca6cd49cf28d370705", size = 5032333, upload-time = "2025-07-16T12:03:55.177Z" }, - { url = "https://files.pythonhosted.org/packages/eb/0c/707c5a19598eafcafd489b73c4cb1c142102d6197e872f531512d084aa76/fonttools-4.59.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:fa39475eaccb98f9199eccfda4298abaf35ae0caec676ffc25b3a5e224044464", size = 4974422, upload-time = "2025-07-16T12:03:57.406Z" }, - { url = "https://files.pythonhosted.org/packages/f6/e7/6d33737d9fe632a0f59289b6f9743a86d2a9d0673de2a0c38c0f54729822/fonttools-4.59.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d3972b13148c1d1fbc092b27678a33b3080d1ac0ca305742b0119b75f9e87e38", size = 5010631, upload-time = "2025-07-16T12:03:59.449Z" }, - { url = "https://files.pythonhosted.org/packages/63/e1/a4c3d089ab034a578820c8f2dff21ef60daf9668034a1e4fb38bb1cc3398/fonttools-4.59.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:a408c3c51358c89b29cfa5317cf11518b7ce5de1717abb55c5ae2d2921027de6", size = 5122198, upload-time = "2025-07-16T12:04:01.542Z" }, - { url = "https://files.pythonhosted.org/packages/09/77/ca82b9c12fa4de3c520b7760ee61787640cf3fde55ef1b0bfe1de38c8153/fonttools-4.59.0-cp311-cp311-win32.whl", hash = "sha256:6770d7da00f358183d8fd5c4615436189e4f683bdb6affb02cad3d221d7bb757", size = 2214216, upload-time = "2025-07-16T12:04:03.515Z" }, - { url = "https://files.pythonhosted.org/packages/ab/25/5aa7ca24b560b2f00f260acf32c4cf29d7aaf8656e159a336111c18bc345/fonttools-4.59.0-cp311-cp311-win_amd64.whl", hash = "sha256:84fc186980231a287b28560d3123bd255d3c6b6659828c642b4cf961e2b923d0", size = 2261879, upload-time = "2025-07-16T12:04:05.015Z" }, - { url = "https://files.pythonhosted.org/packages/e2/77/b1c8af22f4265e951cd2e5535dbef8859efcef4fb8dee742d368c967cddb/fonttools-4.59.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f9b3a78f69dcbd803cf2fb3f972779875b244c1115481dfbdd567b2c22b31f6b", size = 2767562, upload-time = "2025-07-16T12:04:06.895Z" }, - { url = "https://files.pythonhosted.org/packages/ff/5a/aeb975699588176bb357e8b398dfd27e5d3a2230d92b81ab8cbb6187358d/fonttools-4.59.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:57bb7e26928573ee7c6504f54c05860d867fd35e675769f3ce01b52af38d48e2", size = 2335168, upload-time = "2025-07-16T12:04:08.695Z" }, - { url = "https://files.pythonhosted.org/packages/54/97/c6101a7e60ae138c4ef75b22434373a0da50a707dad523dd19a4889315bf/fonttools-4.59.0-cp312-cp312-manylinux1_x86_64.manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:4536f2695fe5c1ffb528d84a35a7d3967e5558d2af58b4775e7ab1449d65767b", size = 4909850, upload-time = "2025-07-16T12:04:10.761Z" }, - { url = "https://files.pythonhosted.org/packages/bd/6c/fa4d18d641054f7bff878cbea14aa9433f292b9057cb1700d8e91a4d5f4f/fonttools-4.59.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:885bde7d26e5b40e15c47bd5def48b38cbd50830a65f98122a8fb90962af7cd1", size = 4955131, upload-time = "2025-07-16T12:04:12.846Z" }, - { url = "https://files.pythonhosted.org/packages/20/5c/331947fc1377deb928a69bde49f9003364f5115e5cbe351eea99e39412a2/fonttools-4.59.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6801aeddb6acb2c42eafa45bc1cb98ba236871ae6f33f31e984670b749a8e58e", size = 4899667, upload-time = "2025-07-16T12:04:14.558Z" }, - { url = "https://files.pythonhosted.org/packages/8a/46/b66469dfa26b8ff0baa7654b2cc7851206c6d57fe3abdabbaab22079a119/fonttools-4.59.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:31003b6a10f70742a63126b80863ab48175fb8272a18ca0846c0482968f0588e", size = 5051349, upload-time = "2025-07-16T12:04:16.388Z" }, - { url = "https://files.pythonhosted.org/packages/2e/05/ebfb6b1f3a4328ab69787d106a7d92ccde77ce66e98659df0f9e3f28d93d/fonttools-4.59.0-cp312-cp312-win32.whl", hash = "sha256:fbce6dae41b692a5973d0f2158f782b9ad05babc2c2019a970a1094a23909b1b", size = 2201315, upload-time = "2025-07-16T12:04:18.557Z" }, - { url = "https://files.pythonhosted.org/packages/09/45/d2bdc9ea20bbadec1016fd0db45696d573d7a26d95ab5174ffcb6d74340b/fonttools-4.59.0-cp312-cp312-win_amd64.whl", hash = "sha256:332bfe685d1ac58ca8d62b8d6c71c2e52a6c64bc218dc8f7825c9ea51385aa01", size = 2249408, upload-time = "2025-07-16T12:04:20.489Z" }, - { url = "https://files.pythonhosted.org/packages/d0/9c/df0ef2c51845a13043e5088f7bb988ca6cd5bb82d5d4203d6a158aa58cf2/fonttools-4.59.0-py3-none-any.whl", hash = "sha256:241313683afd3baacb32a6bd124d0bce7404bc5280e12e291bae1b9bba28711d", size = 1128050, upload-time = "2025-07-16T12:04:52.687Z" }, +version = "4.59.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/11/7f/29c9c3fe4246f6ad96fee52b88d0dc3a863c7563b0afc959e36d78b965dc/fonttools-4.59.1.tar.gz", hash = "sha256:74995b402ad09822a4c8002438e54940d9f1ecda898d2bb057729d7da983e4cb", size = 3534394, upload-time = "2025-08-14T16:28:14.266Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/34/62/9667599561f623d4a523cc9eb4f66f3b94b6155464110fa9aebbf90bbec7/fonttools-4.59.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4909cce2e35706f3d18c54d3dcce0414ba5e0fb436a454dffec459c61653b513", size = 2778815, upload-time = "2025-08-14T16:26:28.484Z" }, + { url = "https://files.pythonhosted.org/packages/8f/78/cc25bcb2ce86033a9df243418d175e58f1956a35047c685ef553acae67d6/fonttools-4.59.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:efbec204fa9f877641747f2d9612b2b656071390d7a7ef07a9dbf0ecf9c7195c", size = 2341631, upload-time = "2025-08-14T16:26:30.396Z" }, + { url = "https://files.pythonhosted.org/packages/a4/cc/fcbb606dd6871f457ac32f281c20bcd6cc77d9fce77b5a4e2b2afab1f500/fonttools-4.59.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:39dfd42cc2dc647b2c5469bc7a5b234d9a49e72565b96dd14ae6f11c2c59ef15", size = 5022222, upload-time = "2025-08-14T16:26:32.447Z" }, + { url = "https://files.pythonhosted.org/packages/61/96/c0b1cf2b74d08eb616a80dbf5564351fe4686147291a25f7dce8ace51eb3/fonttools-4.59.1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:b11bc177a0d428b37890825d7d025040d591aa833f85f8d8878ed183354f47df", size = 4966512, upload-time = "2025-08-14T16:26:34.621Z" }, + { url = "https://files.pythonhosted.org/packages/a4/26/51ce2e3e0835ffc2562b1b11d1fb9dafd0aca89c9041b64a9e903790a761/fonttools-4.59.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:5b9b4c35b3be45e5bc774d3fc9608bbf4f9a8d371103b858c80edbeed31dd5aa", size = 5001645, upload-time = "2025-08-14T16:26:36.876Z" }, + { url = "https://files.pythonhosted.org/packages/36/11/ef0b23f4266349b6d5ccbd1a07b7adc998d5bce925792aa5d1ec33f593e3/fonttools-4.59.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:01158376b8a418a0bae9625c476cebfcfcb5e6761e9d243b219cd58341e7afbb", size = 5113777, upload-time = "2025-08-14T16:26:39.002Z" }, + { url = "https://files.pythonhosted.org/packages/d0/da/b398fe61ef433da0a0472cdb5d4399124f7581ffe1a31b6242c91477d802/fonttools-4.59.1-cp311-cp311-win32.whl", hash = "sha256:cf7c5089d37787387123f1cb8f1793a47c5e1e3d1e4e7bfbc1cc96e0f925eabe", size = 2215076, upload-time = "2025-08-14T16:26:41.196Z" }, + { url = "https://files.pythonhosted.org/packages/94/bd/e2624d06ab94e41c7c77727b2941f1baed7edb647e63503953e6888020c9/fonttools-4.59.1-cp311-cp311-win_amd64.whl", hash = "sha256:c866eef7a0ba320486ade6c32bfc12813d1a5db8567e6904fb56d3d40acc5116", size = 2262779, upload-time = "2025-08-14T16:26:43.483Z" }, + { url = "https://files.pythonhosted.org/packages/ac/fe/6e069cc4cb8881d164a9bd956e9df555bc62d3eb36f6282e43440200009c/fonttools-4.59.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:43ab814bbba5f02a93a152ee61a04182bb5809bd2bc3609f7822e12c53ae2c91", size = 2769172, upload-time = "2025-08-14T16:26:45.729Z" }, + { url = "https://files.pythonhosted.org/packages/b9/98/ec4e03f748fefa0dd72d9d95235aff6fef16601267f4a2340f0e16b9330f/fonttools-4.59.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:4f04c3ffbfa0baafcbc550657cf83657034eb63304d27b05cff1653b448ccff6", size = 2337281, upload-time = "2025-08-14T16:26:47.921Z" }, + { url = "https://files.pythonhosted.org/packages/8b/b1/890360a7e3d04a30ba50b267aca2783f4c1364363797e892e78a4f036076/fonttools-4.59.1-cp312-cp312-manylinux1_x86_64.manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:d601b153e51a5a6221f0d4ec077b6bfc6ac35bfe6c19aeaa233d8990b2b71726", size = 4909215, upload-time = "2025-08-14T16:26:49.682Z" }, + { url = "https://files.pythonhosted.org/packages/8a/ec/2490599550d6c9c97a44c1e36ef4de52d6acf742359eaa385735e30c05c4/fonttools-4.59.1-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c735e385e30278c54f43a0d056736942023c9043f84ee1021eff9fd616d17693", size = 4951958, upload-time = "2025-08-14T16:26:51.616Z" }, + { url = "https://files.pythonhosted.org/packages/d1/40/bd053f6f7634234a9b9805ff8ae4f32df4f2168bee23cafd1271ba9915a9/fonttools-4.59.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1017413cdc8555dce7ee23720da490282ab7ec1cf022af90a241f33f9a49afc4", size = 4894738, upload-time = "2025-08-14T16:26:53.836Z" }, + { url = "https://files.pythonhosted.org/packages/ac/a1/3cd12a010d288325a7cfcf298a84825f0f9c29b01dee1baba64edfe89257/fonttools-4.59.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:5c6d8d773470a5107052874341ed3c487c16ecd179976d81afed89dea5cd7406", size = 5045983, upload-time = "2025-08-14T16:26:56.153Z" }, + { url = "https://files.pythonhosted.org/packages/a2/af/8a2c3f6619cc43cf87951405337cc8460d08a4e717bb05eaa94b335d11dc/fonttools-4.59.1-cp312-cp312-win32.whl", hash = "sha256:2a2d0d33307f6ad3a2086a95dd607c202ea8852fa9fb52af9b48811154d1428a", size = 2203407, upload-time = "2025-08-14T16:26:58.165Z" }, + { url = "https://files.pythonhosted.org/packages/8e/f2/a19b874ddbd3ebcf11d7e25188ef9ac3f68b9219c62263acb34aca8cde05/fonttools-4.59.1-cp312-cp312-win_amd64.whl", hash = "sha256:0b9e4fa7eaf046ed6ac470f6033d52c052481ff7a6e0a92373d14f556f298dc0", size = 2251561, upload-time = "2025-08-14T16:27:00.646Z" }, + { url = "https://files.pythonhosted.org/packages/0f/64/9d606e66d498917cd7a2ff24f558010d42d6fd4576d9dd57f0bd98333f5a/fonttools-4.59.1-py3-none-any.whl", hash = "sha256:647db657073672a8330608970a984d51573557f328030566521bc03415535042", size = 1130094, upload-time = "2025-08-14T16:28:12.048Z" }, ] [[package]] @@ -717,40 +713,41 @@ wheels = [ [[package]] name = "kiwisolver" -version = "1.4.8" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/82/59/7c91426a8ac292e1cdd53a63b6d9439abd573c875c3f92c146767dd33faf/kiwisolver-1.4.8.tar.gz", hash = "sha256:23d5f023bdc8c7e54eb65f03ca5d5bb25b601eac4d7f1a042888a1f45237987e", size = 97538, upload-time = "2024-12-24T18:30:51.519Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/da/ed/c913ee28936c371418cb167b128066ffb20bbf37771eecc2c97edf8a6e4c/kiwisolver-1.4.8-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a4d3601908c560bdf880f07d94f31d734afd1bb71e96585cace0e38ef44c6d84", size = 124635, upload-time = "2024-12-24T18:28:51.826Z" }, - { url = "https://files.pythonhosted.org/packages/4c/45/4a7f896f7467aaf5f56ef093d1f329346f3b594e77c6a3c327b2d415f521/kiwisolver-1.4.8-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:856b269c4d28a5c0d5e6c1955ec36ebfd1651ac00e1ce0afa3e28da95293b561", size = 66717, upload-time = "2024-12-24T18:28:54.256Z" }, - { url = "https://files.pythonhosted.org/packages/5f/b4/c12b3ac0852a3a68f94598d4c8d569f55361beef6159dce4e7b624160da2/kiwisolver-1.4.8-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c2b9a96e0f326205af81a15718a9073328df1173a2619a68553decb7097fd5d7", size = 65413, upload-time = "2024-12-24T18:28:55.184Z" }, - { url = "https://files.pythonhosted.org/packages/a9/98/1df4089b1ed23d83d410adfdc5947245c753bddfbe06541c4aae330e9e70/kiwisolver-1.4.8-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c5020c83e8553f770cb3b5fc13faac40f17e0b205bd237aebd21d53d733adb03", size = 1343994, upload-time = "2024-12-24T18:28:57.493Z" }, - { url = "https://files.pythonhosted.org/packages/8d/bf/b4b169b050c8421a7c53ea1ea74e4ef9c335ee9013216c558a047f162d20/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dace81d28c787956bfbfbbfd72fdcef014f37d9b48830829e488fdb32b49d954", size = 1434804, upload-time = "2024-12-24T18:29:00.077Z" }, - { url = "https://files.pythonhosted.org/packages/66/5a/e13bd341fbcf73325ea60fdc8af752addf75c5079867af2e04cc41f34434/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:11e1022b524bd48ae56c9b4f9296bce77e15a2e42a502cceba602f804b32bb79", size = 1450690, upload-time = "2024-12-24T18:29:01.401Z" }, - { url = "https://files.pythonhosted.org/packages/9b/4f/5955dcb376ba4a830384cc6fab7d7547bd6759fe75a09564910e9e3bb8ea/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3b9b4d2892fefc886f30301cdd80debd8bb01ecdf165a449eb6e78f79f0fabd6", size = 1376839, upload-time = "2024-12-24T18:29:02.685Z" }, - { url = "https://files.pythonhosted.org/packages/3a/97/5edbed69a9d0caa2e4aa616ae7df8127e10f6586940aa683a496c2c280b9/kiwisolver-1.4.8-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3a96c0e790ee875d65e340ab383700e2b4891677b7fcd30a699146f9384a2bb0", size = 1435109, upload-time = "2024-12-24T18:29:04.113Z" }, - { url = "https://files.pythonhosted.org/packages/13/fc/e756382cb64e556af6c1809a1bbb22c141bbc2445049f2da06b420fe52bf/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:23454ff084b07ac54ca8be535f4174170c1094a4cff78fbae4f73a4bcc0d4dab", size = 2245269, upload-time = "2024-12-24T18:29:05.488Z" }, - { url = "https://files.pythonhosted.org/packages/76/15/e59e45829d7f41c776d138245cabae6515cb4eb44b418f6d4109c478b481/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:87b287251ad6488e95b4f0b4a79a6d04d3ea35fde6340eb38fbd1ca9cd35bbbc", size = 2393468, upload-time = "2024-12-24T18:29:06.79Z" }, - { url = "https://files.pythonhosted.org/packages/e9/39/483558c2a913ab8384d6e4b66a932406f87c95a6080112433da5ed668559/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:b21dbe165081142b1232a240fc6383fd32cdd877ca6cc89eab93e5f5883e1c25", size = 2355394, upload-time = "2024-12-24T18:29:08.24Z" }, - { url = "https://files.pythonhosted.org/packages/01/aa/efad1fbca6570a161d29224f14b082960c7e08268a133fe5dc0f6906820e/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:768cade2c2df13db52475bd28d3a3fac8c9eff04b0e9e2fda0f3760f20b3f7fc", size = 2490901, upload-time = "2024-12-24T18:29:09.653Z" }, - { url = "https://files.pythonhosted.org/packages/c9/4f/15988966ba46bcd5ab9d0c8296914436720dd67fca689ae1a75b4ec1c72f/kiwisolver-1.4.8-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d47cfb2650f0e103d4bf68b0b5804c68da97272c84bb12850d877a95c056bd67", size = 2312306, upload-time = "2024-12-24T18:29:12.644Z" }, - { url = "https://files.pythonhosted.org/packages/2d/27/bdf1c769c83f74d98cbc34483a972f221440703054894a37d174fba8aa68/kiwisolver-1.4.8-cp311-cp311-win_amd64.whl", hash = "sha256:ed33ca2002a779a2e20eeb06aea7721b6e47f2d4b8a8ece979d8ba9e2a167e34", size = 71966, upload-time = "2024-12-24T18:29:14.089Z" }, - { url = "https://files.pythonhosted.org/packages/4a/c9/9642ea855604aeb2968a8e145fc662edf61db7632ad2e4fb92424be6b6c0/kiwisolver-1.4.8-cp311-cp311-win_arm64.whl", hash = "sha256:16523b40aab60426ffdebe33ac374457cf62863e330a90a0383639ce14bf44b2", size = 65311, upload-time = "2024-12-24T18:29:15.892Z" }, - { url = "https://files.pythonhosted.org/packages/fc/aa/cea685c4ab647f349c3bc92d2daf7ae34c8e8cf405a6dcd3a497f58a2ac3/kiwisolver-1.4.8-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d6af5e8815fd02997cb6ad9bbed0ee1e60014438ee1a5c2444c96f87b8843502", size = 124152, upload-time = "2024-12-24T18:29:16.85Z" }, - { url = "https://files.pythonhosted.org/packages/c5/0b/8db6d2e2452d60d5ebc4ce4b204feeb16176a851fd42462f66ade6808084/kiwisolver-1.4.8-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:bade438f86e21d91e0cf5dd7c0ed00cda0f77c8c1616bd83f9fc157fa6760d31", size = 66555, upload-time = "2024-12-24T18:29:19.146Z" }, - { url = "https://files.pythonhosted.org/packages/60/26/d6a0db6785dd35d3ba5bf2b2df0aedc5af089962c6eb2cbf67a15b81369e/kiwisolver-1.4.8-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:b83dc6769ddbc57613280118fb4ce3cd08899cc3369f7d0e0fab518a7cf37fdb", size = 65067, upload-time = "2024-12-24T18:29:20.096Z" }, - { url = "https://files.pythonhosted.org/packages/c9/ed/1d97f7e3561e09757a196231edccc1bcf59d55ddccefa2afc9c615abd8e0/kiwisolver-1.4.8-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:111793b232842991be367ed828076b03d96202c19221b5ebab421ce8bcad016f", size = 1378443, upload-time = "2024-12-24T18:29:22.843Z" }, - { url = "https://files.pythonhosted.org/packages/29/61/39d30b99954e6b46f760e6289c12fede2ab96a254c443639052d1b573fbc/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:257af1622860e51b1a9d0ce387bf5c2c4f36a90594cb9514f55b074bcc787cfc", size = 1472728, upload-time = "2024-12-24T18:29:24.463Z" }, - { url = "https://files.pythonhosted.org/packages/0c/3e/804163b932f7603ef256e4a715e5843a9600802bb23a68b4e08c8c0ff61d/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:69b5637c3f316cab1ec1c9a12b8c5f4750a4c4b71af9157645bf32830e39c03a", size = 1478388, upload-time = "2024-12-24T18:29:25.776Z" }, - { url = "https://files.pythonhosted.org/packages/8a/9e/60eaa75169a154700be74f875a4d9961b11ba048bef315fbe89cb6999056/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:782bb86f245ec18009890e7cb8d13a5ef54dcf2ebe18ed65f795e635a96a1c6a", size = 1413849, upload-time = "2024-12-24T18:29:27.202Z" }, - { url = "https://files.pythonhosted.org/packages/bc/b3/9458adb9472e61a998c8c4d95cfdfec91c73c53a375b30b1428310f923e4/kiwisolver-1.4.8-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cc978a80a0db3a66d25767b03688f1147a69e6237175c0f4ffffaaedf744055a", size = 1475533, upload-time = "2024-12-24T18:29:28.638Z" }, - { url = "https://files.pythonhosted.org/packages/e4/7a/0a42d9571e35798de80aef4bb43a9b672aa7f8e58643d7bd1950398ffb0a/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:36dbbfd34838500a31f52c9786990d00150860e46cd5041386f217101350f0d3", size = 2268898, upload-time = "2024-12-24T18:29:30.368Z" }, - { url = "https://files.pythonhosted.org/packages/d9/07/1255dc8d80271400126ed8db35a1795b1a2c098ac3a72645075d06fe5c5d/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:eaa973f1e05131de5ff3569bbba7f5fd07ea0595d3870ed4a526d486fe57fa1b", size = 2425605, upload-time = "2024-12-24T18:29:33.151Z" }, - { url = "https://files.pythonhosted.org/packages/84/df/5a3b4cf13780ef6f6942df67b138b03b7e79e9f1f08f57c49957d5867f6e/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:a66f60f8d0c87ab7f59b6fb80e642ebb29fec354a4dfad687ca4092ae69d04f4", size = 2375801, upload-time = "2024-12-24T18:29:34.584Z" }, - { url = "https://files.pythonhosted.org/packages/8f/10/2348d068e8b0f635c8c86892788dac7a6b5c0cb12356620ab575775aad89/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:858416b7fb777a53f0c59ca08190ce24e9abbd3cffa18886a5781b8e3e26f65d", size = 2520077, upload-time = "2024-12-24T18:29:36.138Z" }, - { url = "https://files.pythonhosted.org/packages/32/d8/014b89fee5d4dce157d814303b0fce4d31385a2af4c41fed194b173b81ac/kiwisolver-1.4.8-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:085940635c62697391baafaaeabdf3dd7a6c3643577dde337f4d66eba021b2b8", size = 2338410, upload-time = "2024-12-24T18:29:39.991Z" }, - { url = "https://files.pythonhosted.org/packages/bd/72/dfff0cc97f2a0776e1c9eb5bef1ddfd45f46246c6533b0191887a427bca5/kiwisolver-1.4.8-cp312-cp312-win_amd64.whl", hash = "sha256:01c3d31902c7db5fb6182832713d3b4122ad9317c2c5877d0539227d96bb2e50", size = 71853, upload-time = "2024-12-24T18:29:42.006Z" }, - { url = "https://files.pythonhosted.org/packages/dc/85/220d13d914485c0948a00f0b9eb419efaf6da81b7d72e88ce2391f7aed8d/kiwisolver-1.4.8-cp312-cp312-win_arm64.whl", hash = "sha256:a3c44cb68861de93f0c4a8175fbaa691f0aa22550c331fefef02b618a9dcb476", size = 65424, upload-time = "2024-12-24T18:29:44.38Z" }, +version = "1.4.9" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/5c/3c/85844f1b0feb11ee581ac23fe5fce65cd049a200c1446708cc1b7f922875/kiwisolver-1.4.9.tar.gz", hash = "sha256:c3b22c26c6fd6811b0ae8363b95ca8ce4ea3c202d3d0975b2914310ceb1bcc4d", size = 97564, upload-time = "2025-08-10T21:27:49.279Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/6f/ab/c80b0d5a9d8a1a65f4f815f2afff9798b12c3b9f31f1d304dd233dd920e2/kiwisolver-1.4.9-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:eb14a5da6dc7642b0f3a18f13654847cd8b7a2550e2645a5bda677862b03ba16", size = 124167, upload-time = "2025-08-10T21:25:53.403Z" }, + { url = "https://files.pythonhosted.org/packages/a0/c0/27fe1a68a39cf62472a300e2879ffc13c0538546c359b86f149cc19f6ac3/kiwisolver-1.4.9-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:39a219e1c81ae3b103643d2aedb90f1ef22650deb266ff12a19e7773f3e5f089", size = 66579, upload-time = "2025-08-10T21:25:54.79Z" }, + { url = "https://files.pythonhosted.org/packages/31/a2/a12a503ac1fd4943c50f9822678e8015a790a13b5490354c68afb8489814/kiwisolver-1.4.9-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:2405a7d98604b87f3fc28b1716783534b1b4b8510d8142adca34ee0bc3c87543", size = 65309, upload-time = "2025-08-10T21:25:55.76Z" }, + { url = "https://files.pythonhosted.org/packages/66/e1/e533435c0be77c3f64040d68d7a657771194a63c279f55573188161e81ca/kiwisolver-1.4.9-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:dc1ae486f9abcef254b5618dfb4113dd49f94c68e3e027d03cf0143f3f772b61", size = 1435596, upload-time = "2025-08-10T21:25:56.861Z" }, + { url = "https://files.pythonhosted.org/packages/67/1e/51b73c7347f9aabdc7215aa79e8b15299097dc2f8e67dee2b095faca9cb0/kiwisolver-1.4.9-cp311-cp311-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:8a1f570ce4d62d718dce3f179ee78dac3b545ac16c0c04bb363b7607a949c0d1", size = 1246548, upload-time = "2025-08-10T21:25:58.246Z" }, + { url = "https://files.pythonhosted.org/packages/21/aa/72a1c5d1e430294f2d32adb9542719cfb441b5da368d09d268c7757af46c/kiwisolver-1.4.9-cp311-cp311-manylinux_2_24_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:cb27e7b78d716c591e88e0a09a2139c6577865d7f2e152488c2cc6257f460872", size = 1263618, upload-time = "2025-08-10T21:25:59.857Z" }, + { url = "https://files.pythonhosted.org/packages/a3/af/db1509a9e79dbf4c260ce0cfa3903ea8945f6240e9e59d1e4deb731b1a40/kiwisolver-1.4.9-cp311-cp311-manylinux_2_24_s390x.manylinux_2_28_s390x.whl", hash = "sha256:15163165efc2f627eb9687ea5f3a28137217d217ac4024893d753f46bce9de26", size = 1317437, upload-time = "2025-08-10T21:26:01.105Z" }, + { url = "https://files.pythonhosted.org/packages/e0/f2/3ea5ee5d52abacdd12013a94130436e19969fa183faa1e7c7fbc89e9a42f/kiwisolver-1.4.9-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:bdee92c56a71d2b24c33a7d4c2856bd6419d017e08caa7802d2963870e315028", size = 2195742, upload-time = "2025-08-10T21:26:02.675Z" }, + { url = "https://files.pythonhosted.org/packages/6f/9b/1efdd3013c2d9a2566aa6a337e9923a00590c516add9a1e89a768a3eb2fc/kiwisolver-1.4.9-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:412f287c55a6f54b0650bd9b6dce5aceddb95864a1a90c87af16979d37c89771", size = 2290810, upload-time = "2025-08-10T21:26:04.009Z" }, + { url = "https://files.pythonhosted.org/packages/fb/e5/cfdc36109ae4e67361f9bc5b41323648cb24a01b9ade18784657e022e65f/kiwisolver-1.4.9-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:2c93f00dcba2eea70af2be5f11a830a742fe6b579a1d4e00f47760ef13be247a", size = 2461579, upload-time = "2025-08-10T21:26:05.317Z" }, + { url = "https://files.pythonhosted.org/packages/62/86/b589e5e86c7610842213994cdea5add00960076bef4ae290c5fa68589cac/kiwisolver-1.4.9-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:f117e1a089d9411663a3207ba874f31be9ac8eaa5b533787024dc07aeb74f464", size = 2268071, upload-time = "2025-08-10T21:26:06.686Z" }, + { url = "https://files.pythonhosted.org/packages/3b/c6/f8df8509fd1eee6c622febe54384a96cfaf4d43bf2ccec7a0cc17e4715c9/kiwisolver-1.4.9-cp311-cp311-win_amd64.whl", hash = "sha256:be6a04e6c79819c9a8c2373317d19a96048e5a3f90bec587787e86a1153883c2", size = 73840, upload-time = "2025-08-10T21:26:07.94Z" }, + { url = "https://files.pythonhosted.org/packages/e2/2d/16e0581daafd147bc11ac53f032a2b45eabac897f42a338d0a13c1e5c436/kiwisolver-1.4.9-cp311-cp311-win_arm64.whl", hash = "sha256:0ae37737256ba2de764ddc12aed4956460277f00c4996d51a197e72f62f5eec7", size = 65159, upload-time = "2025-08-10T21:26:09.048Z" }, + { url = "https://files.pythonhosted.org/packages/86/c9/13573a747838aeb1c76e3267620daa054f4152444d1f3d1a2324b78255b5/kiwisolver-1.4.9-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ac5a486ac389dddcc5bef4f365b6ae3ffff2c433324fb38dd35e3fab7c957999", size = 123686, upload-time = "2025-08-10T21:26:10.034Z" }, + { url = "https://files.pythonhosted.org/packages/51/ea/2ecf727927f103ffd1739271ca19c424d0e65ea473fbaeea1c014aea93f6/kiwisolver-1.4.9-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:f2ba92255faa7309d06fe44c3a4a97efe1c8d640c2a79a5ef728b685762a6fd2", size = 66460, upload-time = "2025-08-10T21:26:11.083Z" }, + { url = "https://files.pythonhosted.org/packages/5b/5a/51f5464373ce2aeb5194508298a508b6f21d3867f499556263c64c621914/kiwisolver-1.4.9-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:4a2899935e724dd1074cb568ce7ac0dce28b2cd6ab539c8e001a8578eb106d14", size = 64952, upload-time = "2025-08-10T21:26:12.058Z" }, + { url = "https://files.pythonhosted.org/packages/70/90/6d240beb0f24b74371762873e9b7f499f1e02166a2d9c5801f4dbf8fa12e/kiwisolver-1.4.9-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:f6008a4919fdbc0b0097089f67a1eb55d950ed7e90ce2cc3e640abadd2757a04", size = 1474756, upload-time = "2025-08-10T21:26:13.096Z" }, + { url = "https://files.pythonhosted.org/packages/12/42/f36816eaf465220f683fb711efdd1bbf7a7005a2473d0e4ed421389bd26c/kiwisolver-1.4.9-cp312-cp312-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:67bb8b474b4181770f926f7b7d2f8c0248cbcb78b660fdd41a47054b28d2a752", size = 1276404, upload-time = "2025-08-10T21:26:14.457Z" }, + { url = "https://files.pythonhosted.org/packages/2e/64/bc2de94800adc830c476dce44e9b40fd0809cddeef1fde9fcf0f73da301f/kiwisolver-1.4.9-cp312-cp312-manylinux_2_24_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:2327a4a30d3ee07d2fbe2e7933e8a37c591663b96ce42a00bc67461a87d7df77", size = 1294410, upload-time = "2025-08-10T21:26:15.73Z" }, + { url = "https://files.pythonhosted.org/packages/5f/42/2dc82330a70aa8e55b6d395b11018045e58d0bb00834502bf11509f79091/kiwisolver-1.4.9-cp312-cp312-manylinux_2_24_s390x.manylinux_2_28_s390x.whl", hash = "sha256:7a08b491ec91b1d5053ac177afe5290adacf1f0f6307d771ccac5de30592d198", size = 1343631, upload-time = "2025-08-10T21:26:17.045Z" }, + { url = "https://files.pythonhosted.org/packages/22/fd/f4c67a6ed1aab149ec5a8a401c323cee7a1cbe364381bb6c9c0d564e0e20/kiwisolver-1.4.9-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:d8fc5c867c22b828001b6a38d2eaeb88160bf5783c6cb4a5e440efc981ce286d", size = 2224963, upload-time = "2025-08-10T21:26:18.737Z" }, + { url = "https://files.pythonhosted.org/packages/45/aa/76720bd4cb3713314677d9ec94dcc21ced3f1baf4830adde5bb9b2430a5f/kiwisolver-1.4.9-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:3b3115b2581ea35bb6d1f24a4c90af37e5d9b49dcff267eeed14c3893c5b86ab", size = 2321295, upload-time = "2025-08-10T21:26:20.11Z" }, + { url = "https://files.pythonhosted.org/packages/80/19/d3ec0d9ab711242f56ae0dc2fc5d70e298bb4a1f9dfab44c027668c673a1/kiwisolver-1.4.9-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:858e4c22fb075920b96a291928cb7dea5644e94c0ee4fcd5af7e865655e4ccf2", size = 2487987, upload-time = "2025-08-10T21:26:21.49Z" }, + { url = "https://files.pythonhosted.org/packages/39/e9/61e4813b2c97e86b6fdbd4dd824bf72d28bcd8d4849b8084a357bc0dd64d/kiwisolver-1.4.9-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ed0fecd28cc62c54b262e3736f8bb2512d8dcfdc2bcf08be5f47f96bf405b145", size = 2291817, upload-time = "2025-08-10T21:26:22.812Z" }, + { url = "https://files.pythonhosted.org/packages/a0/41/85d82b0291db7504da3c2defe35c9a8a5c9803a730f297bd823d11d5fb77/kiwisolver-1.4.9-cp312-cp312-win_amd64.whl", hash = "sha256:f68208a520c3d86ea51acf688a3e3002615a7f0238002cccc17affecc86a8a54", size = 73895, upload-time = "2025-08-10T21:26:24.37Z" }, + { url = "https://files.pythonhosted.org/packages/e2/92/5f3068cf15ee5cb624a0c7596e67e2a0bb2adee33f71c379054a491d07da/kiwisolver-1.4.9-cp312-cp312-win_arm64.whl", hash = "sha256:2c1a4f57df73965f3f14df20b80ee29e6a7930a57d2d9e8491a25f676e197c60", size = 64992, upload-time = "2025-08-10T21:26:25.732Z" }, + { url = "https://files.pythonhosted.org/packages/a3/0f/36d89194b5a32c054ce93e586d4049b6c2c22887b0eb229c61c68afd3078/kiwisolver-1.4.9-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:720e05574713db64c356e86732c0f3c5252818d05f9df320f0ad8380641acea5", size = 60104, upload-time = "2025-08-10T21:27:43.287Z" }, + { url = "https://files.pythonhosted.org/packages/52/ba/4ed75f59e4658fd21fe7dde1fee0ac397c678ec3befba3fe6482d987af87/kiwisolver-1.4.9-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:17680d737d5335b552994a2008fab4c851bcd7de33094a82067ef3a576ff02fa", size = 58592, upload-time = "2025-08-10T21:27:44.314Z" }, + { url = "https://files.pythonhosted.org/packages/33/01/a8ea7c5ea32a9b45ceeaee051a04c8ed4320f5add3c51bfa20879b765b70/kiwisolver-1.4.9-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:85b5352f94e490c028926ea567fc569c52ec79ce131dadb968d3853e809518c2", size = 80281, upload-time = "2025-08-10T21:27:45.369Z" }, + { url = "https://files.pythonhosted.org/packages/da/e3/dbd2ecdce306f1d07a1aaf324817ee993aab7aee9db47ceac757deabafbe/kiwisolver-1.4.9-pp311-pypy311_pp73-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:464415881e4801295659462c49461a24fb107c140de781d55518c4b80cb6790f", size = 78009, upload-time = "2025-08-10T21:27:46.376Z" }, + { url = "https://files.pythonhosted.org/packages/da/e9/0d4add7873a73e462aeb45c036a2dead2562b825aa46ba326727b3f31016/kiwisolver-1.4.9-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:fb940820c63a9590d31d88b815e7a3aa5915cad3ce735ab45f0c730b39547de1", size = 73929, upload-time = "2025-08-10T21:27:48.236Z" }, ] [[package]] @@ -1024,47 +1021,47 @@ wheels = [ [[package]] name = "multidict" -version = "6.6.3" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/3d/2c/5dad12e82fbdf7470f29bff2171484bf07cb3b16ada60a6589af8f376440/multidict-6.6.3.tar.gz", hash = "sha256:798a9eb12dab0a6c2e29c1de6f3468af5cb2da6053a20dfa3344907eed0937cc", size = 101006, upload-time = "2025-06-30T15:53:46.929Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/08/f0/1a39863ced51f639c81a5463fbfa9eb4df59c20d1a8769ab9ef4ca57ae04/multidict-6.6.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:18f4eba0cbac3546b8ae31e0bbc55b02c801ae3cbaf80c247fcdd89b456ff58c", size = 76445, upload-time = "2025-06-30T15:51:24.01Z" }, - { url = "https://files.pythonhosted.org/packages/c9/0e/a7cfa451c7b0365cd844e90b41e21fab32edaa1e42fc0c9f68461ce44ed7/multidict-6.6.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ef43b5dd842382329e4797c46f10748d8c2b6e0614f46b4afe4aee9ac33159df", size = 44610, upload-time = "2025-06-30T15:51:25.158Z" }, - { url = "https://files.pythonhosted.org/packages/c6/bb/a14a4efc5ee748cc1904b0748be278c31b9295ce5f4d2ef66526f410b94d/multidict-6.6.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:bf9bd1fd5eec01494e0f2e8e446a74a85d5e49afb63d75a9934e4a5423dba21d", size = 44267, upload-time = "2025-06-30T15:51:26.326Z" }, - { url = "https://files.pythonhosted.org/packages/c2/f8/410677d563c2d55e063ef74fe578f9d53fe6b0a51649597a5861f83ffa15/multidict-6.6.3-cp311-cp311-manylinux1_i686.manylinux2014_i686.manylinux_2_17_i686.manylinux_2_5_i686.whl", hash = "sha256:5bd8d6f793a787153956cd35e24f60485bf0651c238e207b9a54f7458b16d539", size = 230004, upload-time = "2025-06-30T15:51:27.491Z" }, - { url = "https://files.pythonhosted.org/packages/fd/df/2b787f80059314a98e1ec6a4cc7576244986df3e56b3c755e6fc7c99e038/multidict-6.6.3-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1bf99b4daf908c73856bd87ee0a2499c3c9a3d19bb04b9c6025e66af3fd07462", size = 247196, upload-time = "2025-06-30T15:51:28.762Z" }, - { url = "https://files.pythonhosted.org/packages/05/f2/f9117089151b9a8ab39f9019620d10d9718eec2ac89e7ca9d30f3ec78e96/multidict-6.6.3-cp311-cp311-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:0b9e59946b49dafaf990fd9c17ceafa62976e8471a14952163d10a7a630413a9", size = 225337, upload-time = "2025-06-30T15:51:30.025Z" }, - { url = "https://files.pythonhosted.org/packages/93/2d/7115300ec5b699faa152c56799b089a53ed69e399c3c2d528251f0aeda1a/multidict-6.6.3-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:e2db616467070d0533832d204c54eea6836a5e628f2cb1e6dfd8cd6ba7277cb7", size = 257079, upload-time = "2025-06-30T15:51:31.716Z" }, - { url = "https://files.pythonhosted.org/packages/15/ea/ff4bab367623e39c20d3b07637225c7688d79e4f3cc1f3b9f89867677f9a/multidict-6.6.3-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:7394888236621f61dcdd25189b2768ae5cc280f041029a5bcf1122ac63df79f9", size = 255461, upload-time = "2025-06-30T15:51:33.029Z" }, - { url = "https://files.pythonhosted.org/packages/74/07/2c9246cda322dfe08be85f1b8739646f2c4c5113a1422d7a407763422ec4/multidict-6.6.3-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:f114d8478733ca7388e7c7e0ab34b72547476b97009d643644ac33d4d3fe1821", size = 246611, upload-time = "2025-06-30T15:51:34.47Z" }, - { url = "https://files.pythonhosted.org/packages/a8/62/279c13d584207d5697a752a66ffc9bb19355a95f7659140cb1b3cf82180e/multidict-6.6.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:cdf22e4db76d323bcdc733514bf732e9fb349707c98d341d40ebcc6e9318ef3d", size = 243102, upload-time = "2025-06-30T15:51:36.525Z" }, - { url = "https://files.pythonhosted.org/packages/69/cc/e06636f48c6d51e724a8bc8d9e1db5f136fe1df066d7cafe37ef4000f86a/multidict-6.6.3-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:e995a34c3d44ab511bfc11aa26869b9d66c2d8c799fa0e74b28a473a692532d6", size = 238693, upload-time = "2025-06-30T15:51:38.278Z" }, - { url = "https://files.pythonhosted.org/packages/89/a4/66c9d8fb9acf3b226cdd468ed009537ac65b520aebdc1703dd6908b19d33/multidict-6.6.3-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:766a4a5996f54361d8d5a9050140aa5362fe48ce51c755a50c0bc3706460c430", size = 246582, upload-time = "2025-06-30T15:51:39.709Z" }, - { url = "https://files.pythonhosted.org/packages/cf/01/c69e0317be556e46257826d5449feb4e6aa0d18573e567a48a2c14156f1f/multidict-6.6.3-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:3893a0d7d28a7fe6ca7a1f760593bc13038d1d35daf52199d431b61d2660602b", size = 253355, upload-time = "2025-06-30T15:51:41.013Z" }, - { url = "https://files.pythonhosted.org/packages/c0/da/9cc1da0299762d20e626fe0042e71b5694f9f72d7d3f9678397cbaa71b2b/multidict-6.6.3-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:934796c81ea996e61914ba58064920d6cad5d99140ac3167901eb932150e2e56", size = 247774, upload-time = "2025-06-30T15:51:42.291Z" }, - { url = "https://files.pythonhosted.org/packages/e6/91/b22756afec99cc31105ddd4a52f95ab32b1a4a58f4d417979c570c4a922e/multidict-6.6.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:9ed948328aec2072bc00f05d961ceadfd3e9bfc2966c1319aeaf7b7c21219183", size = 242275, upload-time = "2025-06-30T15:51:43.642Z" }, - { url = "https://files.pythonhosted.org/packages/be/f1/adcc185b878036a20399d5be5228f3cbe7f823d78985d101d425af35c800/multidict-6.6.3-cp311-cp311-win32.whl", hash = "sha256:9f5b28c074c76afc3e4c610c488e3493976fe0e596dd3db6c8ddfbb0134dcac5", size = 41290, upload-time = "2025-06-30T15:51:45.264Z" }, - { url = "https://files.pythonhosted.org/packages/e0/d4/27652c1c6526ea6b4f5ddd397e93f4232ff5de42bea71d339bc6a6cc497f/multidict-6.6.3-cp311-cp311-win_amd64.whl", hash = "sha256:bc7f6fbc61b1c16050a389c630da0b32fc6d4a3d191394ab78972bf5edc568c2", size = 45942, upload-time = "2025-06-30T15:51:46.377Z" }, - { url = "https://files.pythonhosted.org/packages/16/18/23f4932019804e56d3c2413e237f866444b774b0263bcb81df2fdecaf593/multidict-6.6.3-cp311-cp311-win_arm64.whl", hash = "sha256:d4e47d8faffaae822fb5cba20937c048d4f734f43572e7079298a6c39fb172cb", size = 42880, upload-time = "2025-06-30T15:51:47.561Z" }, - { url = "https://files.pythonhosted.org/packages/0e/a0/6b57988ea102da0623ea814160ed78d45a2645e4bbb499c2896d12833a70/multidict-6.6.3-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:056bebbeda16b2e38642d75e9e5310c484b7c24e3841dc0fb943206a72ec89d6", size = 76514, upload-time = "2025-06-30T15:51:48.728Z" }, - { url = "https://files.pythonhosted.org/packages/07/7a/d1e92665b0850c6c0508f101f9cf0410c1afa24973e1115fe9c6a185ebf7/multidict-6.6.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:e5f481cccb3c5c5e5de5d00b5141dc589c1047e60d07e85bbd7dea3d4580d63f", size = 45394, upload-time = "2025-06-30T15:51:49.986Z" }, - { url = "https://files.pythonhosted.org/packages/52/6f/dd104490e01be6ef8bf9573705d8572f8c2d2c561f06e3826b081d9e6591/multidict-6.6.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:10bea2ee839a759ee368b5a6e47787f399b41e70cf0c20d90dfaf4158dfb4e55", size = 43590, upload-time = "2025-06-30T15:51:51.331Z" }, - { url = "https://files.pythonhosted.org/packages/44/fe/06e0e01b1b0611e6581b7fd5a85b43dacc08b6cea3034f902f383b0873e5/multidict-6.6.3-cp312-cp312-manylinux1_i686.manylinux2014_i686.manylinux_2_17_i686.manylinux_2_5_i686.whl", hash = "sha256:2334cfb0fa9549d6ce2c21af2bfbcd3ac4ec3646b1b1581c88e3e2b1779ec92b", size = 237292, upload-time = "2025-06-30T15:51:52.584Z" }, - { url = "https://files.pythonhosted.org/packages/ce/71/4f0e558fb77696b89c233c1ee2d92f3e1d5459070a0e89153c9e9e804186/multidict-6.6.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:b8fee016722550a2276ca2cb5bb624480e0ed2bd49125b2b73b7010b9090e888", size = 258385, upload-time = "2025-06-30T15:51:53.913Z" }, - { url = "https://files.pythonhosted.org/packages/e3/25/cca0e68228addad24903801ed1ab42e21307a1b4b6dd2cf63da5d3ae082a/multidict-6.6.3-cp312-cp312-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:e5511cb35f5c50a2db21047c875eb42f308c5583edf96bd8ebf7d770a9d68f6d", size = 242328, upload-time = "2025-06-30T15:51:55.672Z" }, - { url = "https://files.pythonhosted.org/packages/6e/a3/46f2d420d86bbcb8fe660b26a10a219871a0fbf4d43cb846a4031533f3e0/multidict-6.6.3-cp312-cp312-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:712b348f7f449948e0a6c4564a21c7db965af900973a67db432d724619b3c680", size = 268057, upload-time = "2025-06-30T15:51:57.037Z" }, - { url = "https://files.pythonhosted.org/packages/9e/73/1c743542fe00794a2ec7466abd3f312ccb8fad8dff9f36d42e18fb1ec33e/multidict-6.6.3-cp312-cp312-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:e4e15d2138ee2694e038e33b7c3da70e6b0ad8868b9f8094a72e1414aeda9c1a", size = 269341, upload-time = "2025-06-30T15:51:59.111Z" }, - { url = "https://files.pythonhosted.org/packages/a4/11/6ec9dcbe2264b92778eeb85407d1df18812248bf3506a5a1754bc035db0c/multidict-6.6.3-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:8df25594989aebff8a130f7899fa03cbfcc5d2b5f4a461cf2518236fe6f15961", size = 256081, upload-time = "2025-06-30T15:52:00.533Z" }, - { url = "https://files.pythonhosted.org/packages/9b/2b/631b1e2afeb5f1696846d747d36cda075bfdc0bc7245d6ba5c319278d6c4/multidict-6.6.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:159ca68bfd284a8860f8d8112cf0521113bffd9c17568579e4d13d1f1dc76b65", size = 253581, upload-time = "2025-06-30T15:52:02.43Z" }, - { url = "https://files.pythonhosted.org/packages/bf/0e/7e3b93f79efeb6111d3bf9a1a69e555ba1d07ad1c11bceb56b7310d0d7ee/multidict-6.6.3-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:e098c17856a8c9ade81b4810888c5ad1914099657226283cab3062c0540b0643", size = 250750, upload-time = "2025-06-30T15:52:04.26Z" }, - { url = "https://files.pythonhosted.org/packages/ad/9e/086846c1d6601948e7de556ee464a2d4c85e33883e749f46b9547d7b0704/multidict-6.6.3-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:67c92ed673049dec52d7ed39f8cf9ebbadf5032c774058b4406d18c8f8fe7063", size = 251548, upload-time = "2025-06-30T15:52:06.002Z" }, - { url = "https://files.pythonhosted.org/packages/8c/7b/86ec260118e522f1a31550e87b23542294880c97cfbf6fb18cc67b044c66/multidict-6.6.3-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:bd0578596e3a835ef451784053cfd327d607fc39ea1a14812139339a18a0dbc3", size = 262718, upload-time = "2025-06-30T15:52:07.707Z" }, - { url = "https://files.pythonhosted.org/packages/8c/bd/22ce8f47abb0be04692c9fc4638508b8340987b18691aa7775d927b73f72/multidict-6.6.3-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:346055630a2df2115cd23ae271910b4cae40f4e336773550dca4889b12916e75", size = 259603, upload-time = "2025-06-30T15:52:09.58Z" }, - { url = "https://files.pythonhosted.org/packages/07/9c/91b7ac1691be95cd1f4a26e36a74b97cda6aa9820632d31aab4410f46ebd/multidict-6.6.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:555ff55a359302b79de97e0468e9ee80637b0de1fce77721639f7cd9440b3a10", size = 251351, upload-time = "2025-06-30T15:52:10.947Z" }, - { url = "https://files.pythonhosted.org/packages/6f/5c/4d7adc739884f7a9fbe00d1eac8c034023ef8bad71f2ebe12823ca2e3649/multidict-6.6.3-cp312-cp312-win32.whl", hash = "sha256:73ab034fb8d58ff85c2bcbadc470efc3fafeea8affcf8722855fb94557f14cc5", size = 41860, upload-time = "2025-06-30T15:52:12.334Z" }, - { url = "https://files.pythonhosted.org/packages/6a/a3/0fbc7afdf7cb1aa12a086b02959307848eb6bcc8f66fcb66c0cb57e2a2c1/multidict-6.6.3-cp312-cp312-win_amd64.whl", hash = "sha256:04cbcce84f63b9af41bad04a54d4cc4e60e90c35b9e6ccb130be2d75b71f8c17", size = 45982, upload-time = "2025-06-30T15:52:13.6Z" }, - { url = "https://files.pythonhosted.org/packages/b8/95/8c825bd70ff9b02462dc18d1295dd08d3e9e4eb66856d292ffa62cfe1920/multidict-6.6.3-cp312-cp312-win_arm64.whl", hash = "sha256:0f1130b896ecb52d2a1e615260f3ea2af55fa7dc3d7c3003ba0c3121a759b18b", size = 43210, upload-time = "2025-06-30T15:52:14.893Z" }, - { url = "https://files.pythonhosted.org/packages/d8/30/9aec301e9772b098c1f5c0ca0279237c9766d94b97802e9888010c64b0ed/multidict-6.6.3-py3-none-any.whl", hash = "sha256:8db10f29c7541fc5da4defd8cd697e1ca429db743fa716325f236079b96f775a", size = 12313, upload-time = "2025-06-30T15:53:45.437Z" }, +version = "6.6.4" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/69/7f/0652e6ed47ab288e3756ea9c0df8b14950781184d4bd7883f4d87dd41245/multidict-6.6.4.tar.gz", hash = "sha256:d2d4e4787672911b48350df02ed3fa3fffdc2f2e8ca06dd6afdf34189b76a9dd", size = 101843, upload-time = "2025-08-11T12:08:48.217Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/6b/7f/90a7f01e2d005d6653c689039977f6856718c75c5579445effb7e60923d1/multidict-6.6.4-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c7a0e9b561e6460484318a7612e725df1145d46b0ef57c6b9866441bf6e27e0c", size = 76472, upload-time = "2025-08-11T12:06:29.006Z" }, + { url = "https://files.pythonhosted.org/packages/54/a3/bed07bc9e2bb302ce752f1dabc69e884cd6a676da44fb0e501b246031fdd/multidict-6.6.4-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:6bf2f10f70acc7a2446965ffbc726e5fc0b272c97a90b485857e5c70022213eb", size = 44634, upload-time = "2025-08-11T12:06:30.374Z" }, + { url = "https://files.pythonhosted.org/packages/a7/4b/ceeb4f8f33cf81277da464307afeaf164fb0297947642585884f5cad4f28/multidict-6.6.4-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:66247d72ed62d5dd29752ffc1d3b88f135c6a8de8b5f63b7c14e973ef5bda19e", size = 44282, upload-time = "2025-08-11T12:06:31.958Z" }, + { url = "https://files.pythonhosted.org/packages/03/35/436a5da8702b06866189b69f655ffdb8f70796252a8772a77815f1812679/multidict-6.6.4-cp311-cp311-manylinux1_i686.manylinux2014_i686.manylinux_2_17_i686.manylinux_2_5_i686.whl", hash = "sha256:105245cc6b76f51e408451a844a54e6823bbd5a490ebfe5bdfc79798511ceded", size = 229696, upload-time = "2025-08-11T12:06:33.087Z" }, + { url = "https://files.pythonhosted.org/packages/b6/0e/915160be8fecf1fca35f790c08fb74ca684d752fcba62c11daaf3d92c216/multidict-6.6.4-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:cbbc54e58b34c3bae389ef00046be0961f30fef7cb0dd9c7756aee376a4f7683", size = 246665, upload-time = "2025-08-11T12:06:34.448Z" }, + { url = "https://files.pythonhosted.org/packages/08/ee/2f464330acd83f77dcc346f0b1a0eaae10230291450887f96b204b8ac4d3/multidict-6.6.4-cp311-cp311-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:56c6b3652f945c9bc3ac6c8178cd93132b8d82dd581fcbc3a00676c51302bc1a", size = 225485, upload-time = "2025-08-11T12:06:35.672Z" }, + { url = "https://files.pythonhosted.org/packages/71/cc/9a117f828b4d7fbaec6adeed2204f211e9caf0a012692a1ee32169f846ae/multidict-6.6.4-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:b95494daf857602eccf4c18ca33337dd2be705bccdb6dddbfc9d513e6addb9d9", size = 257318, upload-time = "2025-08-11T12:06:36.98Z" }, + { url = "https://files.pythonhosted.org/packages/25/77/62752d3dbd70e27fdd68e86626c1ae6bccfebe2bb1f84ae226363e112f5a/multidict-6.6.4-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:e5b1413361cef15340ab9dc61523e653d25723e82d488ef7d60a12878227ed50", size = 254689, upload-time = "2025-08-11T12:06:38.233Z" }, + { url = "https://files.pythonhosted.org/packages/00/6e/fac58b1072a6fc59af5e7acb245e8754d3e1f97f4f808a6559951f72a0d4/multidict-6.6.4-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:e167bf899c3d724f9662ef00b4f7fef87a19c22b2fead198a6f68b263618df52", size = 246709, upload-time = "2025-08-11T12:06:39.517Z" }, + { url = "https://files.pythonhosted.org/packages/01/ef/4698d6842ef5e797c6db7744b0081e36fb5de3d00002cc4c58071097fac3/multidict-6.6.4-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:aaea28ba20a9026dfa77f4b80369e51cb767c61e33a2d4043399c67bd95fb7c6", size = 243185, upload-time = "2025-08-11T12:06:40.796Z" }, + { url = "https://files.pythonhosted.org/packages/aa/c9/d82e95ae1d6e4ef396934e9b0e942dfc428775f9554acf04393cce66b157/multidict-6.6.4-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:8c91cdb30809a96d9ecf442ec9bc45e8cfaa0f7f8bdf534e082c2443a196727e", size = 237838, upload-time = "2025-08-11T12:06:42.595Z" }, + { url = "https://files.pythonhosted.org/packages/57/cf/f94af5c36baaa75d44fab9f02e2a6bcfa0cd90acb44d4976a80960759dbc/multidict-6.6.4-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:1a0ccbfe93ca114c5d65a2471d52d8829e56d467c97b0e341cf5ee45410033b3", size = 246368, upload-time = "2025-08-11T12:06:44.304Z" }, + { url = "https://files.pythonhosted.org/packages/4a/fe/29f23460c3d995f6a4b678cb2e9730e7277231b981f0b234702f0177818a/multidict-6.6.4-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:55624b3f321d84c403cb7d8e6e982f41ae233d85f85db54ba6286f7295dc8a9c", size = 253339, upload-time = "2025-08-11T12:06:45.597Z" }, + { url = "https://files.pythonhosted.org/packages/29/b6/fd59449204426187b82bf8a75f629310f68c6adc9559dc922d5abe34797b/multidict-6.6.4-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:4a1fb393a2c9d202cb766c76208bd7945bc194eba8ac920ce98c6e458f0b524b", size = 246933, upload-time = "2025-08-11T12:06:46.841Z" }, + { url = "https://files.pythonhosted.org/packages/19/52/d5d6b344f176a5ac3606f7a61fb44dc746e04550e1a13834dff722b8d7d6/multidict-6.6.4-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:43868297a5759a845fa3a483fb4392973a95fb1de891605a3728130c52b8f40f", size = 242225, upload-time = "2025-08-11T12:06:48.588Z" }, + { url = "https://files.pythonhosted.org/packages/ec/d3/5b2281ed89ff4d5318d82478a2a2450fcdfc3300da48ff15c1778280ad26/multidict-6.6.4-cp311-cp311-win32.whl", hash = "sha256:ed3b94c5e362a8a84d69642dbeac615452e8af9b8eb825b7bc9f31a53a1051e2", size = 41306, upload-time = "2025-08-11T12:06:49.95Z" }, + { url = "https://files.pythonhosted.org/packages/74/7d/36b045c23a1ab98507aefd44fd8b264ee1dd5e5010543c6fccf82141ccef/multidict-6.6.4-cp311-cp311-win_amd64.whl", hash = "sha256:d8c112f7a90d8ca5d20213aa41eac690bb50a76da153e3afb3886418e61cb22e", size = 46029, upload-time = "2025-08-11T12:06:51.082Z" }, + { url = "https://files.pythonhosted.org/packages/0f/5e/553d67d24432c5cd52b49047f2d248821843743ee6d29a704594f656d182/multidict-6.6.4-cp311-cp311-win_arm64.whl", hash = "sha256:3bb0eae408fa1996d87247ca0d6a57b7fc1dcf83e8a5c47ab82c558c250d4adf", size = 43017, upload-time = "2025-08-11T12:06:52.243Z" }, + { url = "https://files.pythonhosted.org/packages/05/f6/512ffd8fd8b37fb2680e5ac35d788f1d71bbaf37789d21a820bdc441e565/multidict-6.6.4-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0ffb87be160942d56d7b87b0fdf098e81ed565add09eaa1294268c7f3caac4c8", size = 76516, upload-time = "2025-08-11T12:06:53.393Z" }, + { url = "https://files.pythonhosted.org/packages/99/58/45c3e75deb8855c36bd66cc1658007589662ba584dbf423d01df478dd1c5/multidict-6.6.4-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:d191de6cbab2aff5de6c5723101705fd044b3e4c7cfd587a1929b5028b9714b3", size = 45394, upload-time = "2025-08-11T12:06:54.555Z" }, + { url = "https://files.pythonhosted.org/packages/fd/ca/e8c4472a93a26e4507c0b8e1f0762c0d8a32de1328ef72fd704ef9cc5447/multidict-6.6.4-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:38a0956dd92d918ad5feff3db8fcb4a5eb7dba114da917e1a88475619781b57b", size = 43591, upload-time = "2025-08-11T12:06:55.672Z" }, + { url = "https://files.pythonhosted.org/packages/05/51/edf414f4df058574a7265034d04c935aa84a89e79ce90fcf4df211f47b16/multidict-6.6.4-cp312-cp312-manylinux1_i686.manylinux2014_i686.manylinux_2_17_i686.manylinux_2_5_i686.whl", hash = "sha256:6865f6d3b7900ae020b495d599fcf3765653bc927951c1abb959017f81ae8287", size = 237215, upload-time = "2025-08-11T12:06:57.213Z" }, + { url = "https://files.pythonhosted.org/packages/c8/45/8b3d6dbad8cf3252553cc41abea09ad527b33ce47a5e199072620b296902/multidict-6.6.4-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0a2088c126b6f72db6c9212ad827d0ba088c01d951cee25e758c450da732c138", size = 258299, upload-time = "2025-08-11T12:06:58.946Z" }, + { url = "https://files.pythonhosted.org/packages/3c/e8/8ca2e9a9f5a435fc6db40438a55730a4bf4956b554e487fa1b9ae920f825/multidict-6.6.4-cp312-cp312-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:0f37bed7319b848097085d7d48116f545985db988e2256b2e6f00563a3416ee6", size = 242357, upload-time = "2025-08-11T12:07:00.301Z" }, + { url = "https://files.pythonhosted.org/packages/0f/84/80c77c99df05a75c28490b2af8f7cba2a12621186e0a8b0865d8e745c104/multidict-6.6.4-cp312-cp312-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:01368e3c94032ba6ca0b78e7ccb099643466cf24f8dc8eefcfdc0571d56e58f9", size = 268369, upload-time = "2025-08-11T12:07:01.638Z" }, + { url = "https://files.pythonhosted.org/packages/0d/e9/920bfa46c27b05fb3e1ad85121fd49f441492dca2449c5bcfe42e4565d8a/multidict-6.6.4-cp312-cp312-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:8fe323540c255db0bffee79ad7f048c909f2ab0edb87a597e1c17da6a54e493c", size = 269341, upload-time = "2025-08-11T12:07:02.943Z" }, + { url = "https://files.pythonhosted.org/packages/af/65/753a2d8b05daf496f4a9c367fe844e90a1b2cac78e2be2c844200d10cc4c/multidict-6.6.4-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:b8eb3025f17b0a4c3cd08cda49acf312a19ad6e8a4edd9dbd591e6506d999402", size = 256100, upload-time = "2025-08-11T12:07:04.564Z" }, + { url = "https://files.pythonhosted.org/packages/09/54/655be13ae324212bf0bc15d665a4e34844f34c206f78801be42f7a0a8aaa/multidict-6.6.4-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:bbc14f0365534d35a06970d6a83478b249752e922d662dc24d489af1aa0d1be7", size = 253584, upload-time = "2025-08-11T12:07:05.914Z" }, + { url = "https://files.pythonhosted.org/packages/5c/74/ab2039ecc05264b5cec73eb018ce417af3ebb384ae9c0e9ed42cb33f8151/multidict-6.6.4-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:75aa52fba2d96bf972e85451b99d8e19cc37ce26fd016f6d4aa60da9ab2b005f", size = 251018, upload-time = "2025-08-11T12:07:08.301Z" }, + { url = "https://files.pythonhosted.org/packages/af/0a/ccbb244ac848e56c6427f2392741c06302bbfba49c0042f1eb3c5b606497/multidict-6.6.4-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:4fefd4a815e362d4f011919d97d7b4a1e566f1dde83dc4ad8cfb5b41de1df68d", size = 251477, upload-time = "2025-08-11T12:07:10.248Z" }, + { url = "https://files.pythonhosted.org/packages/0e/b0/0ed49bba775b135937f52fe13922bc64a7eaf0a3ead84a36e8e4e446e096/multidict-6.6.4-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:db9801fe021f59a5b375ab778973127ca0ac52429a26e2fd86aa9508f4d26eb7", size = 263575, upload-time = "2025-08-11T12:07:11.928Z" }, + { url = "https://files.pythonhosted.org/packages/3e/d9/7fb85a85e14de2e44dfb6a24f03c41e2af8697a6df83daddb0e9b7569f73/multidict-6.6.4-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:a650629970fa21ac1fb06ba25dabfc5b8a2054fcbf6ae97c758aa956b8dba802", size = 259649, upload-time = "2025-08-11T12:07:13.244Z" }, + { url = "https://files.pythonhosted.org/packages/03/9e/b3a459bcf9b6e74fa461a5222a10ff9b544cb1cd52fd482fb1b75ecda2a2/multidict-6.6.4-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:452ff5da78d4720d7516a3a2abd804957532dd69296cb77319c193e3ffb87e24", size = 251505, upload-time = "2025-08-11T12:07:14.57Z" }, + { url = "https://files.pythonhosted.org/packages/86/a2/8022f78f041dfe6d71e364001a5cf987c30edfc83c8a5fb7a3f0974cff39/multidict-6.6.4-cp312-cp312-win32.whl", hash = "sha256:8c2fcb12136530ed19572bbba61b407f655e3953ba669b96a35036a11a485793", size = 41888, upload-time = "2025-08-11T12:07:15.904Z" }, + { url = "https://files.pythonhosted.org/packages/c7/eb/d88b1780d43a56db2cba24289fa744a9d216c1a8546a0dc3956563fd53ea/multidict-6.6.4-cp312-cp312-win_amd64.whl", hash = "sha256:047d9425860a8c9544fed1b9584f0c8bcd31bcde9568b047c5e567a1025ecd6e", size = 46072, upload-time = "2025-08-11T12:07:17.045Z" }, + { url = "https://files.pythonhosted.org/packages/9f/16/b929320bf5750e2d9d4931835a4c638a19d2494a5b519caaaa7492ebe105/multidict-6.6.4-cp312-cp312-win_arm64.whl", hash = "sha256:14754eb72feaa1e8ae528468f24250dd997b8e2188c3d2f593f9eba259e4b364", size = 43222, upload-time = "2025-08-11T12:07:18.328Z" }, + { url = "https://files.pythonhosted.org/packages/fd/69/b547032297c7e63ba2af494edba695d781af8a0c6e89e4d06cf848b21d80/multidict-6.6.4-py3-none-any.whl", hash = "sha256:27d8f8e125c07cb954e54d75d04905a9bba8a439c1d84aca94949d4d03d8601c", size = 12313, upload-time = "2025-08-11T12:08:46.891Z" }, ] [[package]] @@ -1480,14 +1477,14 @@ wheels = [ [[package]] name = "pre-commit-hooks" -version = "5.0.0" +version = "6.0.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "ruamel-yaml" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ac/7d/3299241a753c738d114600c360d754550b28c285281dc6a5132c4ccfae65/pre_commit_hooks-5.0.0.tar.gz", hash = "sha256:10626959a9eaf602fbfc22bc61b6e75801436f82326bfcee82bb1f2fc4bc646e", size = 29747, upload-time = "2024-10-05T18:43:11.225Z" } +sdist = { url = "https://files.pythonhosted.org/packages/36/4d/93e63e48f8fd16d6c1e4cef5dabadcade4d1325c7fd6f29f075a4d2284f3/pre_commit_hooks-6.0.0.tar.gz", hash = "sha256:76d8370c006f5026cdd638a397a678d26dda735a3c88137e05885a020f824034", size = 28293, upload-time = "2025-08-09T19:25:04.6Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/1e/29/db1d855a661c02dbde5cab3057969133fcc62e7a0c6393e48fe9d0e81679/pre_commit_hooks-5.0.0-py2.py3-none-any.whl", hash = "sha256:8d71cfb582c5c314a5498d94e0104b6567a8b93fb35903ea845c491f4e290a7a", size = 41245, upload-time = "2024-10-05T18:43:09.901Z" }, + { url = "https://files.pythonhosted.org/packages/12/46/eba9be9daa403fa94854ce16a458c29df9a01c6c047931c3d8be6016cd9a/pre_commit_hooks-6.0.0-py2.py3-none-any.whl", hash = "sha256:76161b76d321d2f8ee2a8e0b84c30ee8443e01376121fd1c90851e33e3bd7ee2", size = 41338, upload-time = "2025-08-09T19:25:03.513Z" }, ] [[package]] @@ -1539,16 +1536,16 @@ wheels = [ [[package]] name = "protobuf" -version = "6.31.1" +version = "6.32.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/52/f3/b9655a711b32c19720253f6f06326faf90580834e2e83f840472d752bc8b/protobuf-6.31.1.tar.gz", hash = "sha256:d8cac4c982f0b957a4dc73a80e2ea24fab08e679c0de9deb835f4a12d69aca9a", size = 441797, upload-time = "2025-05-28T19:25:54.947Z" } +sdist = { url = "https://files.pythonhosted.org/packages/c0/df/fb4a8eeea482eca989b51cffd274aac2ee24e825f0bf3cbce5281fa1567b/protobuf-6.32.0.tar.gz", hash = "sha256:a81439049127067fc49ec1d36e25c6ee1d1a2b7be930675f919258d03c04e7d2", size = 440614, upload-time = "2025-08-14T21:21:25.015Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f3/6f/6ab8e4bf962fd5570d3deaa2d5c38f0a363f57b4501047b5ebeb83ab1125/protobuf-6.31.1-cp310-abi3-win32.whl", hash = "sha256:7fa17d5a29c2e04b7d90e5e32388b8bfd0e7107cd8e616feef7ed3fa6bdab5c9", size = 423603, upload-time = "2025-05-28T19:25:41.198Z" }, - { url = "https://files.pythonhosted.org/packages/44/3a/b15c4347dd4bf3a1b0ee882f384623e2063bb5cf9fa9d57990a4f7df2fb6/protobuf-6.31.1-cp310-abi3-win_amd64.whl", hash = "sha256:426f59d2964864a1a366254fa703b8632dcec0790d8862d30034d8245e1cd447", size = 435283, upload-time = "2025-05-28T19:25:44.275Z" }, - { url = "https://files.pythonhosted.org/packages/6a/c9/b9689a2a250264a84e66c46d8862ba788ee7a641cdca39bccf64f59284b7/protobuf-6.31.1-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:6f1227473dc43d44ed644425268eb7c2e488ae245d51c6866d19fe158e207402", size = 425604, upload-time = "2025-05-28T19:25:45.702Z" }, - { url = "https://files.pythonhosted.org/packages/76/a1/7a5a94032c83375e4fe7e7f56e3976ea6ac90c5e85fac8576409e25c39c3/protobuf-6.31.1-cp39-abi3-manylinux2014_aarch64.whl", hash = "sha256:a40fc12b84c154884d7d4c4ebd675d5b3b5283e155f324049ae396b95ddebc39", size = 322115, upload-time = "2025-05-28T19:25:47.128Z" }, - { url = "https://files.pythonhosted.org/packages/fa/b1/b59d405d64d31999244643d88c45c8241c58f17cc887e73bcb90602327f8/protobuf-6.31.1-cp39-abi3-manylinux2014_x86_64.whl", hash = "sha256:4ee898bf66f7a8b0bd21bce523814e6fbd8c6add948045ce958b73af7e8878c6", size = 321070, upload-time = "2025-05-28T19:25:50.036Z" }, - { url = "https://files.pythonhosted.org/packages/f7/af/ab3c51ab7507a7325e98ffe691d9495ee3d3aa5f589afad65ec920d39821/protobuf-6.31.1-py3-none-any.whl", hash = "sha256:720a6c7e6b77288b85063569baae8536671b39f15cc22037ec7045658d80489e", size = 168724, upload-time = "2025-05-28T19:25:53.926Z" }, + { url = "https://files.pythonhosted.org/packages/33/18/df8c87da2e47f4f1dcc5153a81cd6bca4e429803f4069a299e236e4dd510/protobuf-6.32.0-cp310-abi3-win32.whl", hash = "sha256:84f9e3c1ff6fb0308dbacb0950d8aa90694b0d0ee68e75719cb044b7078fe741", size = 424409, upload-time = "2025-08-14T21:21:12.366Z" }, + { url = "https://files.pythonhosted.org/packages/e1/59/0a820b7310f8139bd8d5a9388e6a38e1786d179d6f33998448609296c229/protobuf-6.32.0-cp310-abi3-win_amd64.whl", hash = "sha256:a8bdbb2f009cfc22a36d031f22a625a38b615b5e19e558a7b756b3279723e68e", size = 435735, upload-time = "2025-08-14T21:21:15.046Z" }, + { url = "https://files.pythonhosted.org/packages/cc/5b/0d421533c59c789e9c9894683efac582c06246bf24bb26b753b149bd88e4/protobuf-6.32.0-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:d52691e5bee6c860fff9a1c86ad26a13afbeb4b168cd4445c922b7e2cf85aaf0", size = 426449, upload-time = "2025-08-14T21:21:16.687Z" }, + { url = "https://files.pythonhosted.org/packages/ec/7b/607764ebe6c7a23dcee06e054fd1de3d5841b7648a90fd6def9a3bb58c5e/protobuf-6.32.0-cp39-abi3-manylinux2014_aarch64.whl", hash = "sha256:501fe6372fd1c8ea2a30b4d9be8f87955a64d6be9c88a973996cef5ef6f0abf1", size = 322869, upload-time = "2025-08-14T21:21:18.282Z" }, + { url = "https://files.pythonhosted.org/packages/40/01/2e730bd1c25392fc32e3268e02446f0d77cb51a2c3a8486b1798e34d5805/protobuf-6.32.0-cp39-abi3-manylinux2014_x86_64.whl", hash = "sha256:75a2aab2bd1aeb1f5dc7c5f33bcb11d82ea8c055c9becbb41c26a8c43fd7092c", size = 322009, upload-time = "2025-08-14T21:21:19.893Z" }, + { url = "https://files.pythonhosted.org/packages/9c/f2/80ffc4677aac1bc3519b26bc7f7f5de7fce0ee2f7e36e59e27d8beb32dd1/protobuf-6.32.0-py3-none-any.whl", hash = "sha256:ba377e5b67b908c8f3072a57b63e2c6a4cbd18aea4ed98d2584350dbf46f2783", size = 169287, upload-time = "2025-08-14T21:21:23.515Z" }, ] [[package]] @@ -4313,7 +4310,7 @@ wheels = [ [[package]] name = "pytest-xdist" -version = "3.7.1.dev24+g2b4372b" +version = "3.7.1.dev24+g2b4372bd6" source = { git = "https://github.com/sshane/pytest-xdist?rev=2b4372bd62699fb412c4fe2f95bf9f01bd2018da#2b4372bd62699fb412c4fe2f95bf9f01bd2018da" } dependencies = [ { name = "execnet" }, @@ -4580,36 +4577,37 @@ wheels = [ [[package]] name = "rubicon-objc" -version = "0.5.1" +version = "0.5.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e0/83/e57741dcf862a2581d53eccf8b11749c97f73d9754bbc538fb6c7b527da3/rubicon_objc-0.5.1.tar.gz", hash = "sha256:90bee9fc1de4515e17615e15648989b88bb8d4d2ffc8c7c52748272cd7f30a66", size = 174639, upload-time = "2025-06-03T06:33:50.822Z" } +sdist = { url = "https://files.pythonhosted.org/packages/a7/2f/612049b8601e810080f63f4b85acbf2ed0784349088d3c944eb288e1d487/rubicon_objc-0.5.2.tar.gz", hash = "sha256:1180593935f6a8a39c23b5f4b7baa24aedf9f7285e80804a1d9d6b50a50572f5", size = 175710, upload-time = "2025-08-07T06:12:25.194Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/58/0a/e451c3dbda38dd6abab1fd16c3b35623fc0635dffcbbf97f1acc55a58508/rubicon_objc-0.5.1-py3-none-any.whl", hash = "sha256:17092756241b8370231cfaad45ad6e8ce99534987f2acbc944d65df5bdf8f6cd", size = 63323, upload-time = "2025-06-03T06:33:48.863Z" }, + { url = "https://files.pythonhosted.org/packages/9f/a4/11ad29100060af56408ed084dca76a16d2ce8eb31b75081bfc0eec45d755/rubicon_objc-0.5.2-py3-none-any.whl", hash = "sha256:829b253c579e51fc34f4bb6587c34806e78960dcc1eb24e62b38141a1fe02b39", size = 63512, upload-time = "2025-08-07T06:12:23.766Z" }, ] [[package]] name = "ruff" -version = "0.12.7" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/a1/81/0bd3594fa0f690466e41bd033bdcdf86cba8288345ac77ad4afbe5ec743a/ruff-0.12.7.tar.gz", hash = "sha256:1fc3193f238bc2d7968772c82831a4ff69252f673be371fb49663f0068b7ec71", size = 5197814, upload-time = "2025-07-29T22:32:35.877Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/e1/d2/6cb35e9c85e7a91e8d22ab32ae07ac39cc34a71f1009a6f9e4a2a019e602/ruff-0.12.7-py3-none-linux_armv6l.whl", hash = "sha256:76e4f31529899b8c434c3c1dede98c4483b89590e15fb49f2d46183801565303", size = 11852189, upload-time = "2025-07-29T22:31:41.281Z" }, - { url = "https://files.pythonhosted.org/packages/63/5b/a4136b9921aa84638f1a6be7fb086f8cad0fde538ba76bda3682f2599a2f/ruff-0.12.7-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:789b7a03e72507c54fb3ba6209e4bb36517b90f1a3569ea17084e3fd295500fb", size = 12519389, upload-time = "2025-07-29T22:31:54.265Z" }, - { url = "https://files.pythonhosted.org/packages/a8/c9/3e24a8472484269b6b1821794141f879c54645a111ded4b6f58f9ab0705f/ruff-0.12.7-py3-none-macosx_11_0_arm64.whl", hash = "sha256:2e1c2a3b8626339bb6369116e7030a4cf194ea48f49b64bb505732a7fce4f4e3", size = 11743384, upload-time = "2025-07-29T22:31:59.575Z" }, - { url = "https://files.pythonhosted.org/packages/26/7c/458dd25deeb3452c43eaee853c0b17a1e84169f8021a26d500ead77964fd/ruff-0.12.7-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:32dec41817623d388e645612ec70d5757a6d9c035f3744a52c7b195a57e03860", size = 11943759, upload-time = "2025-07-29T22:32:01.95Z" }, - { url = "https://files.pythonhosted.org/packages/7f/8b/658798472ef260ca050e400ab96ef7e85c366c39cf3dfbef4d0a46a528b6/ruff-0.12.7-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:47ef751f722053a5df5fa48d412dbb54d41ab9b17875c6840a58ec63ff0c247c", size = 11654028, upload-time = "2025-07-29T22:32:04.367Z" }, - { url = "https://files.pythonhosted.org/packages/a8/86/9c2336f13b2a3326d06d39178fd3448dcc7025f82514d1b15816fe42bfe8/ruff-0.12.7-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a828a5fc25a3efd3e1ff7b241fd392686c9386f20e5ac90aa9234a5faa12c423", size = 13225209, upload-time = "2025-07-29T22:32:06.952Z" }, - { url = "https://files.pythonhosted.org/packages/76/69/df73f65f53d6c463b19b6b312fd2391dc36425d926ec237a7ed028a90fc1/ruff-0.12.7-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:5726f59b171111fa6a69d82aef48f00b56598b03a22f0f4170664ff4d8298efb", size = 14182353, upload-time = "2025-07-29T22:32:10.053Z" }, - { url = "https://files.pythonhosted.org/packages/58/1e/de6cda406d99fea84b66811c189b5ea139814b98125b052424b55d28a41c/ruff-0.12.7-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:74e6f5c04c4dd4aba223f4fe6e7104f79e0eebf7d307e4f9b18c18362124bccd", size = 13631555, upload-time = "2025-07-29T22:32:12.644Z" }, - { url = "https://files.pythonhosted.org/packages/6f/ae/625d46d5164a6cc9261945a5e89df24457dc8262539ace3ac36c40f0b51e/ruff-0.12.7-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5d0bfe4e77fba61bf2ccadf8cf005d6133e3ce08793bbe870dd1c734f2699a3e", size = 12667556, upload-time = "2025-07-29T22:32:15.312Z" }, - { url = "https://files.pythonhosted.org/packages/55/bf/9cb1ea5e3066779e42ade8d0cd3d3b0582a5720a814ae1586f85014656b6/ruff-0.12.7-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:06bfb01e1623bf7f59ea749a841da56f8f653d641bfd046edee32ede7ff6c606", size = 12939784, upload-time = "2025-07-29T22:32:17.69Z" }, - { url = "https://files.pythonhosted.org/packages/55/7f/7ead2663be5627c04be83754c4f3096603bf5e99ed856c7cd29618c691bd/ruff-0.12.7-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:e41df94a957d50083fd09b916d6e89e497246698c3f3d5c681c8b3e7b9bb4ac8", size = 11771356, upload-time = "2025-07-29T22:32:20.134Z" }, - { url = "https://files.pythonhosted.org/packages/17/40/a95352ea16edf78cd3a938085dccc55df692a4d8ba1b3af7accbe2c806b0/ruff-0.12.7-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:4000623300563c709458d0ce170c3d0d788c23a058912f28bbadc6f905d67afa", size = 11612124, upload-time = "2025-07-29T22:32:22.645Z" }, - { url = "https://files.pythonhosted.org/packages/4d/74/633b04871c669e23b8917877e812376827c06df866e1677f15abfadc95cb/ruff-0.12.7-py3-none-musllinux_1_2_i686.whl", hash = "sha256:69ffe0e5f9b2cf2b8e289a3f8945b402a1b19eff24ec389f45f23c42a3dd6fb5", size = 12479945, upload-time = "2025-07-29T22:32:24.765Z" }, - { url = "https://files.pythonhosted.org/packages/be/34/c3ef2d7799c9778b835a76189c6f53c179d3bdebc8c65288c29032e03613/ruff-0.12.7-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:a07a5c8ffa2611a52732bdc67bf88e243abd84fe2d7f6daef3826b59abbfeda4", size = 12998677, upload-time = "2025-07-29T22:32:27.022Z" }, - { url = "https://files.pythonhosted.org/packages/77/ab/aca2e756ad7b09b3d662a41773f3edcbd262872a4fc81f920dc1ffa44541/ruff-0.12.7-py3-none-win32.whl", hash = "sha256:c928f1b2ec59fb77dfdf70e0419408898b63998789cc98197e15f560b9e77f77", size = 11756687, upload-time = "2025-07-29T22:32:29.381Z" }, - { url = "https://files.pythonhosted.org/packages/b4/71/26d45a5042bc71db22ddd8252ca9d01e9ca454f230e2996bb04f16d72799/ruff-0.12.7-py3-none-win_amd64.whl", hash = "sha256:9c18f3d707ee9edf89da76131956aba1270c6348bfee8f6c647de841eac7194f", size = 12912365, upload-time = "2025-07-29T22:32:31.517Z" }, - { url = "https://files.pythonhosted.org/packages/4c/9b/0b8aa09817b63e78d94b4977f18b1fcaead3165a5ee49251c5d5c245bb2d/ruff-0.12.7-py3-none-win_arm64.whl", hash = "sha256:dfce05101dbd11833a0776716d5d1578641b7fddb537fe7fa956ab85d1769b69", size = 11982083, upload-time = "2025-07-29T22:32:33.881Z" }, +version = "0.12.9" +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" } +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/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/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/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/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/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/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/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/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/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/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/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/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/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/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/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/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/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" }, ] [[package]] @@ -4623,15 +4621,15 @@ wheels = [ [[package]] name = "sentry-sdk" -version = "2.34.1" +version = "2.35.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "certifi" }, { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/3a/38/10d6bfe23df1bfc65ac2262ed10b45823f47f810b0057d3feeea1ca5c7ed/sentry_sdk-2.34.1.tar.gz", hash = "sha256:69274eb8c5c38562a544c3e9f68b5be0a43be4b697f5fd385bf98e4fbe672687", size = 336969, upload-time = "2025-07-30T11:13:37.93Z" } +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" } wheels = [ - { url = "https://files.pythonhosted.org/packages/2d/3e/bb34de65a5787f76848a533afbb6610e01fbcdd59e76d8679c254e02255c/sentry_sdk-2.34.1-py2.py3-none-any.whl", hash = "sha256:b7a072e1cdc5abc48101d5146e1ae680fa81fe886d8d95aaa25a0b450c818d32", size = 357743, upload-time = "2025-07-30T11:13:36.145Z" }, + { 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" }, ] [[package]] @@ -4805,14 +4803,14 @@ wheels = [ [[package]] name = "types-requests" -version = "2.32.4.20250611" +version = "2.32.4.20250809" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "urllib3" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/6d/7f/73b3a04a53b0fd2a911d4ec517940ecd6600630b559e4505cc7b68beb5a0/types_requests-2.32.4.20250611.tar.gz", hash = "sha256:741c8777ed6425830bf51e54d6abe245f79b4dcb9019f1622b773463946bf826", size = 23118, upload-time = "2025-06-11T03:11:41.272Z" } +sdist = { url = "https://files.pythonhosted.org/packages/ed/b0/9355adb86ec84d057fea765e4c49cce592aaf3d5117ce5609a95a7fc3dac/types_requests-2.32.4.20250809.tar.gz", hash = "sha256:d8060de1c8ee599311f56ff58010fb4902f462a1470802cf9f6ed27bc46c4df3", size = 23027, upload-time = "2025-08-09T03:17:10.664Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/3d/ea/0be9258c5a4fa1ba2300111aa5a0767ee6d18eb3fd20e91616c12082284d/types_requests-2.32.4.20250611-py3-none-any.whl", hash = "sha256:ad2fe5d3b0cb3c2c902c8815a70e7fb2302c4b8c1f77bdcd738192cdb3878072", size = 20643, upload-time = "2025-06-11T03:11:40.186Z" }, + { url = "https://files.pythonhosted.org/packages/2b/6f/ec0012be842b1d888d46884ac5558fd62aeae1f0ec4f7a581433d890d4b5/types_requests-2.32.4.20250809-py3-none-any.whl", hash = "sha256:f73d1832fb519ece02c85b1f09d5f0dd3108938e7d47e7f94bbfa18a6782b163", size = 20644, upload-time = "2025-08-09T03:17:09.716Z" }, ] [[package]] @@ -4966,43 +4964,42 @@ wheels = [ [[package]] name = "zstandard" -version = "0.23.0" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "cffi", marker = "platform_python_implementation == 'PyPy'" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/ed/f6/2ac0287b442160a89d726b17a9184a4c615bb5237db763791a7fd16d9df1/zstandard-0.23.0.tar.gz", hash = "sha256:b2d8c62d08e7255f68f7a740bae85b3c9b8e5466baa9cbf7f57f1cde0ac6bc09", size = 681701, upload-time = "2024-07-15T00:18:06.141Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/9e/40/f67e7d2c25a0e2dc1744dd781110b0b60306657f8696cafb7ad7579469bd/zstandard-0.23.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:34895a41273ad33347b2fc70e1bff4240556de3c46c6ea430a7ed91f9042aa4e", size = 788699, upload-time = "2024-07-15T00:14:04.909Z" }, - { url = "https://files.pythonhosted.org/packages/e8/46/66d5b55f4d737dd6ab75851b224abf0afe5774976fe511a54d2eb9063a41/zstandard-0.23.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:77ea385f7dd5b5676d7fd943292ffa18fbf5c72ba98f7d09fc1fb9e819b34c23", size = 633681, upload-time = "2024-07-15T00:14:13.99Z" }, - { url = "https://files.pythonhosted.org/packages/63/b6/677e65c095d8e12b66b8f862b069bcf1f1d781b9c9c6f12eb55000d57583/zstandard-0.23.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:983b6efd649723474f29ed42e1467f90a35a74793437d0bc64a5bf482bedfa0a", size = 4944328, upload-time = "2024-07-15T00:14:16.588Z" }, - { url = "https://files.pythonhosted.org/packages/59/cc/e76acb4c42afa05a9d20827116d1f9287e9c32b7ad58cc3af0721ce2b481/zstandard-0.23.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:80a539906390591dd39ebb8d773771dc4db82ace6372c4d41e2d293f8e32b8db", size = 5311955, upload-time = "2024-07-15T00:14:19.389Z" }, - { url = "https://files.pythonhosted.org/packages/78/e4/644b8075f18fc7f632130c32e8f36f6dc1b93065bf2dd87f03223b187f26/zstandard-0.23.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:445e4cb5048b04e90ce96a79b4b63140e3f4ab5f662321975679b5f6360b90e2", size = 5344944, upload-time = "2024-07-15T00:14:22.173Z" }, - { url = "https://files.pythonhosted.org/packages/76/3f/dbafccf19cfeca25bbabf6f2dd81796b7218f768ec400f043edc767015a6/zstandard-0.23.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fd30d9c67d13d891f2360b2a120186729c111238ac63b43dbd37a5a40670b8ca", size = 5442927, upload-time = "2024-07-15T00:14:24.825Z" }, - { url = "https://files.pythonhosted.org/packages/0c/c3/d24a01a19b6733b9f218e94d1a87c477d523237e07f94899e1c10f6fd06c/zstandard-0.23.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d20fd853fbb5807c8e84c136c278827b6167ded66c72ec6f9a14b863d809211c", size = 4864910, upload-time = "2024-07-15T00:14:26.982Z" }, - { url = "https://files.pythonhosted.org/packages/1c/a9/cf8f78ead4597264f7618d0875be01f9bc23c9d1d11afb6d225b867cb423/zstandard-0.23.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ed1708dbf4d2e3a1c5c69110ba2b4eb6678262028afd6c6fbcc5a8dac9cda68e", size = 4935544, upload-time = "2024-07-15T00:14:29.582Z" }, - { url = "https://files.pythonhosted.org/packages/2c/96/8af1e3731b67965fb995a940c04a2c20997a7b3b14826b9d1301cf160879/zstandard-0.23.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:be9b5b8659dff1f913039c2feee1aca499cfbc19e98fa12bc85e037c17ec6ca5", size = 5467094, upload-time = "2024-07-15T00:14:40.126Z" }, - { url = "https://files.pythonhosted.org/packages/ff/57/43ea9df642c636cb79f88a13ab07d92d88d3bfe3e550b55a25a07a26d878/zstandard-0.23.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:65308f4b4890aa12d9b6ad9f2844b7ee42c7f7a4fd3390425b242ffc57498f48", size = 4860440, upload-time = "2024-07-15T00:14:42.786Z" }, - { url = "https://files.pythonhosted.org/packages/46/37/edb78f33c7f44f806525f27baa300341918fd4c4af9472fbc2c3094be2e8/zstandard-0.23.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:98da17ce9cbf3bfe4617e836d561e433f871129e3a7ac16d6ef4c680f13a839c", size = 4700091, upload-time = "2024-07-15T00:14:45.184Z" }, - { url = "https://files.pythonhosted.org/packages/c1/f1/454ac3962671a754f3cb49242472df5c2cced4eb959ae203a377b45b1a3c/zstandard-0.23.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:8ed7d27cb56b3e058d3cf684d7200703bcae623e1dcc06ed1e18ecda39fee003", size = 5208682, upload-time = "2024-07-15T00:14:47.407Z" }, - { url = "https://files.pythonhosted.org/packages/85/b2/1734b0fff1634390b1b887202d557d2dd542de84a4c155c258cf75da4773/zstandard-0.23.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:b69bb4f51daf461b15e7b3db033160937d3ff88303a7bc808c67bbc1eaf98c78", size = 5669707, upload-time = "2024-07-15T00:15:03.529Z" }, - { url = "https://files.pythonhosted.org/packages/52/5a/87d6971f0997c4b9b09c495bf92189fb63de86a83cadc4977dc19735f652/zstandard-0.23.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:034b88913ecc1b097f528e42b539453fa82c3557e414b3de9d5632c80439a473", size = 5201792, upload-time = "2024-07-15T00:15:28.372Z" }, - { url = "https://files.pythonhosted.org/packages/79/02/6f6a42cc84459d399bd1a4e1adfc78d4dfe45e56d05b072008d10040e13b/zstandard-0.23.0-cp311-cp311-win32.whl", hash = "sha256:f2d4380bf5f62daabd7b751ea2339c1a21d1c9463f1feb7fc2bdcea2c29c3160", size = 430586, upload-time = "2024-07-15T00:15:32.26Z" }, - { url = "https://files.pythonhosted.org/packages/be/a2/4272175d47c623ff78196f3c10e9dc7045c1b9caf3735bf041e65271eca4/zstandard-0.23.0-cp311-cp311-win_amd64.whl", hash = "sha256:62136da96a973bd2557f06ddd4e8e807f9e13cbb0bfb9cc06cfe6d98ea90dfe0", size = 495420, upload-time = "2024-07-15T00:15:34.004Z" }, - { url = "https://files.pythonhosted.org/packages/7b/83/f23338c963bd9de687d47bf32efe9fd30164e722ba27fb59df33e6b1719b/zstandard-0.23.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:b4567955a6bc1b20e9c31612e615af6b53733491aeaa19a6b3b37f3b65477094", size = 788713, upload-time = "2024-07-15T00:15:35.815Z" }, - { url = "https://files.pythonhosted.org/packages/5b/b3/1a028f6750fd9227ee0b937a278a434ab7f7fdc3066c3173f64366fe2466/zstandard-0.23.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:1e172f57cd78c20f13a3415cc8dfe24bf388614324d25539146594c16d78fcc8", size = 633459, upload-time = "2024-07-15T00:15:37.995Z" }, - { url = "https://files.pythonhosted.org/packages/26/af/36d89aae0c1f95a0a98e50711bc5d92c144939efc1f81a2fcd3e78d7f4c1/zstandard-0.23.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b0e166f698c5a3e914947388c162be2583e0c638a4703fc6a543e23a88dea3c1", size = 4945707, upload-time = "2024-07-15T00:15:39.872Z" }, - { url = "https://files.pythonhosted.org/packages/cd/2e/2051f5c772f4dfc0aae3741d5fc72c3dcfe3aaeb461cc231668a4db1ce14/zstandard-0.23.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:12a289832e520c6bd4dcaad68e944b86da3bad0d339ef7989fb7e88f92e96072", size = 5306545, upload-time = "2024-07-15T00:15:41.75Z" }, - { url = "https://files.pythonhosted.org/packages/0a/9e/a11c97b087f89cab030fa71206963090d2fecd8eb83e67bb8f3ffb84c024/zstandard-0.23.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d50d31bfedd53a928fed6707b15a8dbeef011bb6366297cc435accc888b27c20", size = 5337533, upload-time = "2024-07-15T00:15:44.114Z" }, - { url = "https://files.pythonhosted.org/packages/fc/79/edeb217c57fe1bf16d890aa91a1c2c96b28c07b46afed54a5dcf310c3f6f/zstandard-0.23.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:72c68dda124a1a138340fb62fa21b9bf4848437d9ca60bd35db36f2d3345f373", size = 5436510, upload-time = "2024-07-15T00:15:46.509Z" }, - { url = "https://files.pythonhosted.org/packages/81/4f/c21383d97cb7a422ddf1ae824b53ce4b51063d0eeb2afa757eb40804a8ef/zstandard-0.23.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:53dd9d5e3d29f95acd5de6802e909ada8d8d8cfa37a3ac64836f3bc4bc5512db", size = 4859973, upload-time = "2024-07-15T00:15:49.939Z" }, - { url = "https://files.pythonhosted.org/packages/ab/15/08d22e87753304405ccac8be2493a495f529edd81d39a0870621462276ef/zstandard-0.23.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:6a41c120c3dbc0d81a8e8adc73312d668cd34acd7725f036992b1b72d22c1772", size = 4936968, upload-time = "2024-07-15T00:15:52.025Z" }, - { url = "https://files.pythonhosted.org/packages/eb/fa/f3670a597949fe7dcf38119a39f7da49a8a84a6f0b1a2e46b2f71a0ab83f/zstandard-0.23.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:40b33d93c6eddf02d2c19f5773196068d875c41ca25730e8288e9b672897c105", size = 5467179, upload-time = "2024-07-15T00:15:54.971Z" }, - { url = "https://files.pythonhosted.org/packages/4e/a9/dad2ab22020211e380adc477a1dbf9f109b1f8d94c614944843e20dc2a99/zstandard-0.23.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:9206649ec587e6b02bd124fb7799b86cddec350f6f6c14bc82a2b70183e708ba", size = 4848577, upload-time = "2024-07-15T00:15:57.634Z" }, - { url = "https://files.pythonhosted.org/packages/08/03/dd28b4484b0770f1e23478413e01bee476ae8227bbc81561f9c329e12564/zstandard-0.23.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:76e79bc28a65f467e0409098fa2c4376931fd3207fbeb6b956c7c476d53746dd", size = 4693899, upload-time = "2024-07-15T00:16:00.811Z" }, - { url = "https://files.pythonhosted.org/packages/2b/64/3da7497eb635d025841e958bcd66a86117ae320c3b14b0ae86e9e8627518/zstandard-0.23.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:66b689c107857eceabf2cf3d3fc699c3c0fe8ccd18df2219d978c0283e4c508a", size = 5199964, upload-time = "2024-07-15T00:16:03.669Z" }, - { url = "https://files.pythonhosted.org/packages/43/a4/d82decbab158a0e8a6ebb7fc98bc4d903266bce85b6e9aaedea1d288338c/zstandard-0.23.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:9c236e635582742fee16603042553d276cca506e824fa2e6489db04039521e90", size = 5655398, upload-time = "2024-07-15T00:16:06.694Z" }, - { url = "https://files.pythonhosted.org/packages/f2/61/ac78a1263bc83a5cf29e7458b77a568eda5a8f81980691bbc6eb6a0d45cc/zstandard-0.23.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:a8fffdbd9d1408006baaf02f1068d7dd1f016c6bcb7538682622c556e7b68e35", size = 5191313, upload-time = "2024-07-15T00:16:09.758Z" }, - { url = "https://files.pythonhosted.org/packages/e7/54/967c478314e16af5baf849b6ee9d6ea724ae5b100eb506011f045d3d4e16/zstandard-0.23.0-cp312-cp312-win32.whl", hash = "sha256:dc1d33abb8a0d754ea4763bad944fd965d3d95b5baef6b121c0c9013eaf1907d", size = 430877, upload-time = "2024-07-15T00:16:11.758Z" }, - { url = "https://files.pythonhosted.org/packages/75/37/872d74bd7739639c4553bf94c84af7d54d8211b626b352bc57f0fd8d1e3f/zstandard-0.23.0-cp312-cp312-win_amd64.whl", hash = "sha256:64585e1dba664dc67c7cdabd56c1e5685233fbb1fc1966cfba2a340ec0dfff7b", size = 495595, upload-time = "2024-07-15T00:16:13.731Z" }, +version = "0.24.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/09/1b/c20b2ef1d987627765dcd5bf1dadb8ef6564f00a87972635099bb76b7a05/zstandard-0.24.0.tar.gz", hash = "sha256:fe3198b81c00032326342d973e526803f183f97aa9e9a98e3f897ebafe21178f", size = 905681, upload-time = "2025-08-17T18:36:36.352Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/01/1f/5c72806f76043c0ef9191a2b65281dacdf3b65b0828eb13bb2c987c4fb90/zstandard-0.24.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:addfc23e3bd5f4b6787b9ca95b2d09a1a67ad5a3c318daaa783ff90b2d3a366e", size = 795228, upload-time = "2025-08-17T18:21:46.978Z" }, + { url = "https://files.pythonhosted.org/packages/0b/ba/3059bd5cd834666a789251d14417621b5c61233bd46e7d9023ea8bc1043a/zstandard-0.24.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:6b005bcee4be9c3984b355336283afe77b2defa76ed6b89332eced7b6fa68b68", size = 640520, upload-time = "2025-08-17T18:21:48.162Z" }, + { url = "https://files.pythonhosted.org/packages/57/07/f0e632bf783f915c1fdd0bf68614c4764cae9dd46ba32cbae4dd659592c3/zstandard-0.24.0-cp311-cp311-manylinux2010_i686.manylinux2014_i686.manylinux_2_12_i686.manylinux_2_17_i686.whl", hash = "sha256:3f96a9130171e01dbb6c3d4d9925d604e2131a97f540e223b88ba45daf56d6fb", size = 5347682, upload-time = "2025-08-17T18:21:50.266Z" }, + { url = "https://files.pythonhosted.org/packages/a6/4c/63523169fe84773a7462cd090b0989cb7c7a7f2a8b0a5fbf00009ba7d74d/zstandard-0.24.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:cd0d3d16e63873253bad22b413ec679cf6586e51b5772eb10733899832efec42", size = 5057650, upload-time = "2025-08-17T18:21:52.634Z" }, + { url = "https://files.pythonhosted.org/packages/c6/16/49013f7ef80293f5cebf4c4229535a9f4c9416bbfd238560edc579815dbe/zstandard-0.24.0-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:b7a8c30d9bf4bd5e4dcfe26900bef0fcd9749acde45cdf0b3c89e2052fda9a13", size = 5404893, upload-time = "2025-08-17T18:21:54.54Z" }, + { url = "https://files.pythonhosted.org/packages/4d/38/78e8bcb5fc32a63b055f2b99e0be49b506f2351d0180173674f516cf8a7a/zstandard-0.24.0-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:52cd7d9fa0a115c9446abb79b06a47171b7d916c35c10e0c3aa6f01d57561382", size = 5452389, upload-time = "2025-08-17T18:21:56.822Z" }, + { url = "https://files.pythonhosted.org/packages/55/8a/81671f05619edbacd49bd84ce6899a09fc8299be20c09ae92f6618ccb92d/zstandard-0.24.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:a0f6fc2ea6e07e20df48752e7700e02e1892c61f9a6bfbacaf2c5b24d5ad504b", size = 5558888, upload-time = "2025-08-17T18:21:58.68Z" }, + { url = "https://files.pythonhosted.org/packages/49/cc/e83feb2d7d22d1f88434defbaeb6e5e91f42a4f607b5d4d2d58912b69d67/zstandard-0.24.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:e46eb6702691b24ddb3e31e88b4a499e31506991db3d3724a85bd1c5fc3cfe4e", size = 5048038, upload-time = "2025-08-17T18:22:00.642Z" }, + { url = "https://files.pythonhosted.org/packages/08/c3/7a5c57ff49ef8943877f85c23368c104c2aea510abb339a2dc31ad0a27c3/zstandard-0.24.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:d5e3b9310fd7f0d12edc75532cd9a56da6293840c84da90070d692e0bb15f186", size = 5573833, upload-time = "2025-08-17T18:22:02.402Z" }, + { url = "https://files.pythonhosted.org/packages/f9/00/64519983cd92535ba4bdd4ac26ac52db00040a52d6c4efb8d1764abcc343/zstandard-0.24.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:76cdfe7f920738ea871f035568f82bad3328cbc8d98f1f6988264096b5264efd", size = 4961072, upload-time = "2025-08-17T18:22:04.384Z" }, + { url = "https://files.pythonhosted.org/packages/72/ab/3a08a43067387d22994fc87c3113636aa34ccd2914a4d2d188ce365c5d85/zstandard-0.24.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:3f2fe35ec84908dddf0fbf66b35d7c2878dbe349552dd52e005c755d3493d61c", size = 5268462, upload-time = "2025-08-17T18:22:06.095Z" }, + { url = "https://files.pythonhosted.org/packages/49/cf/2abb3a1ad85aebe18c53e7eca73223f1546ddfa3bf4d2fb83fc5a064c5ca/zstandard-0.24.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:aa705beb74ab116563f4ce784fa94771f230c05d09ab5de9c397793e725bb1db", size = 5443319, upload-time = "2025-08-17T18:22:08.572Z" }, + { url = "https://files.pythonhosted.org/packages/40/42/0dd59fc2f68f1664cda11c3b26abdf987f4e57cb6b6b0f329520cd074552/zstandard-0.24.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:aadf32c389bb7f02b8ec5c243c38302b92c006da565e120dfcb7bf0378f4f848", size = 5822355, upload-time = "2025-08-17T18:22:10.537Z" }, + { url = "https://files.pythonhosted.org/packages/99/c0/ea4e640fd4f7d58d6f87a1e7aca11fb886ac24db277fbbb879336c912f63/zstandard-0.24.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:e40cd0fc734aa1d4bd0e7ad102fd2a1aefa50ce9ef570005ffc2273c5442ddc3", size = 5365257, upload-time = "2025-08-17T18:22:13.159Z" }, + { url = "https://files.pythonhosted.org/packages/27/a9/92da42a5c4e7e4003271f2e1f0efd1f37cfd565d763ad3604e9597980a1c/zstandard-0.24.0-cp311-cp311-win32.whl", hash = "sha256:cda61c46343809ecda43dc620d1333dd7433a25d0a252f2dcc7667f6331c7b61", size = 435559, upload-time = "2025-08-17T18:22:17.29Z" }, + { url = "https://files.pythonhosted.org/packages/e2/8e/2c8e5c681ae4937c007938f954a060fa7c74f36273b289cabdb5ef0e9a7e/zstandard-0.24.0-cp311-cp311-win_amd64.whl", hash = "sha256:3b95fc06489aa9388400d1aab01a83652bc040c9c087bd732eb214909d7fb0dd", size = 505070, upload-time = "2025-08-17T18:22:14.808Z" }, + { url = "https://files.pythonhosted.org/packages/52/10/a2f27a66bec75e236b575c9f7b0d7d37004a03aa2dcde8e2decbe9ed7b4d/zstandard-0.24.0-cp311-cp311-win_arm64.whl", hash = "sha256:ad9fd176ff6800a0cf52bcf59c71e5de4fa25bf3ba62b58800e0f84885344d34", size = 461507, upload-time = "2025-08-17T18:22:15.964Z" }, + { url = "https://files.pythonhosted.org/packages/26/e9/0bd281d9154bba7fc421a291e263911e1d69d6951aa80955b992a48289f6/zstandard-0.24.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:a2bda8f2790add22773ee7a4e43c90ea05598bffc94c21c40ae0a9000b0133c3", size = 795710, upload-time = "2025-08-17T18:22:19.189Z" }, + { url = "https://files.pythonhosted.org/packages/36/26/b250a2eef515caf492e2d86732e75240cdac9d92b04383722b9753590c36/zstandard-0.24.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:cc76de75300f65b8eb574d855c12518dc25a075dadb41dd18f6322bda3fe15d5", size = 640336, upload-time = "2025-08-17T18:22:20.466Z" }, + { url = "https://files.pythonhosted.org/packages/79/bf/3ba6b522306d9bf097aac8547556b98a4f753dc807a170becaf30dcd6f01/zstandard-0.24.0-cp312-cp312-manylinux2010_i686.manylinux2014_i686.manylinux_2_12_i686.manylinux_2_17_i686.whl", hash = "sha256:d2b3b4bda1a025b10fe0269369475f420177f2cb06e0f9d32c95b4873c9f80b8", size = 5342533, upload-time = "2025-08-17T18:22:22.326Z" }, + { url = "https://files.pythonhosted.org/packages/ea/ec/22bc75bf054e25accdf8e928bc68ab36b4466809729c554ff3a1c1c8bce6/zstandard-0.24.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:9b84c6c210684286e504022d11ec294d2b7922d66c823e87575d8b23eba7c81f", size = 5062837, upload-time = "2025-08-17T18:22:24.416Z" }, + { url = "https://files.pythonhosted.org/packages/48/cc/33edfc9d286e517fb5b51d9c3210e5bcfce578d02a675f994308ca587ae1/zstandard-0.24.0-cp312-cp312-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:c59740682a686bf835a1a4d8d0ed1eefe31ac07f1c5a7ed5f2e72cf577692b00", size = 5393855, upload-time = "2025-08-17T18:22:26.786Z" }, + { url = "https://files.pythonhosted.org/packages/73/36/59254e9b29da6215fb3a717812bf87192d89f190f23817d88cb8868c47ac/zstandard-0.24.0-cp312-cp312-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:6324fde5cf5120fbf6541d5ff3c86011ec056e8d0f915d8e7822926a5377193a", size = 5451058, upload-time = "2025-08-17T18:22:28.885Z" }, + { url = "https://files.pythonhosted.org/packages/9a/c7/31674cb2168b741bbbe71ce37dd397c9c671e73349d88ad3bca9e9fae25b/zstandard-0.24.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:51a86bd963de3f36688553926a84e550d45d7f9745bd1947d79472eca27fcc75", size = 5546619, upload-time = "2025-08-17T18:22:31.115Z" }, + { url = "https://files.pythonhosted.org/packages/e6/01/1a9f22239f08c00c156f2266db857545ece66a6fc0303d45c298564bc20b/zstandard-0.24.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:d82ac87017b734f2fb70ff93818c66f0ad2c3810f61040f077ed38d924e19980", size = 5046676, upload-time = "2025-08-17T18:22:33.077Z" }, + { url = "https://files.pythonhosted.org/packages/a7/91/6c0cf8fa143a4988a0361380ac2ef0d7cb98a374704b389fbc38b5891712/zstandard-0.24.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:92ea7855d5bcfb386c34557516c73753435fb2d4a014e2c9343b5f5ba148b5d8", size = 5576381, upload-time = "2025-08-17T18:22:35.391Z" }, + { url = "https://files.pythonhosted.org/packages/e2/77/1526080e22e78871e786ccf3c84bf5cec9ed25110a9585507d3c551da3d6/zstandard-0.24.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:3adb4b5414febf074800d264ddf69ecade8c658837a83a19e8ab820e924c9933", size = 4953403, upload-time = "2025-08-17T18:22:37.266Z" }, + { url = "https://files.pythonhosted.org/packages/6e/d0/a3a833930bff01eab697eb8abeafb0ab068438771fa066558d96d7dafbf9/zstandard-0.24.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:6374feaf347e6b83ec13cc5dcfa70076f06d8f7ecd46cc71d58fac798ff08b76", size = 5267396, upload-time = "2025-08-17T18:22:39.757Z" }, + { url = "https://files.pythonhosted.org/packages/f3/5e/90a0db9a61cd4769c06374297ecfcbbf66654f74cec89392519deba64d76/zstandard-0.24.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:13fc548e214df08d896ee5f29e1f91ee35db14f733fef8eabea8dca6e451d1e2", size = 5433269, upload-time = "2025-08-17T18:22:42.131Z" }, + { url = "https://files.pythonhosted.org/packages/ce/58/fc6a71060dd67c26a9c5566e0d7c99248cbe5abfda6b3b65b8f1a28d59f7/zstandard-0.24.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:0a416814608610abf5488889c74e43ffa0343ca6cf43957c6b6ec526212422da", size = 5814203, upload-time = "2025-08-17T18:22:44.017Z" }, + { url = "https://files.pythonhosted.org/packages/5c/6a/89573d4393e3ecbfa425d9a4e391027f58d7810dec5cdb13a26e4cdeef5c/zstandard-0.24.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:0d66da2649bb0af4471699aeb7a83d6f59ae30236fb9f6b5d20fb618ef6c6777", size = 5359622, upload-time = "2025-08-17T18:22:45.802Z" }, + { url = "https://files.pythonhosted.org/packages/60/ff/2cbab815d6f02a53a9d8d8703bc727d8408a2e508143ca9af6c3cca2054b/zstandard-0.24.0-cp312-cp312-win32.whl", hash = "sha256:ff19efaa33e7f136fe95f9bbcc90ab7fb60648453b03f95d1de3ab6997de0f32", size = 435968, upload-time = "2025-08-17T18:22:49.493Z" }, + { url = "https://files.pythonhosted.org/packages/ce/a3/8f96b8ddb7ad12344218fbd0fd2805702dafd126ae9f8a1fb91eef7b33da/zstandard-0.24.0-cp312-cp312-win_amd64.whl", hash = "sha256:bc05f8a875eb651d1cc62e12a4a0e6afa5cd0cc231381adb830d2e9c196ea895", size = 505195, upload-time = "2025-08-17T18:22:47.193Z" }, + { url = "https://files.pythonhosted.org/packages/a3/4a/bfca20679da63bfc236634ef2e4b1b4254203098b0170e3511fee781351f/zstandard-0.24.0-cp312-cp312-win_arm64.whl", hash = "sha256:b04c94718f7a8ed7cdd01b162b6caa1954b3c9d486f00ecbbd300f149d2b2606", size = 461605, upload-time = "2025-08-17T18:22:48.317Z" }, ]