diff --git a/.github/workflows/docs.yaml b/.github/workflows/docs.yaml
index 6ede255a00a20c..92c311829c0654 100644
--- a/.github/workflows/docs.yaml
+++ b/.github/workflows/docs.yaml
@@ -18,7 +18,7 @@ concurrency:
jobs:
docs:
name: build docs
- runs-on: ubuntu-latest
+ runs-on: ubuntu-24.04
steps:
- uses: commaai/timeout@v1
diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml
index 86fad1fca8c941..09fb52b9c2dc3e 100644
--- a/.github/workflows/selfdrive_tests.yaml
+++ b/.github/workflows/selfdrive_tests.yaml
@@ -231,7 +231,7 @@ jobs:
uses: actions/cache@v4
with:
path: .ci_cache/comma_download_cache
- key: car_models-${{ hashFiles('selfdrive/car/tests/test_models.py', 'selfdrive/car/tests/routes.py') }}-${{ matrix.job }}
+ key: car_models-${{ hashFiles('selfdrive/car/tests/test_models.py', 'opendbc/car/tests/routes.py') }}-${{ matrix.job }}
- name: Build openpilot
run: ${{ env.RUN }} "scons -j$(nproc)"
- name: Test car models
diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot
index e26a427eb1aba9..f34caba81ba0ee 100644
--- a/Dockerfile.openpilot
+++ b/Dockerfile.openpilot
@@ -1,9 +1,9 @@
FROM ghcr.io/commaai/openpilot-base:latest
-ENV PYTHONUNBUFFERED 1
+ENV PYTHONUNBUFFERED=1
-ENV OPENPILOT_PATH /home/batman/openpilot
-ENV PYTHONPATH ${OPENPILOT_PATH}:${PYTHONPATH}
+ENV OPENPILOT_PATH=/home/batman/openpilot
+ENV PYTHONPATH=${OPENPILOT_PATH}:${PYTHONPATH}
RUN mkdir -p ${OPENPILOT_PATH}
WORKDIR ${OPENPILOT_PATH}
diff --git a/Dockerfile.openpilot_base b/Dockerfile.openpilot_base
index ae0cda374d9471..44d8d95e95d926 100644
--- a/Dockerfile.openpilot_base
+++ b/Dockerfile.openpilot_base
@@ -1,16 +1,16 @@
FROM ubuntu:24.04
-ENV PYTHONUNBUFFERED 1
+ENV PYTHONUNBUFFERED=1
ENV DEBIAN_FRONTEND=noninteractive
RUN apt-get update && \
- apt-get install -y --no-install-recommends sudo tzdata locales ssh pulseaudio xvfb x11-xserver-utils gnome-screenshot && \
+ apt-get install -y --no-install-recommends sudo tzdata locales ssh pulseaudio xvfb x11-xserver-utils gnome-screenshot python3-tk python3-dev && \
rm -rf /var/lib/apt/lists/*
RUN sed -i -e 's/# en_US.UTF-8 UTF-8/en_US.UTF-8 UTF-8/' /etc/locale.gen && locale-gen
-ENV LANG en_US.UTF-8
-ENV LANGUAGE en_US:en
-ENV LC_ALL en_US.UTF-8
+ENV LANG=en_US.UTF-8
+ENV LANGUAGE=en_US:en
+ENV LC_ALL=en_US.UTF-8
COPY tools/install_ubuntu_dependencies.sh /tmp/tools/
RUN /tmp/tools/install_ubuntu_dependencies.sh && \
@@ -55,9 +55,9 @@ RUN mkdir -p /tmp/opencl-driver-intel && \
cd / && \
rm -rf /tmp/opencl-driver-intel
-ENV NVIDIA_VISIBLE_DEVICES all
-ENV NVIDIA_DRIVER_CAPABILITIES graphics,utility,compute
-ENV QTWEBENGINE_DISABLE_SANDBOX 1
+ENV NVIDIA_VISIBLE_DEVICES=all
+ENV NVIDIA_DRIVER_CAPABILITIES=graphics,utility,compute
+ENV QTWEBENGINE_DISABLE_SANDBOX=1
RUN dbus-uuidgen > /etc/machine-id
diff --git a/README.md b/README.md
index 38d32ec3b69761..77002481d31cb2 100644
--- a/README.md
+++ b/README.md
@@ -38,7 +38,8 @@ Quick start: `bash <(curl -fsSL openpilot.comma.ai)`
-To start using openpilot in a car
+
+Using openpilot in a car
------
To use openpilot in a car, you need four things:
@@ -49,6 +50,14 @@ To use openpilot in a car, you need four things:
We have detailed instructions for [how to install the harness and device in a car](https://comma.ai/setup). Note that it's possible to run openpilot on [other hardware](https://blog.comma.ai/self-driving-car-for-free/), although it's not plug-and-play.
+### Branches
+| branch | URL | description |
+|------------------|----------------------------------------|-------------------------------------------------------------------------------------|
+| `release3` | openpilot.comma.ai | This is openpilot's release branch. |
+| `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. |
+
To start developing openpilot
------
diff --git a/cereal/log.capnp b/cereal/log.capnp
index 70508f36e268b9..68ea3099b8f090 100644
--- a/cereal/log.capnp
+++ b/cereal/log.capnp
@@ -2440,6 +2440,14 @@ struct Microphone {
filteredSoundPressureWeightedDb @2 :Float32;
}
+struct Touch {
+ sec @0 :Int64;
+ usec @1 :Int64;
+ type @2 :UInt8;
+ code @3 :Int32;
+ value @4 :Int32;
+}
+
struct Event {
logMonoTime @0 :UInt64; # nanoseconds
valid @67 :Bool = true;
@@ -2520,6 +2528,9 @@ struct Event {
logMessage @18 :Text;
errorLogMessage @85 :Text;
+ # touch frame
+ touch @135 :List(Touch);
+
# navigation
navInstruction @82 :NavInstruction;
navRoute @83 :NavRoute;
diff --git a/cereal/services.py b/cereal/services.py
index 771338f50780e1..87fdca77b79b15 100755
--- a/cereal/services.py
+++ b/cereal/services.py
@@ -22,6 +22,7 @@ def __init__(self, should_log: bool, frequency: float, decimation: Optional[int]
"temperatureSensor2": (True, 2., 200),
"gpsNMEA": (True, 9.),
"deviceState": (True, 2., 1),
+ "touch": (True, 20., 1),
"can": (True, 100., 2053), # decimation gives ~3 msgs in a full segment
"controlsState": (True, 100., 10),
"selfdriveState": (True, 100., 10),
diff --git a/common/transformations/model.py b/common/transformations/model.py
index aaa12d776a8ed0..ea1dff30e8fc4e 100644
--- a/common/transformations/model.py
+++ b/common/transformations/model.py
@@ -1,7 +1,7 @@
import numpy as np
from openpilot.common.transformations.orientation import rot_from_euler
-from openpilot.common.transformations.camera import get_view_frame_from_calib_frame, view_frame_from_device_frame
+from openpilot.common.transformations.camera import get_view_frame_from_calib_frame, view_frame_from_device_frame, _ar_ox_fisheye
# segnet
SEGNET_SIZE = (512, 384)
@@ -39,6 +39,13 @@
[0.0, sbigmodel_fl, 0.5 * (256 + MEDMODEL_CY)],
[0.0, 0.0, 1.0]])
+DM_INPUT_SIZE = (1440, 960)
+dmonitoringmodel_fl = _ar_ox_fisheye.focal_length
+dmonitoringmodel_intrinsics = np.array([
+ [dmonitoringmodel_fl, 0.0, DM_INPUT_SIZE[0]/2],
+ [0.0, dmonitoringmodel_fl, DM_INPUT_SIZE[1]/2 - (_ar_ox_fisheye.height - DM_INPUT_SIZE[1])/2],
+ [0.0, 0.0, 1.0]])
+
bigmodel_frame_from_calib_frame = np.dot(bigmodel_intrinsics,
get_view_frame_from_calib_frame(0, 0, 0, 0))
diff --git a/docs/CARS.md b/docs/CARS.md
index 2e2a614a3853c7..c0b0f1706e1b55 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -103,7 +103,7 @@ A supported vehicle is one that just works when you install a comma device. All
|Hyundai|Ioniq Plug-in Hybrid 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Parts
- 1 Hyundai H connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here ||
|Hyundai|Kona 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|6 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Parts
- 1 Hyundai B connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here ||
|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Parts
- 1 Hyundai G connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here ||
-|Hyundai|Kona Electric 2022-23|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Parts
- 1 Hyundai O connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here ||
+|Hyundai|Kona Electric 2022-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Parts
- 1 Hyundai O connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here ||
|Hyundai|Kona Electric (with HDA II, Korea only) 2023[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Parts
- 1 Hyundai R connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here ||
|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Parts
- 1 Hyundai I connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here ||
|Hyundai|Palisade 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Parts
- 1 Hyundai H connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here ||
diff --git a/docs/css/tooltip.css b/docs/css/tooltip.css
new file mode 100644
index 00000000000000..b9a54f793f9fe5
--- /dev/null
+++ b/docs/css/tooltip.css
@@ -0,0 +1,44 @@
+[data-tooltip] {
+ position: relative;
+ display: inline-block;
+ border-bottom: 1px dotted black;
+}
+
+[data-tooltip] .tooltip-content {
+ width: max-content;
+ max-width: 25em;
+ position: absolute;
+ top: 100%;
+ left: 50%;
+ transform: translateX(-50%);
+ background-color: white;
+ color: #404040;
+ box-shadow: 0 4px 14px 0 rgba(0,0,0,.2), 0 0 0 1px rgba(0,0,0,.05);
+ padding: 10px;
+ font: 14px/1.5 Lato, proxima-nova, Helvetica Neue, Arial, sans-serif;
+ text-decoration: none;
+ opacity: 0;
+ visibility: hidden;
+ transition: opacity 0.1s, visibility 0s;
+ z-index: 1000;
+ pointer-events: none; /* Prevent accidental interaction */
+}
+
+[data-tooltip]:hover .tooltip-content {
+ opacity: 1;
+ visibility: visible;
+ pointer-events: auto; /* Allow interaction when visible */
+}
+
+.tooltip-content .tooltip-glossary-link {
+ display: inline-block;
+ margin-top: 8px;
+ font-size: 12px;
+ color: #007bff;
+ text-decoration: none;
+}
+
+.tooltip-content .tooltip-glossary-link:hover {
+ color: #0056b3;
+ text-decoration: underline;
+}
diff --git a/docs/glossary.toml b/docs/glossary.toml
new file mode 100644
index 00000000000000..e69de29bb2d1d6
diff --git a/docs/hooks/glossary.py b/docs/hooks/glossary.py
new file mode 100644
index 00000000000000..e2fa3d51e04cb9
--- /dev/null
+++ b/docs/hooks/glossary.py
@@ -0,0 +1,68 @@
+import re
+import tomllib
+
+def load_glossary(file_path="docs/glossary.toml"):
+ with open(file_path, "rb") as f:
+ glossary_data = tomllib.load(f)
+ return glossary_data.get("glossary", {})
+
+def generate_anchor_id(name):
+ return name.replace(" ", "-").replace("_", "-").lower()
+
+def format_markdown_term(name, definition):
+ anchor_id = generate_anchor_id(name)
+ markdown = f"* [**{name.replace('_', ' ').title()}**](#{anchor_id})"
+ if definition.get("abbreviation"):
+ markdown += f" *({definition['abbreviation']})*"
+ if definition.get("description"):
+ markdown += f": {definition['description']}\n"
+ return markdown
+
+def glossary_markdown(vocabulary):
+ markdown = ""
+ for category, terms in vocabulary.items():
+ markdown += f"## {category.replace('_', ' ').title()}\n\n"
+ for name, definition in terms.items():
+ markdown += format_markdown_term(name, definition)
+ return markdown
+
+def format_tooltip_html(term_key, definition, html):
+ display_term = term_key.replace("_", " ").title()
+ clean_description = re.sub(r"\[(.+)]\(.+\)", r"\1", definition["description"])
+ glossary_link = (
+ f"Glossaryđź”—"
+ )
+ return re.sub(
+ re.escape(display_term),
+ lambda
+ match: f"{match.group(0)}{clean_description} {glossary_link}",
+ html,
+ flags=re.IGNORECASE,
+ )
+
+def apply_tooltip(_term_key, _definition, pattern, html):
+ return re.sub(
+ pattern,
+ lambda match: format_tooltip_html(_term_key, _definition, match.group(0)),
+ html,
+ flags=re.IGNORECASE,
+ )
+
+def tooltip_html(vocabulary, html):
+ for _category, terms in vocabulary.items():
+ for term_key, definition in terms.items():
+ if definition.get("description"):
+ pattern = rf"(?)(?!\([^)]*\))"
+ html = apply_tooltip(term_key, definition, pattern, html)
+ return html
+
+# Page Hooks
+def on_page_markdown(markdown, **kwargs):
+ glossary = load_glossary()
+ return markdown.replace("{{GLOSSARY_DEFINITIONS}}", glossary_markdown(glossary))
+
+def on_page_content(html, **kwargs):
+ if kwargs.get("page").title == "Glossary":
+ return html
+ glossary = load_glossary()
+ return tooltip_html(glossary, html)
diff --git a/launch_env.sh b/launch_env.sh
index 3d2900650b1322..5f67052e67db05 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="11.3"
+ export AGNOS_VERSION="11.4"
fi
export STAGING_ROOT="/data/safe_staging"
diff --git a/mkdocs.yml b/mkdocs.yml
index 58527ea7ee021d..a66d1c76d45bba 100644
--- a/mkdocs.yml
+++ b/mkdocs.yml
@@ -8,6 +8,10 @@ strict: true
docs_dir: docs
site_dir: docs_site/
+hooks:
+ - docs/hooks/glossary.py
+extra_css:
+ - css/tooltip.css
theme:
name: readthedocs
navigation_depth: 3
diff --git a/msgq_repo b/msgq_repo
index 434ed2312c980b..5bb86f8bc74340 160000
--- a/msgq_repo
+++ b/msgq_repo
@@ -1 +1 @@
-Subproject commit 434ed2312c980b5504a4a75001d04c3ecbddf93f
+Subproject commit 5bb86f8bc7434048ab2d5ce0243a97d9848b34de
diff --git a/opendbc_repo b/opendbc_repo
index b89fe79950121c..fd8471dc0d6fbd 160000
--- a/opendbc_repo
+++ b/opendbc_repo
@@ -1 +1 @@
-Subproject commit b89fe79950121ca93d8a1f0d3fd17df31703be2a
+Subproject commit fd8471dc0d6fbd7ae009ab6d75036667c5b576a5
diff --git a/panda b/panda
index c7cc2deaf04640..4ca9905011ba87 160000
--- a/panda
+++ b/panda
@@ -1 +1 @@
-Subproject commit c7cc2deaf046403899b5bcc964b9f48bfd508534
+Subproject commit 4ca9905011ba875efa4278b2dcb507a759b0e13e
diff --git a/pyproject.toml b/pyproject.toml
index ff5c1e239261fd..3d577c7f626e62 100644
--- a/pyproject.toml
+++ b/pyproject.toml
@@ -1,6 +1,6 @@
[project]
name = "openpilot"
-requires-python = ">= 3.11, <= 3.12"
+requires-python = ">= 3.11, < 3.13"
license = {text = "MIT License"}
version = "0.1.0"
description = "an open source driver assistance system"
@@ -118,7 +118,7 @@ dev = [
]
tools = [
- "metadrive-simulator @ https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal/metadrive_simulator-0.4.2.3-py3-none-any.whl ; (platform_machine != 'aarch64')",
+ "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",
]
diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py
index 94afec50e2a390..9477b36bbb8815 100644
--- a/selfdrive/car/car_specific.py
+++ b/selfdrive/car/car_specific.py
@@ -148,7 +148,8 @@ def update(self, CS: car.CarState, CS_prev: car.CarState, CC: car.CarControl):
# To avoid re-engaging when openpilot cancels, check user engagement intention via buttons
# Main button also can trigger an engagement on these cars
self.cruise_buttons.append(any(ev.type in HYUNDAI_ENABLE_BUTTONS for ev in CS.buttonEvents))
- events = self.create_common_events(CS, CS_prev, pcm_enable=self.CP.pcmCruise, allow_enable=any(self.cruise_buttons))
+ events = self.create_common_events(CS, CS_prev, extra_gears=(GearShifter.sport, GearShifter.manumatic),
+ pcm_enable=self.CP.pcmCruise, allow_enable=any(self.cruise_buttons))
# low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s)
if CS.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.:
diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py
index 64cbf473d63d29..66b92319ca03cc 100644
--- a/selfdrive/controls/lib/drive_helpers.py
+++ b/selfdrive/controls/lib/drive_helpers.py
@@ -5,12 +5,15 @@
MIN_SPEED = 1.0
CONTROL_N = 17
CAR_ROTATION_RADIUS = 0.0
+# This is a turn radius smaller than most cars can achieve
+MAX_CURVATURE = 0.2
# EU guidelines
MAX_LATERAL_JERK = 5.0
MAX_VEL_ERR = 5.0
def clip_curvature(v_ego, prev_curvature, new_curvature):
+ new_curvature = clip(new_curvature, -MAX_CURVATURE, MAX_CURVATURE)
v_ego = max(MIN_SPEED, v_ego)
max_curvature_rate = MAX_LATERAL_JERK / (v_ego**2) # inexact calculation, check https://github.com/commaai/openpilot/pull/24755
safe_desired_curvature = clip(new_curvature,
diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py
index f1637d960cf58e..eba8019117166b 100755
--- a/selfdrive/controls/lib/longitudinal_planner.py
+++ b/selfdrive/controls/lib/longitudinal_planner.py
@@ -50,24 +50,20 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP):
return [a_target[0], min(a_target[1], a_x_allowed)]
-def get_accel_from_plan(CP, speeds, accels):
+def get_accel_from_plan(speeds, accels, action_t=DT_MDL, vEgoStopping=0.05):
if len(speeds) == CONTROL_N:
- v_target_now = interp(DT_MDL, CONTROL_N_T_IDX, speeds)
- a_target_now = interp(DT_MDL, CONTROL_N_T_IDX, accels)
+ v_now = speeds[0]
+ a_now = accels[0]
- v_target = interp(CP.longitudinalActuatorDelay + DT_MDL, CONTROL_N_T_IDX, speeds)
- if v_target != v_target_now:
- a_target = 2 * (v_target - v_target_now) / CP.longitudinalActuatorDelay - a_target_now
- else:
- a_target = a_target_now
-
- v_target_1sec = interp(CP.longitudinalActuatorDelay + DT_MDL + 1.0, CONTROL_N_T_IDX, speeds)
+ v_target = interp(action_t, CONTROL_N_T_IDX, speeds)
+ a_target = 2 * (v_target - v_now) / (action_t) - a_now
+ v_target_1sec = interp(action_t + 1.0, CONTROL_N_T_IDX, speeds)
else:
v_target = 0.0
v_target_1sec = 0.0
a_target = 0.0
- should_stop = (v_target < CP.vEgoStopping and
- v_target_1sec < CP.vEgoStopping)
+ should_stop = (v_target < vEgoStopping and
+ v_target_1sec < vEgoStopping)
return a_target, should_stop
@@ -201,7 +197,9 @@ def publish(self, sm, pm):
longitudinalPlan.longitudinalPlanSource = self.mpc.source
longitudinalPlan.fcw = self.fcw
- a_target, should_stop = get_accel_from_plan(self.CP, longitudinalPlan.speeds, longitudinalPlan.accels)
+ action_t = self.CP.longitudinalActuatorDelay + DT_MDL
+ a_target, should_stop = get_accel_from_plan(longitudinalPlan.speeds, longitudinalPlan.accels,
+ action_t=action_t, vEgoStopping=self.CP.vEgoStopping)
longitudinalPlan.aTarget = a_target
longitudinalPlan.shouldStop = should_stop
longitudinalPlan.allowBrake = True
diff --git a/selfdrive/debug/touch_replay.py b/selfdrive/debug/touch_replay.py
new file mode 100755
index 00000000000000..1e1596d2640817
--- /dev/null
+++ b/selfdrive/debug/touch_replay.py
@@ -0,0 +1,54 @@
+#!/usr/bin/env python3
+import argparse
+
+import numpy as np
+import matplotlib.pyplot as plt
+
+from openpilot.tools.lib.logreader import LogReader
+
+if __name__ == '__main__':
+ parser = argparse.ArgumentParser()
+ parser.add_argument('--width', default=2160, type=int)
+ parser.add_argument('--height', default=1080, type=int)
+ parser.add_argument('--route', default='rlog', type=str)
+ args = parser.parse_args()
+
+ w = args.width
+ h = args.height
+ route = args.route
+
+ fingers = [[-1, -1]] * 5
+ touch_points = []
+ current_slot = 0
+
+ lr = list(LogReader(route))
+ for msg in lr:
+ if msg.which() == 'touch':
+ for event in msg.touch:
+ if event.type == 3 and event.code == 47:
+ current_slot = event.value
+ elif event.type == 3 and event.code == 57 and event.value == -1:
+ fingers[current_slot] = [-1, -1]
+ elif event.type == 3 and event.code == 53:
+ fingers[current_slot][1] = h - (h - event.value)
+ if fingers[current_slot][0] != -1:
+ touch_points.append(fingers[current_slot].copy())
+ elif event.type == 3 and event.code == 54:
+ fingers[current_slot][0] = w - event.value
+ if fingers[current_slot][1] != -1:
+ touch_points.append(fingers[current_slot].copy())
+
+ if not touch_points:
+ print(f'No touch events found for {route}')
+ quit()
+
+ unique_points, counts = np.unique(touch_points, axis=0, return_counts=True)
+
+ plt.figure(figsize=(10, 3))
+ plt.scatter(unique_points[:, 0], unique_points[:, 1], c=counts, s=counts * 20, edgecolors='red')
+ plt.colorbar()
+ plt.title(f'Touches for {route}')
+ plt.xlim(0, w)
+ plt.ylim(0, h)
+ plt.grid(True)
+ plt.show()
diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript
index 2a965b8690e506..ef0fd52f334dcb 100644
--- a/selfdrive/modeld/SConscript
+++ b/selfdrive/modeld/SConscript
@@ -33,8 +33,7 @@ snpe_rpath = lenvCython['RPATH'] + [snpe_rpath_qcom if arch == "larch64" else sn
cython_libs = envCython["LIBS"] + libs
commonmodel_lib = lenv.Library('commonmodel', common_src)
lenvCython.Program('models/commonmodel_pyx.so', 'models/commonmodel_pyx.pyx', LIBS=[commonmodel_lib, *cython_libs], FRAMEWORKS=frameworks)
-
-tinygrad_files = ["#"+x for x in glob.glob(env.Dir("#tinygrad_repo").relpath + "/**", recursive=True, root_dir=env.Dir("#").abspath)]
+tinygrad_files = ["#"+x for x in glob.glob(env.Dir("#tinygrad_repo").relpath + "/**", recursive=True, root_dir=env.Dir("#").abspath) if 'pycache' not in x]
# Get model metadata
fn = File("models/supercombo").abspath
@@ -42,8 +41,6 @@ cmd = f'python3 {Dir("#selfdrive/modeld").abspath}/get_model_metadata.py {fn}.on
lenv.Command(fn + "_metadata.pkl", [fn + ".onnx"] + tinygrad_files, cmd)
# Compile tinygrad model
-# TODO this is all super hacky
-
pythonpath_string = 'PYTHONPATH="${PYTHONPATH}:' + env.Dir("#tinygrad_repo").abspath + '"'
if arch == 'larch64':
device_string = 'QCOM=1'
diff --git a/selfdrive/modeld/dmonitoringmodeld.py b/selfdrive/modeld/dmonitoringmodeld.py
index 0ac2d4675ce079..ebc24ad0246dec 100755
--- a/selfdrive/modeld/dmonitoringmodeld.py
+++ b/selfdrive/modeld/dmonitoringmodeld.py
@@ -1,8 +1,10 @@
#!/usr/bin/env python3
import os
from openpilot.system.hardware import TICI
-## TODO this is hack
if TICI:
+ from tinygrad.tensor import Tensor
+ from tinygrad.dtype import dtypes
+ from openpilot.selfdrive.modeld.runners.tinygrad_helpers import qcom_tensor_from_opencl_address
os.environ['QCOM'] = '1'
else:
from openpilot.selfdrive.modeld.runners.ort_helpers import make_onnx_cpu_runner
@@ -20,13 +22,13 @@
from msgq.visionipc import VisionIpcClient, VisionStreamType, VisionBuf
from openpilot.common.swaglog import cloudlog
from openpilot.common.realtime import set_realtime_priority
-from openpilot.selfdrive.modeld.models.commonmodel_pyx import CLContext
+from openpilot.common.transformations.model import dmonitoringmodel_intrinsics, DM_INPUT_SIZE
+from openpilot.common.transformations.camera import _ar_ox_fisheye, _os_fisheye
+from openpilot.selfdrive.modeld.models.commonmodel_pyx import CLContext, MonitoringModelFrame
from openpilot.selfdrive.modeld.parse_model_outputs import sigmoid
-from tinygrad.tensor import Tensor
+MODEL_WIDTH, MODEL_HEIGHT = DM_INPUT_SIZE
CALIB_LEN = 3
-MODEL_WIDTH = 1440
-MODEL_HEIGHT = 960
FEATURE_LEN = 512
OUTPUT_SIZE = 84 + FEATURE_LEN
@@ -67,26 +69,31 @@ class ModelState:
def __init__(self, cl_ctx):
assert ctypes.sizeof(DMonitoringModelResult) == OUTPUT_SIZE * ctypes.sizeof(ctypes.c_float)
- self.numpy_inputs = {'calib': np.zeros((1, CALIB_LEN), dtype=np.float32),
- 'input_img': np.zeros((1,MODEL_HEIGHT * MODEL_WIDTH), dtype=np.uint8)}
- self.tensor_inputs = {k: Tensor(v, device='NPY').realize() for k,v in self.numpy_inputs.items()}
+ self.frame = MonitoringModelFrame(cl_ctx)
+ self.numpy_inputs = {
+ 'calib': np.zeros((1, CALIB_LEN), dtype=np.float32),
+ }
if TICI:
+ self.tensor_inputs = {k: Tensor(v, device='NPY').realize() for k,v in self.numpy_inputs.items()}
with open(MODEL_PKL_PATH, "rb") as f:
self.model_run = pickle.load(f)
else:
self.onnx_cpu_runner = make_onnx_cpu_runner(MODEL_PATH)
- def run(self, buf:VisionBuf, calib:np.ndarray) -> tuple[np.ndarray, float]:
+ def run(self, buf:VisionBuf, calib:np.ndarray, transform:np.ndarray) -> tuple[np.ndarray, float]:
self.numpy_inputs['calib'][0,:] = calib
t1 = time.perf_counter()
- # TODO use opencl buffer directly to make tensor
- v_offset = buf.height - MODEL_HEIGHT
- h_offset = (buf.width - MODEL_WIDTH) // 2
- buf_data = buf.data.reshape(-1, buf.stride)
- self.numpy_inputs['input_img'][:] = buf_data[v_offset:v_offset+MODEL_HEIGHT, h_offset:h_offset+MODEL_WIDTH].reshape((1, -1))
+
+ input_img_cl = self.frame.prepare(buf, transform.flatten())
+ if TICI:
+ # The imgs tensors are backed by opencl memory, only need init once
+ if 'input_img' not in self.tensor_inputs:
+ self.tensor_inputs['input_img'] = qcom_tensor_from_opencl_address(input_img_cl.mem_address, (1, MODEL_WIDTH*MODEL_HEIGHT), dtype=dtypes.uint8)
+ else:
+ self.numpy_inputs['input_img'] = self.frame.buffer_from_cl(input_img_cl).reshape((1, MODEL_WIDTH*MODEL_HEIGHT))
if TICI:
output = self.model_run(**self.tensor_inputs).numpy().flatten()
@@ -147,18 +154,23 @@ def main():
pm = PubMaster(["driverStateV2"])
calib = np.zeros(CALIB_LEN, dtype=np.float32)
+ model_transform = None
while True:
buf = vipc_client.recv()
if buf is None:
continue
+ if model_transform is None:
+ cam = _os_fisheye if buf.width == _os_fisheye.width else _ar_ox_fisheye
+ model_transform = np.linalg.inv(np.dot(dmonitoringmodel_intrinsics, np.linalg.inv(cam.intrinsics))).astype(np.float32)
+
sm.update(0)
if sm.updated["liveCalibration"]:
calib[:] = np.array(sm["liveCalibration"].rpyCalib)
t1 = time.perf_counter()
- model_output, gpu_execution_time = model.run(buf, calib)
+ model_output, gpu_execution_time = model.run(buf, calib, model_transform)
t2 = time.perf_counter()
pm.send("driverStateV2", get_driverstate_packet(model_output, vipc_client.frame_id, vipc_client.timestamp_sof, t2 - t1, gpu_execution_time))
diff --git a/selfdrive/modeld/fill_model_msg.py b/selfdrive/modeld/fill_model_msg.py
index 115ec94f88fcbd..a13d632aa676f9 100644
--- a/selfdrive/modeld/fill_model_msg.py
+++ b/selfdrive/modeld/fill_model_msg.py
@@ -3,11 +3,22 @@
import numpy as np
from cereal import log
from openpilot.selfdrive.modeld.constants import ModelConstants, Plan, Meta
+from openpilot.selfdrive.controls.lib.drive_helpers import MIN_SPEED
SEND_RAW_PRED = os.getenv('SEND_RAW_PRED')
ConfidenceClass = log.ModelDataV2.ConfidenceClass
+def curv_from_psis(psi_target, psi_rate, vego, delay):
+ vego = np.clip(vego, MIN_SPEED, np.inf)
+ curv_from_psi = psi_target / (vego * delay) # epsilon to prevent divide-by-zero
+ return 2*curv_from_psi - psi_rate / vego
+
+def get_curvature_from_plan(plan, vego, delay):
+ psi_target = np.interp(delay, ModelConstants.T_IDXS, plan[:, Plan.T_FROM_CURRENT_EULER][:, 2])
+ psi_rate = plan[:, Plan.ORIENTATION_RATE][0, 2]
+ return curv_from_psis(psi_target, psi_rate, vego, delay)
+
class PublishState:
def __init__(self):
self.disengage_buffer = np.zeros(ModelConstants.CONFIDENCE_BUFFER_LEN*ModelConstants.DISENGAGE_WIDTH, dtype=np.float32)
@@ -55,14 +66,17 @@ def fill_lane_line_meta(builder, lane_lines, lane_line_probs):
builder.rightProb = lane_line_probs[2]
def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._DynamicStructBuilder,
- net_output_data: dict[str, np.ndarray], publish_state: PublishState,
- vipc_frame_id: int, vipc_frame_id_extra: int, frame_id: int, frame_drop: float,
- timestamp_eof: int, model_execution_time: float, valid: bool) -> None:
+ net_output_data: dict[str, np.ndarray], v_ego: float, delay: float,
+ publish_state: PublishState, vipc_frame_id: int, vipc_frame_id_extra: int,
+ frame_id: int, frame_drop: float, timestamp_eof: int, model_execution_time: float,
+ valid: bool) -> None:
frame_age = frame_id - vipc_frame_id if frame_id > vipc_frame_id else 0
frame_drop_perc = frame_drop * 100
extended_msg.valid = valid
base_msg.valid = valid
+ desired_curv = float(get_curvature_from_plan(net_output_data['plan'][0], v_ego, delay))
+
driving_model_data = base_msg.drivingModelData
driving_model_data.frameId = vipc_frame_id
@@ -71,7 +85,7 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D
driving_model_data.modelExecutionTime = model_execution_time
action = driving_model_data.action
- action.desiredCurvature = float(net_output_data['desired_curvature'][0,0])
+ action.desiredCurvature = desired_curv
modelV2 = extended_msg.modelV2
modelV2.frameId = vipc_frame_id
@@ -106,7 +120,7 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D
# lateral planning
action = modelV2.action
- action.desiredCurvature = float(net_output_data['desired_curvature'][0,0])
+ action.desiredCurvature = desired_curv
# times at X_IDXS according to model plan
PLAN_T_IDXS = [np.nan] * ModelConstants.IDX_N
diff --git a/selfdrive/modeld/modeld b/selfdrive/modeld/modeld
index e1cef4dcc35f18..5ba46885548af1 100755
--- a/selfdrive/modeld/modeld
+++ b/selfdrive/modeld/modeld
@@ -1,10 +1,4 @@
#!/usr/bin/env bash
DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)"
-cd "$DIR/../../"
-
-if [ -f "$DIR/libthneed.so" ]; then
- export LD_PRELOAD="$DIR/libthneed.so"
-fi
-
exec "$DIR/modeld.py" "$@"
diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py
index 4b19d103b4281e..49f8c483f05501 100755
--- a/selfdrive/modeld/modeld.py
+++ b/selfdrive/modeld/modeld.py
@@ -1,7 +1,8 @@
#!/usr/bin/env python3
import os
from openpilot.system.hardware import TICI
-## TODO this is hack
+
+#
if TICI:
from tinygrad.tensor import Tensor
from tinygrad.dtype import dtypes
@@ -30,7 +31,7 @@
from openpilot.selfdrive.modeld.parse_model_outputs import Parser
from openpilot.selfdrive.modeld.fill_model_msg import fill_model_msg, fill_pose_msg, PublishState
from openpilot.selfdrive.modeld.constants import ModelConstants
-from openpilot.selfdrive.modeld.models.commonmodel_pyx import ModelFrame, CLContext
+from openpilot.selfdrive.modeld.models.commonmodel_pyx import DrivingModelFrame, CLContext
PROCESS_NAME = "selfdrive.modeld.modeld"
@@ -40,9 +41,6 @@
MODEL_PKL_PATH = Path(__file__).parent / 'models/supercombo_tinygrad.pkl'
METADATA_PATH = Path(__file__).parent / 'models/supercombo_metadata.pkl'
-# TODO: should not hardcoded
-IMG_INPUT_SHAPE = (1, 12, 128, 256)
-
class FrameMeta:
frame_id: int = 0
timestamp_sof: int = 0
@@ -53,31 +51,27 @@ def __init__(self, vipc=None):
self.frame_id, self.timestamp_sof, self.timestamp_eof = vipc.frame_id, vipc.timestamp_sof, vipc.timestamp_eof
class ModelState:
- frame: ModelFrame
- wide_frame: ModelFrame
+ frames: dict[str, DrivingModelFrame]
inputs: dict[str, np.ndarray]
output: np.ndarray
prev_desire: np.ndarray # for tracking the rising edge of the pulse
def __init__(self, context: CLContext):
- self.frame = ModelFrame(context)
- self.wide_frame = ModelFrame(context)
+ self.frames = {'input_imgs': DrivingModelFrame(context), 'big_input_imgs': DrivingModelFrame(context)}
self.prev_desire = np.zeros(ModelConstants.DESIRE_LEN, dtype=np.float32)
self.full_features_20Hz = np.zeros((ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32)
self.desire_20Hz = np.zeros((ModelConstants.FULL_HISTORY_BUFFER_LEN + 1, ModelConstants.DESIRE_LEN), dtype=np.float32)
- self.prev_desired_curv_20hz = np.zeros((ModelConstants.FULL_HISTORY_BUFFER_LEN + 1, ModelConstants.PREV_DESIRED_CURV_LEN), dtype=np.float32)
# img buffers are managed in openCL transform code
self.numpy_inputs = {
'desire': np.zeros((1, (ModelConstants.HISTORY_BUFFER_LEN+1), 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.HISTORY_BUFFER_LEN+1), ModelConstants.PREV_DESIRED_CURV_LEN), dtype=np.float32),
'features_buffer': np.zeros((1, ModelConstants.HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32),
}
with open(METADATA_PATH, 'rb') as f:
model_metadata = pickle.load(f)
+ self.input_shapes = model_metadata['input_shapes']
self.output_slices = model_metadata['output_slices']
net_output_size = model_metadata['output_shapes']['outputs'][1]
@@ -109,18 +103,17 @@ def run(self, buf: VisionBuf, wbuf: VisionBuf, transform: np.ndarray, transform_
self.numpy_inputs['desire'][:] = self.desire_20Hz.reshape((1,25,4,-1)).max(axis=2)
self.numpy_inputs['traffic_convention'][:] = inputs['traffic_convention']
- self.numpy_inputs['lateral_control_params'][:] = inputs['lateral_control_params']
- input_imgs_cl = self.frame.prepare(buf, transform.flatten())
- big_input_imgs_cl = self.wide_frame.prepare(wbuf, transform_wide.flatten())
+ imgs_cl = {'input_imgs': self.frames['input_imgs'].prepare(buf, transform.flatten()),
+ 'big_input_imgs': self.frames['big_input_imgs'].prepare(wbuf, transform_wide.flatten())}
if TICI:
# The imgs tensors are backed by opencl memory, only need init once
- if 'input_imgs' not in self.tensor_inputs:
- self.tensor_inputs['input_imgs'] = qcom_tensor_from_opencl_address(input_imgs_cl.mem_address, IMG_INPUT_SHAPE, dtype=dtypes.uint8)
- self.tensor_inputs['big_input_imgs'] = qcom_tensor_from_opencl_address(big_input_imgs_cl.mem_address, IMG_INPUT_SHAPE, dtype=dtypes.uint8)
+ for key in imgs_cl:
+ if key not in self.tensor_inputs:
+ self.tensor_inputs[key] = qcom_tensor_from_opencl_address(imgs_cl[key].mem_address, self.input_shapes[key], dtype=dtypes.uint8)
else:
- self.numpy_inputs['input_imgs'] = self.frame.buffer_from_cl(input_imgs_cl).reshape(IMG_INPUT_SHAPE)
- self.numpy_inputs['big_input_imgs'] = self.wide_frame.buffer_from_cl(big_input_imgs_cl).reshape(IMG_INPUT_SHAPE)
+ for key in imgs_cl:
+ self.numpy_inputs[key] = self.frames[key].buffer_from_cl(imgs_cl[key]).reshape(self.input_shapes[key])
if prepare_only:
return None
@@ -135,13 +128,8 @@ def run(self, buf: VisionBuf, wbuf: VisionBuf, transform: np.ndarray, transform_
self.full_features_20Hz[:-1] = self.full_features_20Hz[1:]
self.full_features_20Hz[-1] = outputs['hidden_state'][0, :]
- self.prev_desired_curv_20hz[:-1] = self.prev_desired_curv_20hz[1:]
- self.prev_desired_curv_20hz[-1] = outputs['desired_curvature'][0, :]
-
idxs = np.arange(-4,-100,-4)[::-1]
self.numpy_inputs['features_buffer'][:] = self.full_features_20Hz[idxs]
- # TODO model only uses last value now, once that changes we need to input strided action history buffer
- self.numpy_inputs['prev_desired_curv'][-ModelConstants.PREV_DESIRED_CURV_LEN:] = 0. * self.prev_desired_curv_20hz[-4, :]
return outputs
@@ -252,7 +240,6 @@ def main(demo=False):
is_rhd = sm["driverMonitoringState"].isRHD
frame_id = sm["roadCameraState"].frameId
v_ego = max(sm["carState"].vEgo, 0.)
- lateral_control_params = np.array([v_ego, steer_delay], dtype=np.float32)
if sm.updated["liveCalibration"] and sm.seen['roadCameraState'] and sm.seen['deviceState']:
device_from_calib_euler = np.array(sm["liveCalibration"].rpyCalib, dtype=np.float32)
dc = DEVICE_CAMERAS[(str(sm['deviceState'].deviceType), str(sm['roadCameraState'].sensor))]
@@ -283,7 +270,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()
@@ -295,7 +281,8 @@ def main(demo=False):
modelv2_send = messaging.new_message('modelV2')
drivingdata_send = messaging.new_message('drivingModelData')
posenet_send = messaging.new_message('cameraOdometry')
- fill_model_msg(drivingdata_send, modelv2_send, model_output, publish_state, meta_main.frame_id, meta_extra.frame_id, frame_id,
+ fill_model_msg(drivingdata_send, modelv2_send, model_output, v_ego, steer_delay,
+ publish_state, meta_main.frame_id, meta_extra.frame_id, frame_id,
frame_drop_ratio, meta_main.timestamp_eof, model_execution_time, live_calib_seen)
desire_state = modelv2_send.modelV2.meta.desireState
diff --git a/selfdrive/modeld/models/commonmodel.cc b/selfdrive/modeld/models/commonmodel.cc
index ef730e01aaaa3a..ad2620c7b4a687 100644
--- a/selfdrive/modeld/models/commonmodel.cc
+++ b/selfdrive/modeld/models/commonmodel.cc
@@ -1,32 +1,24 @@
#include "selfdrive/modeld/models/commonmodel.h"
-#include
#include
#include
#include "common/clutil.h"
-ModelFrame::ModelFrame(cl_device_id device_id, cl_context context) {
+DrivingModelFrame::DrivingModelFrame(cl_device_id device_id, cl_context context) : ModelFrame(device_id, context) {
input_frames = std::make_unique(buf_size);
input_frames_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, buf_size, NULL, &err));
-
- q = CL_CHECK_ERR(clCreateCommandQueue(context, device_id, 0, &err));
- y_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_WIDTH * MODEL_HEIGHT, NULL, &err));
- u_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err));
- v_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err));
img_buffer_20hz_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, 5*frame_size_bytes, NULL, &err));
region.origin = 4 * frame_size_bytes;
region.size = frame_size_bytes;
last_img_cl = CL_CHECK_ERR(clCreateSubBuffer(img_buffer_20hz_cl, CL_MEM_READ_WRITE, CL_BUFFER_CREATE_TYPE_REGION, ®ion, &err));
- transform_init(&transform, context, device_id);
loadyuv_init(&loadyuv, context, device_id, MODEL_WIDTH, MODEL_HEIGHT);
+ init_transform(device_id, context, MODEL_WIDTH, MODEL_HEIGHT);
}
-cl_mem* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3 &projection) {
- transform_queue(&this->transform, q,
- yuv_cl, frame_width, frame_height, frame_stride, frame_uv_offset,
- y_cl, u_cl, v_cl, MODEL_WIDTH, MODEL_HEIGHT, projection);
+cl_mem* DrivingModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3& projection) {
+ run_transform(yuv_cl, MODEL_WIDTH, MODEL_HEIGHT, frame_width, frame_height, frame_stride, frame_uv_offset, projection);
for (int i = 0; i < 4; i++) {
CL_CHECK(clEnqueueCopyBuffer(q, img_buffer_20hz_cl, img_buffer_20hz_cl, (i+1)*frame_size_bytes, i*frame_size_bytes, frame_size_bytes, 0, nullptr, nullptr));
@@ -41,19 +33,29 @@ cl_mem* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, in
return &input_frames_cl;
}
-uint8_t* ModelFrame::buffer_from_cl(cl_mem *in_frames) {
- CL_CHECK(clEnqueueReadBuffer(q, *in_frames, CL_TRUE, 0, MODEL_FRAME_SIZE * 2 * sizeof(uint8_t), &input_frames[0], 0, nullptr, nullptr));
- clFinish(q);
- return &input_frames[0];
-}
-
-ModelFrame::~ModelFrame() {
- transform_destroy(&transform);
+DrivingModelFrame::~DrivingModelFrame() {
+ deinit_transform();
loadyuv_destroy(&loadyuv);
CL_CHECK(clReleaseMemObject(img_buffer_20hz_cl));
CL_CHECK(clReleaseMemObject(last_img_cl));
- CL_CHECK(clReleaseMemObject(v_cl));
- CL_CHECK(clReleaseMemObject(u_cl));
- CL_CHECK(clReleaseMemObject(y_cl));
CL_CHECK(clReleaseCommandQueue(q));
-}
\ No newline at end of file
+}
+
+
+MonitoringModelFrame::MonitoringModelFrame(cl_device_id device_id, cl_context context) : ModelFrame(device_id, context) {
+ input_frames = std::make_unique(buf_size);
+ input_frame_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, buf_size, NULL, &err));
+
+ init_transform(device_id, context, MODEL_WIDTH, MODEL_HEIGHT);
+}
+
+cl_mem* MonitoringModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3& projection) {
+ run_transform(yuv_cl, MODEL_WIDTH, MODEL_HEIGHT, frame_width, frame_height, frame_stride, frame_uv_offset, projection);
+ clFinish(q);
+ return &y_cl;
+}
+
+MonitoringModelFrame::~MonitoringModelFrame() {
+ deinit_transform();
+ CL_CHECK(clReleaseCommandQueue(q));
+}
diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h
index 91cbbcddd3c942..14409943e43481 100644
--- a/selfdrive/modeld/models/commonmodel.h
+++ b/selfdrive/modeld/models/commonmodel.h
@@ -2,6 +2,7 @@
#include
#include
+#include
#include
@@ -18,10 +19,54 @@
class ModelFrame {
public:
- ModelFrame(cl_device_id device_id, cl_context context);
- ~ModelFrame();
- cl_mem* prepare(cl_mem yuv_cl, int width, int height, int frame_stride, int frame_uv_offset, const mat3& transform);
- uint8_t* buffer_from_cl(cl_mem *in_frames);
+ ModelFrame(cl_device_id device_id, cl_context context) {
+ q = CL_CHECK_ERR(clCreateCommandQueue(context, device_id, 0, &err));
+ }
+ virtual ~ModelFrame() {}
+ virtual cl_mem* prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3& projection) { return NULL; }
+ uint8_t* buffer_from_cl(cl_mem *in_frames, int buffer_size) {
+ CL_CHECK(clEnqueueReadBuffer(q, *in_frames, CL_TRUE, 0, buffer_size, input_frames.get(), 0, nullptr, nullptr));
+ clFinish(q);
+ return &input_frames[0];
+ }
+
+ int MODEL_WIDTH;
+ int MODEL_HEIGHT;
+ int MODEL_FRAME_SIZE;
+ int buf_size;
+
+protected:
+ cl_mem y_cl, u_cl, v_cl;
+ Transform transform;
+ cl_command_queue q;
+ std::unique_ptr input_frames;
+
+ void init_transform(cl_device_id device_id, cl_context context, int model_width, int model_height) {
+ y_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, model_width * model_height, NULL, &err));
+ u_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (model_width / 2) * (model_height / 2), NULL, &err));
+ v_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (model_width / 2) * (model_height / 2), NULL, &err));
+ transform_init(&transform, context, device_id);
+ }
+
+ void deinit_transform() {
+ transform_destroy(&transform);
+ CL_CHECK(clReleaseMemObject(v_cl));
+ CL_CHECK(clReleaseMemObject(u_cl));
+ CL_CHECK(clReleaseMemObject(y_cl));
+ }
+
+ void run_transform(cl_mem yuv_cl, int model_width, int model_height, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3& projection) {
+ transform_queue(&transform, q,
+ yuv_cl, frame_width, frame_height, frame_stride, frame_uv_offset,
+ y_cl, u_cl, v_cl, model_width, model_height, projection);
+ }
+};
+
+class DrivingModelFrame : public ModelFrame {
+public:
+ DrivingModelFrame(cl_device_id device_id, cl_context context);
+ ~DrivingModelFrame();
+ cl_mem* prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3& projection);
const int MODEL_WIDTH = 512;
const int MODEL_HEIGHT = 256;
@@ -30,10 +75,22 @@ class ModelFrame {
const size_t frame_size_bytes = MODEL_FRAME_SIZE * sizeof(uint8_t);
private:
- Transform transform;
LoadYUVState loadyuv;
- cl_command_queue q;
- cl_mem y_cl, u_cl, v_cl, img_buffer_20hz_cl, last_img_cl, input_frames_cl;
+ cl_mem img_buffer_20hz_cl, last_img_cl, input_frames_cl;
cl_buffer_region region;
- std::unique_ptr input_frames;
+};
+
+class MonitoringModelFrame : public ModelFrame {
+public:
+ MonitoringModelFrame(cl_device_id device_id, cl_context context);
+ ~MonitoringModelFrame();
+ cl_mem* prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3& projection);
+
+ const int MODEL_WIDTH = 1440;
+ const int MODEL_HEIGHT = 960;
+ const int MODEL_FRAME_SIZE = MODEL_WIDTH * MODEL_HEIGHT;
+ const int buf_size = MODEL_FRAME_SIZE;
+
+private:
+ cl_mem input_frame_cl;
};
diff --git a/selfdrive/modeld/models/commonmodel.pxd b/selfdrive/modeld/models/commonmodel.pxd
index 676defe15c3d1b..d2a8fb4dcd9fd6 100644
--- a/selfdrive/modeld/models/commonmodel.pxd
+++ b/selfdrive/modeld/models/commonmodel.pxd
@@ -14,6 +14,13 @@ cdef extern from "common/clutil.h":
cdef extern from "selfdrive/modeld/models/commonmodel.h":
cppclass ModelFrame:
int buf_size
- ModelFrame(cl_device_id, cl_context)
+ unsigned char * buffer_from_cl(cl_mem*, int);
cl_mem * prepare(cl_mem, int, int, int, int, mat3)
- unsigned char * buffer_from_cl(cl_mem*);
+
+ cppclass DrivingModelFrame:
+ int buf_size
+ DrivingModelFrame(cl_device_id, cl_context)
+
+ cppclass MonitoringModelFrame:
+ int buf_size
+ MonitoringModelFrame(cl_device_id, cl_context)
diff --git a/selfdrive/modeld/models/commonmodel_pyx.pyx b/selfdrive/modeld/models/commonmodel_pyx.pyx
index e6ae349e005836..b75408654428b1 100644
--- a/selfdrive/modeld/models/commonmodel_pyx.pyx
+++ b/selfdrive/modeld/models/commonmodel_pyx.pyx
@@ -9,7 +9,7 @@ from libc.stdint cimport uintptr_t
from msgq.visionipc.visionipc cimport cl_mem
from msgq.visionipc.visionipc_pyx cimport VisionBuf, CLContext as BaseCLContext
from .commonmodel cimport CL_DEVICE_TYPE_DEFAULT, cl_get_device_id, cl_create_context
-from .commonmodel cimport mat3, ModelFrame as cppModelFrame
+from .commonmodel cimport mat3, ModelFrame as cppModelFrame, DrivingModelFrame as cppDrivingModelFrame, MonitoringModelFrame as cppMonitoringModelFrame
cdef class CLContext(BaseCLContext):
@@ -31,11 +31,10 @@ cdef class CLMem:
def cl_from_visionbuf(VisionBuf buf):
return CLMem.create(&buf.buf.buf_cl)
+
cdef class ModelFrame:
cdef cppModelFrame * frame
-
- def __cinit__(self, CLContext context):
- self.frame = new cppModelFrame(context.device_id, context.context)
+ cdef int buf_size
def __dealloc__(self):
del self.frame
@@ -49,5 +48,23 @@ cdef class ModelFrame:
def buffer_from_cl(self, CLMem in_frames):
cdef unsigned char * data2
- data2 = self.frame.buffer_from_cl(in_frames.mem)
- return np.asarray( data2)
+ data2 = self.frame.buffer_from_cl(in_frames.mem, self.buf_size)
+ return np.asarray( data2)
+
+
+cdef class DrivingModelFrame(ModelFrame):
+ cdef cppDrivingModelFrame * _frame
+
+ def __cinit__(self, CLContext context):
+ self._frame = new cppDrivingModelFrame(context.device_id, context.context)
+ self.frame = (self._frame)
+ self.buf_size = self._frame.buf_size
+
+cdef class MonitoringModelFrame(ModelFrame):
+ cdef cppMonitoringModelFrame * _frame
+
+ def __cinit__(self, CLContext context):
+ self._frame = new cppMonitoringModelFrame(context.device_id, context.context)
+ self.frame = (self._frame)
+ self.buf_size = self._frame.buf_size
+
diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx
index a57e5dd2259b8d..777aa8aa7e4d35 100644
--- a/selfdrive/modeld/models/supercombo.onnx
+++ b/selfdrive/modeld/models/supercombo.onnx
@@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1
-oid sha256:9dc64f5d1e7d6b67f1d4659a3483f03b4324b4c7b969a5ba90c4e37e62bf6fce
-size 50320584
+oid sha256:72d3d6f8d3c98f5431ec86be77b6350d7d4f43c25075c0106f1d1e7ec7c77668
+size 49096168
diff --git a/selfdrive/modeld/parse_model_outputs.py b/selfdrive/modeld/parse_model_outputs.py
index 4367e9db8a2bcd..b699c5fd13593f 100644
--- a/selfdrive/modeld/parse_model_outputs.py
+++ b/selfdrive/modeld/parse_model_outputs.py
@@ -96,8 +96,6 @@ def parse_outputs(self, outs: dict[str, np.ndarray]) -> dict[str, np.ndarray]:
out_shape=(ModelConstants.LEAD_TRAJ_LEN,ModelConstants.LEAD_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,))
for k in ['lead_prob', 'lane_lines_prob', 'meta']:
self.parse_binary_crossentropy(k, outs)
self.parse_categorical_crossentropy('desire_state', outs, out_shape=(ModelConstants.DESIRE_PRED_WIDTH,))
diff --git a/selfdrive/modeld/runners/ort_helpers.py b/selfdrive/modeld/runners/ort_helpers.py
index ad6efed397670d..26afb035624a29 100644
--- a/selfdrive/modeld/runners/ort_helpers.py
+++ b/selfdrive/modeld/runners/ort_helpers.py
@@ -10,8 +10,7 @@ def attributeproto_fp16_to_fp32(attr):
attr.data_type = 1
attr.raw_data = float32_list.astype(np.float32).tobytes()
-def convert_fp16_to_fp32(onnx_path):
- model = onnx.load(onnx_path)
+def convert_fp16_to_fp32(model):
for i in model.graph.initializer:
if i.data_type == 10:
attributeproto_fp16_to_fp32(i)
@@ -33,6 +32,5 @@ def make_onnx_cpu_runner(model_path):
options.intra_op_num_threads = 4
options.execution_mode = ort.ExecutionMode.ORT_SEQUENTIAL
options.graph_optimization_level = ort.GraphOptimizationLevel.ORT_ENABLE_ALL
- model_data = convert_fp16_to_fp32(model_path)
+ model_data = convert_fp16_to_fp32(onnx.load(model_path))
return ort.InferenceSession(model_data, options, providers=['CPUExecutionProvider'])
-
diff --git a/selfdrive/pandad/panda_comms.cc b/selfdrive/pandad/panda_comms.cc
index 59908f0cde23d7..8a20f397d31d32 100644
--- a/selfdrive/pandad/panda_comms.cc
+++ b/selfdrive/pandad/panda_comms.cc
@@ -36,7 +36,7 @@ PandaUsbHandle::PandaUsbHandle(std::string serial) : PandaCommsHandle(serial) {
for (size_t i = 0; i < num_devices; ++i) {
libusb_device_descriptor desc;
libusb_get_device_descriptor(dev_list[i], &desc);
- if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) {
+ if (desc.idVendor == 0x3801 && desc.idProduct == 0xddcc) {
int ret = libusb_open(dev_list[i], &dev_handle);
if (dev_handle == NULL || ret < 0) { goto fail; }
@@ -110,7 +110,7 @@ std::vector PandaUsbHandle::list() {
libusb_device *device = dev_list[i];
libusb_device_descriptor desc;
libusb_get_device_descriptor(device, &desc);
- if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) {
+ if (desc.idVendor == 0x3801 && desc.idProduct == 0xddcc) {
libusb_device_handle *handle = NULL;
int ret = libusb_open(device, &handle);
if (ret < 0) { goto finish; }
diff --git a/selfdrive/pandad/pandad.cc b/selfdrive/pandad/pandad.cc
index dd970dd16ce09d..bf2a465d78127a 100644
--- a/selfdrive/pandad/pandad.cc
+++ b/selfdrive/pandad/pandad.cc
@@ -416,6 +416,7 @@ void process_peripheral_state(Panda *panda, PubMaster *pm, bool no_fan_control)
if (ir_pwr != prev_ir_pwr || sm.frame % 100 == 0 || ir_pwr >= 50.0) {
panda->set_ir_pwr(ir_pwr);
+ Hardware::set_ir_power(ir_pwr);
prev_ir_pwr = ir_pwr;
}
}
diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py
index 5376f91aee427f..d531b3b7edc807 100644
--- a/selfdrive/test/process_replay/migration.py
+++ b/selfdrive/test/process_replay/migration.py
@@ -107,7 +107,7 @@ def migrate_longitudinalPlan(msgs):
if msg.which() != 'longitudinalPlan':
continue
new_msg = msg.as_builder()
- new_msg.longitudinalPlan.aTarget, new_msg.longitudinalPlan.shouldStop = get_accel_from_plan(CP, msg.longitudinalPlan.speeds, msg.longitudinalPlan.accels)
+ new_msg.longitudinalPlan.aTarget, new_msg.longitudinalPlan.shouldStop = get_accel_from_plan(msg.longitudinalPlan.speeds, msg.longitudinalPlan.accels)
ops.append((index, new_msg.as_reader()))
return ops, [], []
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index d4892b51f25e2d..3120a4de3a144b 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-7a1b6253e715cec2a254c3e7b6839d6f2bd06fb1
+1f37082d56a60f20ba9e36b702a23cbdde3caca7
diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py
index c3c2461790c3ad..25aaa95f0f18fd 100644
--- a/selfdrive/test/test_onroad.py
+++ b/selfdrive/test/test_onroad.py
@@ -377,7 +377,7 @@ def test_model_execution_timings(self):
]
for (s, instant_max, avg_max) in cfgs:
ts = [getattr(m, s).modelExecutionTime for m in self.msgs[s]]
- # TODO some tinygrad init happens in first iteration
+ # TODO some init can happen in first iteration
ts = ts[1:]
assert max(ts) < instant_max, f"high '{s}' execution time: {max(ts)}"
assert np.mean(ts) < avg_max, f"high avg '{s}' execution time: {np.mean(ts)}"
diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript
index 22bf4760bfbdc8..c851d7a969332e 100644
--- a/selfdrive/ui/SConscript
+++ b/selfdrive/ui/SConscript
@@ -67,14 +67,13 @@ 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)
-if GetOption('extras') and arch != "Darwin":
+if GetOption('extras'):
qt_env.SharedLibrary("qt/python_helpers", ["qt/qt_window.cc"], LIBS=qt_libs)
# spinner and text window
qt_env.Program("_text", ["qt/text.cc"], LIBS=qt_libs)
qt_env.Program("_spinner", ["qt/spinner.cc"], LIBS=qt_libs)
-
# setup and factory resetter
qt_env.Program("qt/setup/reset", ["qt/setup/reset.cc"], LIBS=qt_libs)
qt_env.Program("qt/setup/setup", ["qt/setup/setup.cc", asset_obj],
@@ -83,29 +82,30 @@ if GetOption('extras') and arch != "Darwin":
# build updater UI
qt_env.Program("qt/setup/updater", ["qt/setup/updater.cc", asset_obj], LIBS=qt_libs)
- # build installers
- senv = qt_env.Clone()
- senv['LINKFLAGS'].append('-Wl,-strip-debug')
-
- release = "release3"
- installers = [
- ("openpilot", release),
- ("openpilot_test", f"{release}-staging"),
- ("openpilot_nightly", "nightly"),
- ("openpilot_internal", "nightly-dev"),
- ]
-
- cont = senv.Command(f"installer/continue_openpilot.o", f"installer/continue_openpilot.sh",
- "ld -r -b binary -o $TARGET $SOURCE")
- for name, branch in installers:
- d = {'BRANCH': f"'\"{branch}\"'"}
- if "internal" in name:
- d['INTERNAL'] = "1"
-
- obj = senv.Object(f"installer/installers/installer_{name}.o", ["installer/installer.cc"], CPPDEFINES=d)
- f = senv.Program(f"installer/installers/installer_{name}", [obj, cont], LIBS=qt_libs)
- # keep installers small
- assert f[0].get_size() < 370*1e3
+ if arch != "Darwin":
+ # build installers
+ senv = qt_env.Clone()
+ senv['LINKFLAGS'].append('-Wl,-strip-debug')
+
+ release = "release3"
+ installers = [
+ ("openpilot", release),
+ ("openpilot_test", f"{release}-staging"),
+ ("openpilot_nightly", "nightly"),
+ ("openpilot_internal", "nightly-dev"),
+ ]
+
+ cont = senv.Command(f"installer/continue_openpilot.o", f"installer/continue_openpilot.sh",
+ "ld -r -b binary -o $TARGET $SOURCE")
+ for name, branch in installers:
+ d = {'BRANCH': f"'\"{branch}\"'"}
+ if "internal" in name:
+ d['INTERNAL'] = "1"
+
+ obj = senv.Object(f"installer/installers/installer_{name}.o", ["installer/installer.cc"], CPPDEFINES=d)
+ f = senv.Program(f"installer/installers/installer_{name}", [obj, cont], LIBS=qt_libs)
+ # keep installers small
+ assert f[0].get_size() < 370*1e3
# build watch3
if arch in ['x86_64', 'aarch64', 'Darwin'] or GetOption('extras'):
diff --git a/selfdrive/ui/qt/network/wifi_manager.cc b/selfdrive/ui/qt/network/wifi_manager.cc
index fd9ee17078c86c..17172106345798 100644
--- a/selfdrive/ui/qt/network/wifi_manager.cc
+++ b/selfdrive/ui/qt/network/wifi_manager.cc
@@ -203,7 +203,7 @@ void WifiManager::connect(const Network &n, const bool is_hidden, const QString
connection["ipv4"]["dns-priority"] = 600;
connection["ipv6"]["method"] = "ignore";
- call(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "AddConnection", QVariant::fromValue(connection));
+ asyncCall(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "AddConnection", QVariant::fromValue(connection));
}
void WifiManager::deactivateConnectionBySsid(const QString &ssid) {
@@ -330,6 +330,10 @@ void WifiManager::initConnections() {
lteConnectionPath = path;
}
}
+
+ if (!isKnownConnection(tethering_ssid)) {
+ addTetheringConnection();
+ }
}
std::optional WifiManager::activateWifiConnection(const QString &ssid) {
@@ -399,9 +403,13 @@ void WifiManager::updateGsmSettings(bool roaming, QString apn, bool metered) {
}
if (changes) {
- call(lteConnectionPath.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "UpdateUnsaved", QVariant::fromValue(settings)); // update is temporary
- deactivateConnection(lteConnectionPath);
- activateModemConnection(lteConnectionPath);
+ QDBusPendingCall pending_call = asyncCall(lteConnectionPath.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "UpdateUnsaved", QVariant::fromValue(settings)); // update is temporary
+ QDBusPendingCallWatcher *watcher = new QDBusPendingCallWatcher(pending_call);
+ QObject::connect(watcher, &QDBusPendingCallWatcher::finished, this, [this, watcher]() {
+ deactivateConnection(lteConnectionPath);
+ activateModemConnection(lteConnectionPath);
+ watcher->deleteLater();
+ });
}
}
}
@@ -434,10 +442,7 @@ void WifiManager::addTetheringConnection() {
connection["ipv4"]["route-metric"] = 1100;
connection["ipv6"]["method"] = "ignore";
- auto path = call(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "AddConnection", QVariant::fromValue(connection));
- if (!path.path().isEmpty()) {
- knownConnections[path] = tethering_ssid;
- }
+ asyncCall(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "AddConnection", QVariant::fromValue(connection));
}
void WifiManager::tetheringActivated(QDBusPendingCallWatcher *call) {
@@ -453,10 +458,6 @@ void WifiManager::tetheringActivated(QDBusPendingCallWatcher *call) {
void WifiManager::setTetheringEnabled(bool enabled) {
if (enabled) {
- if (!isKnownConnection(tethering_ssid)) {
- addTetheringConnection();
- }
-
auto pending_call = activateWifiConnection(tethering_ssid);
if (pending_call) {
@@ -478,9 +479,6 @@ bool WifiManager::isTetheringEnabled() {
}
QString WifiManager::getTetheringPassword() {
- if (!isKnownConnection(tethering_ssid)) {
- addTetheringConnection();
- }
const QDBusObjectPath &path = getConnectionPath(tethering_ssid);
if (!path.path().isEmpty()) {
QDBusReply> response = call(path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "GetSecrets", "802-11-wireless-security");
diff --git a/system/athena/athenad.py b/system/athena/athenad.py
index 2d9ad110aadd57..2f455981cce3b2 100755
--- a/system/athena/athenad.py
+++ b/system/athena/athenad.py
@@ -100,9 +100,9 @@ def from_dict(cls, d: dict) -> UploadItem:
upload_queue: Queue[UploadItem] = queue.Queue()
low_priority_send_queue: Queue[str] = queue.Queue()
log_recv_queue: Queue[str] = queue.Queue()
+cancelled_uploads: set[str] = set()
cur_upload_items: dict[int, UploadItem | None] = {}
-cur_upload_items_lock = threading.Lock()
def strip_zst_extension(fn: str) -> str:
@@ -130,9 +130,8 @@ def initialize(upload_queue: Queue[UploadItem]) -> None:
@staticmethod
def cache(upload_queue: Queue[UploadItem]) -> None:
try:
- with upload_queue.mutex:
- items = [asdict(item) for item in upload_queue.queue]
-
+ queue: list[UploadItem | None] = list(upload_queue.queue)
+ items = [asdict(i) for i in queue if i is not None and (i.id not in cancelled_uploads)]
Params().put("AthenadUploadQueue", json.dumps(items))
except Exception:
cloudlog.exception("athena.UploadQueueCache.cache.exception")
@@ -199,13 +198,11 @@ def retry_upload(tid: int, end_event: threading.Event, increase_count: bool = Tr
progress=0,
current=False
)
-
- with cur_upload_items_lock:
- upload_queue.put_nowait(item)
- cur_upload_items[tid] = None
-
+ upload_queue.put_nowait(item)
UploadQueueCache.cache(upload_queue)
+ cur_upload_items[tid] = None
+
for _ in range(RETRY_DELAY):
time.sleep(1)
if end_event.is_set():
@@ -224,8 +221,7 @@ def cb(sm, item, tid, end_event: threading.Event, sz: int, cur: int) -> None:
if end_event.is_set():
raise AbortTransferException
- with cur_upload_items_lock:
- cur_upload_items[tid] = replace(item, progress=cur / sz if sz else 1)
+ cur_upload_items[tid] = replace(item, progress=cur / sz if sz else 1)
def upload_handler(end_event: threading.Event) -> None:
@@ -233,10 +229,14 @@ def upload_handler(end_event: threading.Event) -> None:
tid = threading.get_ident()
while not end_event.is_set():
+ cur_upload_items[tid] = None
+
try:
- with cur_upload_items_lock:
- cur_upload_items[tid] = None
- cur_upload_items[tid] = item = replace(upload_queue.get(timeout=1), current=True)
+ cur_upload_items[tid] = item = replace(upload_queue.get(timeout=1), current=True)
+
+ if item.id in cancelled_uploads:
+ cancelled_uploads.remove(item.id)
+ continue
# Remove item if too old
age = datetime.now() - datetime.fromtimestamp(item.created_at / 1000)
@@ -415,10 +415,8 @@ def uploadFilesToUrls(files_data: list[UploadFileDict]) -> UploadFilesToUrlRespo
@dispatcher.add_method
def listUploadQueue() -> list[UploadItemDict]:
- with cur_upload_items_lock, upload_queue.mutex:
- items = list(upload_queue.queue) + [item for item in cur_upload_items.values() if item is not None]
-
- return [asdict(item) for item in items]
+ items = list(upload_queue.queue) + list(cur_upload_items.values())
+ return [asdict(i) for i in items if (i is not None) and (i.id not in cancelled_uploads)]
@dispatcher.add_method
@@ -426,14 +424,13 @@ def cancelUpload(upload_id: str | list[str]) -> dict[str, int | str]:
if not isinstance(upload_id, list):
upload_id = [upload_id]
- with upload_queue.mutex:
- remaining_items = [item for item in upload_queue.queue if item.id not in upload_id]
- if len(remaining_items) == len(upload_queue.queue):
- return {"success": 0, "error": "not found"}
+ uploading_ids = {item.id for item in list(upload_queue.queue)}
+ cancelled_ids = uploading_ids.intersection(upload_id)
+ if len(cancelled_ids) == 0:
+ return {"success": 0, "error": "not found"}
- upload_queue.queue.clear()
- upload_queue.queue.extend(remaining_items)
- return {"success": 1}
+ cancelled_uploads.update(cancelled_ids)
+ return {"success": 1}
@dispatcher.add_method
def setRouteViewed(route: str) -> dict[str, int | str]:
diff --git a/system/athena/tests/test_athenad.py b/system/athena/tests/test_athenad.py
index cee37064b9cfad..a6bfc689306533 100644
--- a/system/athena/tests/test_athenad.py
+++ b/system/athena/tests/test_athenad.py
@@ -78,6 +78,7 @@ def setup_method(self):
athenad.upload_queue = queue.Queue()
athenad.cur_upload_items.clear()
+ athenad.cancelled_uploads.clear()
for i in os.listdir(Paths.log_root()):
p = os.path.join(Paths.log_root(), i)
@@ -281,10 +282,13 @@ def test_cancel_upload(self):
athenad.upload_queue.put_nowait(item)
dispatcher["cancelUpload"](item.id)
+ assert item.id in athenad.cancelled_uploads
+
self._wait_for_upload()
time.sleep(0.1)
assert athenad.upload_queue.qsize() == 0
+ assert len(athenad.cancelled_uploads) == 0
@with_upload_handler
def test_cancel_expiry(self):
@@ -327,7 +331,7 @@ def test_list_upload_queue(self):
assert items[0] == asdict(item)
assert not items[0]['current']
- dispatcher["cancelUpload"](item.id)
+ athenad.cancelled_uploads.add(item.id)
items = dispatcher["listUploadQueue"]()
assert len(items) == 0
@@ -339,7 +343,7 @@ def test_upload_queue_persistence(self):
athenad.upload_queue.put_nowait(item2)
# Ensure canceled items are not persisted
- dispatcher["cancelUpload"](item2.id)
+ athenad.cancelled_uploads.add(item2.id)
# serialize item
athenad.UploadQueueCache.cache(athenad.upload_queue)
diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc
index b0193cf5dfcf67..366feae0b2e339 100644
--- a/system/camerad/cameras/camera_common.cc
+++ b/system/camerad/cameras/camera_common.cc
@@ -89,12 +89,14 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, SpectraCamera *
vipc_server->create_buffers_with_sizes(stream_type, VIPC_BUFFER_COUNT, out_img_width, out_img_height, nv12_size, cam->stride, cam->uv_offset);
LOGD("created %d YUV vipc buffers with size %dx%d", VIPC_BUFFER_COUNT, cam->stride, cam->y_height);
- imgproc = new ImgProc(device_id, context, this, sensor, cam->cc.camera_num, cam->stride, cam->uv_offset);
+ if (is_raw) imgproc = new ImgProc(device_id, context, this, sensor, cam->cc.camera_num, cam->stride, cam->uv_offset);
}
CameraBuf::~CameraBuf() {
- for (int i = 0; i < frame_buf_count; i++) {
- camera_bufs_raw[i].free();
+ if (camera_bufs_raw != nullptr) {
+ for (int i = 0; i < frame_buf_count; i++) {
+ camera_bufs_raw[i].free();
+ }
}
if (imgproc) delete imgproc;
}
diff --git a/system/camerad/cameras/process_raw.cl b/system/camerad/cameras/process_raw.cl
index 6f6612fab0328a..ff6060d855d07c 100644
--- a/system/camerad/cameras/process_raw.cl
+++ b/system/camerad/cameras/process_raw.cl
@@ -19,6 +19,17 @@
#endif
float get_vignetting_s(float r) {
+#if defined(VIGNETTE_PROFILE_4DT6MM)
+ if (r < 100000) {
+ return 1.0f + 0.0000013f*r;
+ } else if (r < 250000) {
+ return 1.02f + 0.0000011f*r;
+ } else if (r < 400000) {
+ return 0.92f + 0.0000015f*r;
+ } else {
+ return 0.44f + 0.0000027f*r;
+ }
+#elif defined(VIGNETTE_PROFILE_8DT0MM)
if (r < 62500) {
return (1.0f + 0.0000008f*r);
} else if (r < 490000) {
@@ -28,6 +39,9 @@ float get_vignetting_s(float r) {
} else {
return (0.53503625f + 0.0000000000022f*r*r);
}
+#else
+ return 1.0f;
+#endif
}
int4 parse_12bit(uchar8 pvs) {
@@ -65,7 +79,7 @@ __kernel void process_raw(const __global uchar * in, __global uchar * out, int e
#if VIGNETTING
int gx = (gid_x*2 - RGB_WIDTH/2);
int gy = (gid_y*2 - RGB_HEIGHT/2);
- const float vignette_factor = get_vignetting_s((gx*gx + gy*gy) / VIGNETTE_RSZ);
+ const float vignette_factor = get_vignetting_s(gx*gx + gy*gy);
#else
const float vignette_factor = 1.0;
#endif
diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc
index 83b331cf4a8aac..3f416839012fc7 100644
--- a/system/camerad/cameras/spectra.cc
+++ b/system/camerad/cameras/spectra.cc
@@ -196,9 +196,9 @@ void SpectraMaster::init() {
assert(isp_fd >= 0);
LOGD("opened isp");
- //icp_fd = open_v4l_by_name_and_index("cam-icp");
- //assert(icp_fd >= 0);
- //LOGD("opened icp");
+ icp_fd = open_v4l_by_name_and_index("cam-icp");
+ assert(icp_fd >= 0);
+ LOGD("opened icp");
// query ISP for MMU handles
LOG("-- Query for MMU handles");
@@ -215,7 +215,6 @@ void SpectraMaster::init() {
cdm_iommu = isp_query_cap_cmd.cdm_iommu.non_secure;
// query ICP for MMU handles
- /*
struct cam_icp_query_cap_cmd icp_query_cap_cmd = {0};
query_cap_cmd.caps_handle = (uint64_t)&icp_query_cap_cmd;
query_cap_cmd.size = sizeof(icp_query_cap_cmd);
@@ -223,7 +222,6 @@ void SpectraMaster::init() {
assert(ret == 0);
LOGD("using ICP MMU handle: %x", icp_query_cap_cmd.dev_iommu_handle.non_secure);
icp_device_iommu = icp_query_cap_cmd.dev_iommu_handle.non_secure;
- */
// subscribe
LOG("-- Subscribing");
@@ -712,13 +710,13 @@ void SpectraCamera::enqueue_buffer(int i, bool dp) {
}
sync_objs[i] = sync_create.sync_obj;
- /*
- ret = do_cam_control(m->cam_sync_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create));
- if (ret != 0) {
- LOGE("failed to create fence: %d %d", ret, sync_create.sync_obj);
+ if (icp_dev_handle > 0) {
+ ret = do_cam_control(m->cam_sync_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create));
+ if (ret != 0) {
+ LOGE("failed to create fence: %d %d", ret, sync_create.sync_obj);
+ }
+ sync_objs_bps_out[i] = sync_create.sync_obj;
}
- sync_objs_bps_out[i] = sync_create.sync_obj;
- */
// schedule request with camera request manager
struct cam_req_mgr_sched_request req_mgr_sched_request = {0};
@@ -746,8 +744,10 @@ void SpectraCamera::camera_map_bufs() {
mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE;
mem_mgr_map_cmd.mmu_hdls[0] = m->device_iommu;
mem_mgr_map_cmd.num_hdl = 1;
- //mem_mgr_map_cmd.mmu_hdls[1] = m->icp_device_iommu;
- //mem_mgr_map_cmd.num_hdl = 2;
+ if (icp_dev_handle > 0) {
+ mem_mgr_map_cmd.num_hdl = 2;
+ mem_mgr_map_cmd.mmu_hdls[1] = m->icp_device_iommu;
+ }
if (is_raw) {
// RAW bayer images
@@ -899,8 +899,6 @@ void SpectraCamera::configISP() {
}
void SpectraCamera::configICP() {
- if (!enabled) return;
-
/*
Configures both the ICP and BPS.
*/
@@ -1048,6 +1046,10 @@ void SpectraCamera::camera_close() {
// release devices
LOGD("-- Release devices");
+ if (icp_dev_handle > 0) {
+ ret = device_control(m->icp_fd, CAM_RELEASE_DEV, session_handle, icp_dev_handle);
+ LOGD("release icp: %d", ret);
+ }
ret = device_control(m->isp_fd, CAM_RELEASE_DEV, session_handle, isp_dev_handle);
LOGD("release isp: %d", ret);
ret = device_control(csiphy_fd, CAM_RELEASE_DEV, session_handle, csiphy_dev_handle);
diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h
index 476722b664a8fb..689fcb9cc38f2b 100644
--- a/system/camerad/cameras/spectra.h
+++ b/system/camerad/cameras/spectra.h
@@ -22,8 +22,9 @@ const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py
// CSLDeviceType/CSLPacketOpcodesIFE from camx
// cam_packet_header.op_code = (device << 24) | (opcode);
-#define CSLDeviceTypeImageSensor (0x1 << 24)
-#define CSLDeviceTypeIFE (0xF << 24)
+#define CSLDeviceTypeImageSensor (0x01 << 24)
+#define CSLDeviceTypeIFE (0x0F << 24)
+#define CSLDeviceTypeBPS (0x10 << 24)
#define OpcodesIFEInitialConfig 0x0
#define OpcodesIFEUpdate 0x1
diff --git a/system/camerad/sensors/ar0231_cl.h b/system/camerad/sensors/ar0231_cl.h
index 8e96bbce5b6aad..c79242543b27f2 100644
--- a/system/camerad/sensors/ar0231_cl.h
+++ b/system/camerad/sensors/ar0231_cl.h
@@ -1,9 +1,10 @@
#if SENSOR_ID == 1
+#define VIGNETTE_PROFILE_8DT0MM
+
#define BIT_DEPTH 12
#define PV_MAX 4096
#define BLACK_LVL 168
-#define VIGNETTE_RSZ 1.0f
float4 normalize_pv(int4 parsed, float vignette_factor) {
float4 pv = (convert_float4(parsed) - BLACK_LVL) / (PV_MAX - BLACK_LVL);
@@ -30,4 +31,4 @@ float3 apply_gamma(float3 rgb, int expo_time) {
((rk * (rgb-mp) * (gamma_k*mp+gamma_b) * (1+1/(rk*mp)) / (1-rk*(rgb-mp))) + gamma_k*mp + gamma_b);
}
-#endif
\ No newline at end of file
+#endif
diff --git a/system/camerad/sensors/os04c10_cl.h b/system/camerad/sensors/os04c10_cl.h
index 3da3fab8dfe146..3b5cf88839dc51 100644
--- a/system/camerad/sensors/os04c10_cl.h
+++ b/system/camerad/sensors/os04c10_cl.h
@@ -1,13 +1,13 @@
#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
-#define VIGNETTE_RSZ 2.2545f
float combine_dual_pvs(float lv, float sv, int expo_time) {
float svc = fmax(sv * expo_time, (float)(64 * (PV_MAX10 - BLACK_LVL)));
diff --git a/system/camerad/sensors/ox03c10_cl.h b/system/camerad/sensors/ox03c10_cl.h
index f1fbd16ccbd008..c8cec7cf8a1477 100644
--- a/system/camerad/sensors/ox03c10_cl.h
+++ b/system/camerad/sensors/ox03c10_cl.h
@@ -1,8 +1,9 @@
#if SENSOR_ID == 2
+#define VIGNETTE_PROFILE_8DT0MM
+
#define BIT_DEPTH 12
#define BLACK_LVL 64
-#define VIGNETTE_RSZ 1.0f
float ox_lut_func(int x) {
if (x < 512) {
diff --git a/system/camerad/test/debug.sh b/system/camerad/test/debug.sh
index 44ff0ffa89f984..8bd8d9d4f05c56 100755
--- a/system/camerad/test/debug.sh
+++ b/system/camerad/test/debug.sh
@@ -10,7 +10,7 @@ echo 0 | sudo tee /sys/module/cam_debug_util/parameters/debug_mdl
sudo dmesg -C
scons -u -j8 --minimal .
export DEBUG_FRAMES=1
-#export DISABLE_ROAD=1 DISABLE_WIDE_ROAD=1
-export DISABLE_DRIVER=1
-#export LOGPRINT=debug
+export DISABLE_ROAD=1 DISABLE_WIDE_ROAD=1
+#export DISABLE_DRIVER=1
+export LOGPRINT=debug
./camerad
diff --git a/system/camerad/test/icp_debug.sh b/system/camerad/test/icp_debug.sh
new file mode 100755
index 00000000000000..ebeef9bf8f2d7c
--- /dev/null
+++ b/system/camerad/test/icp_debug.sh
@@ -0,0 +1,13 @@
+#!/usr/bin/env bash
+set -e
+
+cd /sys/kernel/debug/tracing
+echo "" > trace
+echo 1 > tracing_on
+#echo Y > /sys/kernel/debug/camera_icp/a5_debug_q
+echo 0x1 > /sys/kernel/debug/camera_icp/a5_debug_type
+echo 1 > /sys/kernel/debug/tracing/events/camera/enable
+echo 0xffffffff > /sys/kernel/debug/camera_icp/a5_debug_lvl
+echo 1 > /sys/kernel/debug/tracing/events/camera/cam_icp_fw_dbg/enable
+
+cat /sys/kernel/debug/tracing/trace_pipe
diff --git a/system/hardware/base.h b/system/hardware/base.h
index ca24633a182a91..732f0f99e0acd0 100644
--- a/system/hardware/base.h
+++ b/system/hardware/base.h
@@ -28,6 +28,7 @@ class HardwareNone {
static void reboot() {}
static void poweroff() {}
static void set_brightness(int percent) {}
+ static void set_ir_power(int percentage) {}
static void set_display_power(bool on) {}
static bool get_ssh_enabled() { return false; }
diff --git a/system/hardware/hardwared.py b/system/hardware/hardwared.py
index 48c916b146a078..b6de91818e922e 100755
--- a/system/hardware/hardwared.py
+++ b/system/hardware/hardwared.py
@@ -1,7 +1,9 @@
#!/usr/bin/env python3
+import fcntl
import os
import json
import queue
+import struct
import threading
import time
from collections import OrderedDict, namedtuple
@@ -59,6 +61,40 @@ def set_offroad_alert_if_changed(offroad_alert: str, show_alert: bool, extra_tex
prev_offroad_states[offroad_alert] = (show_alert, extra_text)
set_offroad_alert(offroad_alert, show_alert, extra_text)
+def touch_thread(end_event):
+ count = 0
+
+ pm = messaging.PubMaster(["touch"])
+
+ event_format = "llHHi"
+ event_size = struct.calcsize(event_format)
+ event_frame = []
+
+ with open("/dev/input/by-path/platform-894000.i2c-event", "rb") as event_file:
+ fcntl.fcntl(event_file, fcntl.F_SETFL, os.O_NONBLOCK)
+ while not end_event.is_set():
+ if (count % int(1. / DT_HW)) == 0:
+ event = event_file.read(event_size)
+ if event:
+ (sec, usec, etype, code, value) = struct.unpack(event_format, event)
+ if etype != 0 or code != 0 or value != 0:
+ touch = log.Touch.new_message()
+ touch.sec = sec
+ touch.usec = usec
+ touch.type = etype
+ touch.code = code
+ touch.value = value
+ event_frame.append(touch)
+ else: # end of frame, push new log
+ msg = messaging.new_message('touch', len(event_frame), valid=True)
+ msg.touch = event_frame
+ pm.send('touch', msg)
+ event_frame = []
+ continue
+
+ count += 1
+ time.sleep(DT_HW)
+
def hw_state_thread(end_event, hw_queue):
"""Handles non critical hardware state, and sends over queue"""
@@ -420,6 +456,9 @@ def main():
threading.Thread(target=hardware_thread, args=(end_event, hw_queue)),
]
+ if TICI:
+ threads.append(threading.Thread(target=touch_thread, args=(end_event,)))
+
for t in threads:
t.start()
diff --git a/system/hardware/tici/agnos.json b/system/hardware/tici/agnos.json
index 430f86bfedf51d..d5002159d730ec 100644
--- a/system/hardware/tici/agnos.json
+++ b/system/hardware/tici/agnos.json
@@ -1,19 +1,19 @@
[
{
"name": "boot",
- "url": "https://commadist.azureedge.net/agnosupdate/boot-45e107ad65e6cc9ee95dc139f9ed11d56ef7f5f0657f579498a4a48f0a2f7ea3.img.xz",
- "hash": "45e107ad65e6cc9ee95dc139f9ed11d56ef7f5f0657f579498a4a48f0a2f7ea3",
- "hash_raw": "45e107ad65e6cc9ee95dc139f9ed11d56ef7f5f0657f579498a4a48f0a2f7ea3",
- "size": 16418816,
+ "url": "https://commadist.azureedge.net/agnosupdate/boot-62d10fad3f057dad70a803c74b584296120ed4216a6b67c83f052f0186f73e50.img.xz",
+ "hash": "62d10fad3f057dad70a803c74b584296120ed4216a6b67c83f052f0186f73e50",
+ "hash_raw": "62d10fad3f057dad70a803c74b584296120ed4216a6b67c83f052f0186f73e50",
+ "size": 16422912,
"sparse": false,
"full_check": true,
"has_ab": true
},
{
"name": "system",
- "url": "https://commadist.azureedge.net/agnosupdate/system-c0d738052c77f97b10bcea111479ddabd3fde2653d50533dd0fa2b17bb7881e9.img.xz",
- "hash": "c0d738052c77f97b10bcea111479ddabd3fde2653d50533dd0fa2b17bb7881e9",
- "hash_raw": "c0d738052c77f97b10bcea111479ddabd3fde2653d50533dd0fa2b17bb7881e9",
+ "url": "https://commadist.azureedge.net/agnosupdate/system-70c493b8407ba3e315807042448cd957bcf53e81014440195e3dfd25fd60f53c.img.xz",
+ "hash": "70c493b8407ba3e315807042448cd957bcf53e81014440195e3dfd25fd60f53c",
+ "hash_raw": "70c493b8407ba3e315807042448cd957bcf53e81014440195e3dfd25fd60f53c",
"size": 4404019200,
"sparse": false,
"full_check": false,
@@ -21,9 +21,9 @@
},
{
"name": "xbl",
- "url": "https://commadist.azureedge.net/agnosupdate/xbl-bece486a68d9470c165e87955e451339cd86ada6ca2c7fde13c49144624ce030.img.xz",
- "hash": "bece486a68d9470c165e87955e451339cd86ada6ca2c7fde13c49144624ce030",
- "hash_raw": "bece486a68d9470c165e87955e451339cd86ada6ca2c7fde13c49144624ce030",
+ "url": "https://commadist.azureedge.net/agnosupdate/xbl-468f1ad6ab55e198647ff9191f91bd2918db9c0a3e27bae5673b4c5575c1254c.img.xz",
+ "hash": "468f1ad6ab55e198647ff9191f91bd2918db9c0a3e27bae5673b4c5575c1254c",
+ "hash_raw": "468f1ad6ab55e198647ff9191f91bd2918db9c0a3e27bae5673b4c5575c1254c",
"size": 3282256,
"sparse": false,
"full_check": true,
@@ -41,9 +41,9 @@
},
{
"name": "xbl_config",
- "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-868b6f9aa98871dc50ef191a2d8f432578d1eca84f87d9185f8fb61242c3b66f.img.xz",
- "hash": "868b6f9aa98871dc50ef191a2d8f432578d1eca84f87d9185f8fb61242c3b66f",
- "hash_raw": "868b6f9aa98871dc50ef191a2d8f432578d1eca84f87d9185f8fb61242c3b66f",
+ "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-92b675dc2862ed15c732d91d9eb307d7e852e349217db8bee8f8829db543686b.img.xz",
+ "hash": "92b675dc2862ed15c732d91d9eb307d7e852e349217db8bee8f8829db543686b",
+ "hash_raw": "92b675dc2862ed15c732d91d9eb307d7e852e349217db8bee8f8829db543686b",
"size": 98124,
"sparse": false,
"full_check": true,
@@ -51,9 +51,9 @@
},
{
"name": "devcfg",
- "url": "https://commadist.azureedge.net/agnosupdate/devcfg-c27dc9ab628015ef265e1204ca736b2838ec179e9ecdd79e2ddb59d984b78df1.img.xz",
- "hash": "c27dc9ab628015ef265e1204ca736b2838ec179e9ecdd79e2ddb59d984b78df1",
- "hash_raw": "c27dc9ab628015ef265e1204ca736b2838ec179e9ecdd79e2ddb59d984b78df1",
+ "url": "https://commadist.azureedge.net/agnosupdate/devcfg-225b24ea7b1d2fee7f7d2da21386920ddacac2e33e9e938168436292f4eae180.img.xz",
+ "hash": "225b24ea7b1d2fee7f7d2da21386920ddacac2e33e9e938168436292f4eae180",
+ "hash_raw": "225b24ea7b1d2fee7f7d2da21386920ddacac2e33e9e938168436292f4eae180",
"size": 40336,
"sparse": false,
"full_check": true,
@@ -61,9 +61,9 @@
},
{
"name": "aop",
- "url": "https://commadist.azureedge.net/agnosupdate/aop-588bb60f0f8194d2df12f041e320a6dfeafae7209b312be3e4f6fe0744192837.img.xz",
- "hash": "588bb60f0f8194d2df12f041e320a6dfeafae7209b312be3e4f6fe0744192837",
- "hash_raw": "588bb60f0f8194d2df12f041e320a6dfeafae7209b312be3e4f6fe0744192837",
+ "url": "https://commadist.azureedge.net/agnosupdate/aop-f0fcf7611d0890a72984f15a516dd37fa532dfcb70d428a8406838cf74ce23d5.img.xz",
+ "hash": "f0fcf7611d0890a72984f15a516dd37fa532dfcb70d428a8406838cf74ce23d5",
+ "hash_raw": "f0fcf7611d0890a72984f15a516dd37fa532dfcb70d428a8406838cf74ce23d5",
"size": 184364,
"sparse": false,
"full_check": true,
diff --git a/system/hardware/tici/hardware.h b/system/hardware/tici/hardware.h
index f1d1f1e717ed88..da89bb9002a052 100644
--- a/system/hardware/tici/hardware.h
+++ b/system/hardware/tici/hardware.h
@@ -4,6 +4,7 @@
#include
#include