6 Commits

Author SHA1 Message Date
brianhansonxyz cea422b075 locationd: ignore GPS as Kalman input; expand park-cached-output to onroad consumers
locationd: ignore gpsLocation observations entirely (clearpilot_disable_gps
const at the top of handle_gps; falls through to determine_gps_mode's
no-GPS path). gpsd.py keeps publishing real GPS for UI / dashcam / clock
/ night-mode — only locationd ignores it. The previous gpsd.py path was
hard-coding vNED=[0,0,0] while the car was moving 28 m/s, feeding the
Kalman contradictory GPS-vs-IMU velocity observations that propagated into
latcontrol_torque through liveLocationKalman.angularVelocityCalibrated and
caused a real "drift right on straight roads" symptom.

controlsd: short-circuit state_control() while parked. Skips LaC/LoC PID,
MPC, model_v2 reads, lane-change logic — all wasted work when the car
isn't moving. Returns the same enabled=False/latActive=False/longActive=False
CC the original code would have produced, so publish_logs runs unchanged
and card.controls_update keeps the sendcan / tester-present heartbeat
flowing at 100Hz. controlsd CPU dropped from ~59% to ~3% in park.

controlsd: also wire self.FPCC.noLatLaneChange = True/False in the
existing lane-change suppression branch. The Hyundai carcontroller already
reads off frogpilot_variables.no_lat_lane_change for the no-steer signal,
but the UI's distinctive yellow CHANGE_LANE_PATH_COLOR (onroad.cc:901)
reads from frogpilotCarControl.NoLatLaneChange — which nobody was setting,
so the yellow line never appeared during lane-change suppression.

plannerd: skip longitudinal_planner.update + publish + publish_ui_plan
while parked. Downstream controlsd already short-circuits in park, so
longitudinalPlan / uiPlan staleness is fine.

frogpilot_process: same idea — skip frogpilot_planner.update + publish
while parked.

dmonitoringmodeld: mirror the cached-output trick from modeld. Add carState
to the SubMaster, cache the last (model_output, dsp_execution_time) tuple,
and serve it on every frame while gear is in park instead of running DSP
inference on the driver camera.

Together with the existing modeld park-cached-output, the heavy onroad
processing pipeline (modeld → plannerd → controlsd → carcontroller) now
all idles in park and only fires when the car leaves park.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-04-26 12:12:38 -05:00
brianhansonxyz dc7e0a2db7 controlsd+calibrationd: suppress commIssue from valid=False cascade
Two fixes that reinstate the pre-revert defenses against the "TAKE CONTROL
IMMEDIATELY / Communication Issue" banner that fires when self-driving
on the baseline modelrevert stack:

calibrationd: publish valid based on calStatus == calibrated, not
sm.all_checks(). Original gate cascaded upstream freq glitches into
liveCalibration.valid=False, which kept locationd.filterInitialized
False, which fed garbage into paramsd, which corrupted steerRatio
(erratic steering). "valid" here is a question about convergence, not
input freshness.

controlsd: narrow the commIssue trigger to genuine comm failures —
not_alive OR can_rcv_timeout. The `not sm.all_checks()` branch also
picked up valid=False, but paramsd / torqued / plannerd / frogpilot_planner
/ dmonitoringd all propagate their sm.all_checks() into msg.valid via
a polling-pattern artifact (freq_ok inside poll='...' subscribers
tracks gaps between drain bursts rather than the publish rate), so
the whole stack flaps valid and trips the banner during normal
driving. Content and rate are fine; just the flag.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-04-23 11:00:45 -05:00
brianhansonxyz f896dfe25a modeld: cached-output standby while gear is in park
Narrow re-introduction of the power-save mode: when carState reports
gearShifter == park, serve the last rendered model_output instead of
running GPU inference. First cycle (or before carState is flowing)
still runs one real inference so we have something to cache and serve.
Out-of-park returns to per-frame inference immediately.

Avoids the pitfall of the earlier variable-rate path: this doesn't
change the publish rate on modelV2/cameraOdometry (we still publish
every frame), so downstream freq_ok / valid checks in calibrationd /
locationd / paramsd stay happy. Only the GPU inference is skipped.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-04-23 10:49:44 -05:00
brianhansonxyz 2ce6e8fe0c modelrevert: boot fixes + strip remaining variable-rate cruft
controlsd:
- stop writing the removed 'no_lat_lane_change' persistent param
  (key isn't in the whitelist anymore). Write to
  frogpilot_variables.no_lat_lane_change instead so the carcontroller
  read still works and the lane-change-disengage feature is preserved.
- initialize self.driving_gear = False in __init__; it's set at the
  end of step() in update_frogpilot_variables but clearpilot_state_control
  reads it on the first iteration before that's run.

modeld:
- remove the remaining CLEARPILOT variable-rate / standby code path
  that was baked into the initial-import commit (the one our first
  commit captured). Constant 20fps, no ModelStandby/ModelStandbyTs
  writes, no params_memory reads for 'no_lat_lane_change' (which
  isn't registered anymore).
- drop now-unused locals (model_standby, last_standby_ts_write,
  params_memory).

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-04-23 10:42:11 -05:00
brianhansonxyz 3bd0c942e8 controlsd: re-apply QoL hooks on top of reverted baseline
Re-adds the non-self-drive controlsd integrations that the UI and
memory-param pipeline need:

- import SpeedState from clearpilot.speed_logic
- self.speed_state, speed_state_frame, was_driving_gear init
- subscribe to gpsLocation (ignored in alive/freq_ok/valid gates — OK if
  the GPS daemon isn't publishing)
- clearpilot_state_control:
  - auto-reset ScreenDisplayMode 3→0 on park→drive transition
  - ~2Hz speed-state update driving the speed-limit sign and cruise
    over/under warning sign via ClearpilotCruiseWarning /
    ClearpilotSpeedLimitDisplay memory params

The debug-button (LFA) ScreenDisplayMode cycling already lived in the
reverted baseline (it was in the first commit), so it's preserved.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-04-19 13:31:51 -05:00
brianhansonxyz 12da9acfdd revert modeld/controlsd/plannerd/locationd to first-commit baseline
Starting point for rebuilding self-drive from a known-good baseline.
Reverts the following to their state at f46339c:
- selfdrive/modeld/modeld.py (constant 20fps, no variable-rate / standby skip)
- selfdrive/modeld/dmonitoringmodeld.py (no carState sub, no standstill skip)
- selfdrive/controls/controlsd.py (no parked-cycle skip, no FPCC hoisting, no MDPS split)
- selfdrive/controls/lib/longitudinal_planner.py
- selfdrive/locationd/calibrationd.py (valid = sm.all_checks again)
- selfdrive/locationd/paramsd.py
- selfdrive/locationd/torqued.py

All non-self-drive features (thermald fan control, speed limit controller,
cruise warning signs, UI state transitions, GPS fixes, ClearPilot menu,
dashcamd, telemetry, etc.) remain as-is on this branch — only the 4 core
self-drive processes are reverted.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-04-19 13:26:36 -05:00
130 changed files with 9786 additions and 878 deletions
+2
View File
@@ -2,6 +2,8 @@ prebuilt
system/clearpilot/dev/on_start_brian.sh system/clearpilot/dev/on_start_brian.sh
system/clearpilot/dev/id_rsa system/clearpilot/dev/id_rsa
system/clearpilot/dev/id_rsa.pub system/clearpilot/dev/id_rsa.pub
system/clearpilot/dev/id_ed25519
system/clearpilot/dev/id_ed25519.pub
venv/ venv/
.venv/ .venv/
.ci_cache .ci_cache
+29
View File
@@ -0,0 +1,29 @@
# CAN-FD Issues to Investigate
## Cruise Control Desync on Hot Start
### Problem
When the car is already in cruise control mode before openpilot starts (or before controlsd initializes), pressing the cruise control button causes a desync:
1. Car has active cruise control when openpilot comes online
2. Driver presses cruise button — car interprets as "toggle off" (cruise was already on)
3. openpilot interprets it as "engage" (from its perspective, it hasn't seen a cruise enable transition)
4. Result: car disengages cruise, but openpilot thinks it just engaged lateral mode
### Proposed Fix
When controlsd first reads carState and discovers `cruiseState.enabled` is already true:
1. Set a flag `cruise_was_active_at_start = True`
2. While this flag is set, do NOT allow openpilot to transition to engaged state on button press
3. Only clear the flag after seeing `cruiseState.enabled` go to `False` at least once (a full stop of cruise, not just standstill/pause)
4. After the first full off cycle, normal engagement logic resumes
### Status
- Could not reproduce on 2026-04-14 — may require specific timing (openpilot restart while driving with cruise active)
- Need to capture telemetry data during reproduction to see exact signal sequence
- Key telemetry groups to watch: `cruise` (enabled, available, ACCMode, VSetDis), `buttons` (cruise_button)
### Relevant Code
- `selfdrive/controls/controlsd.py` — engagement state machine
- `selfdrive/car/hyundai/carstate.py` — CAN-FD cruise state parsing
- `selfdrive/car/interfaces.py` — pcm_enable / cruise state transitions
+601
View File
@@ -0,0 +1,601 @@
# ClearPilot — CLAUDE.md
## Project Overview
ClearPilot is a custom fork of **FrogPilot** (itself a fork of comma.ai's openpilot), based on a 2024 release. It is purpose-built for Brian Hanson's **Hyundai Tucson** (HDA2 equipped). The vehicle's HDA2 system has specific quirks around how it synchronizes driving state with openpilot that require careful handling.
### Key Customizations in This Fork
- **UI changes** to the onroad driving interface
- **Lane change behavior**: brief disengage when turn signal is active during lane changes
- **Lateral control disabled**: the car's own radar cruise control handles lateral; openpilot handles longitudinal only
- **Driver monitoring timeouts**: modified safety timeouts for the driver monitoring system
- **Custom driving models**: `duck-amigo.thneed`, `farmville.onnx`, `wd-40.thneed` in `selfdrive/clearpilot/models/`
- **ClearPilot service**: Node.js service at `selfdrive/clearpilot/` with behavior scripts for lane change and longitudinal control
- **Native dashcamd**: C++ process capturing raw camera frames via VisionIPC with OMX H.264 hardware encoding
- **Standstill power saving**: model inference throttled to 1fps and fan quieted when car is stopped
- **ClearPilot menu**: sidebar settings panel replacing stock home screen (Home, Dashcam, Debug panels)
- **Status window**: live system stats (temp, fan, storage, RAM, WiFi, VPN, GPS, telemetry, dashcam status)
- **Debug button (LFA)**: steering wheel button repurposed for screen toggle and future UI actions
- **Telemetry system**: diff-based CSV logger via ZMQ IPC, toggleable from Debug panel
- **Bench mode**: `--bench` flag for onroad UI testing without car connected
- **GPS**: custom AT-command based GPS daemon (`system/clearpilot/gpsd.py`) replacing broken qcomgpsd diag interface
- **OpenVPN tunnel**: auto-connecting VPN to expose device on remote network for SSH access
See `GOALS.md` for feature roadmap.
## Working Rules
### CRITICAL: Change Control
This is self-driving software. All changes must be deliberate and well-understood.
- **NEVER make changes outside of what is explicitly requested**
- **Always explain proposed changes first** — describe the change, the logic, and the architecture; let Brian review and approve before writing any code
- **Brian is an expert on this software** — do not override his judgment or assume responsibility for changes he doesn't understand
- **Every line must be understood** — work slowly and deliberately
- **Test everything thoroughly** — Brian must always be in the loop
- **Do not refactor, clean up, or "improve" code beyond the specific request**
### Logging
**NEVER use `cloudlog`.** It's comma.ai's cloud telemetry pipeline, not ours — writes go to a publisher that's effectively a black hole for us (and the only thing it could do if ever reachable is bother the upstream FrogPilot developer). Our changes must always use **file logging** instead.
Use `print(..., file=sys.stderr, flush=True)`. `manager.py` redirects each managed process's stderr to `/data/log2/current/{process}.log`, so these lines land in the per-process log we already grep. Prefix custom log lines with `CLP ` so they're easy to filter out from upstream noise.
Example:
```python
import sys
print(f"CLP frogpilotPlan valid=False: carState_freq_ok={sm.freq_ok['carState']}", file=sys.stderr, flush=True)
```
Do not use `cloudlog.warning`, `cloudlog.info`, `cloudlog.error`, `cloudlog.event`, or `cloudlog.exception` in any CLEARPILOT-added code. Existing upstream/FrogPilot `cloudlog` calls can stay untouched.
### File Ownership
We operate as `root` on this device, but openpilot runs as the `comma` user (uid=1000, gid=1000). After any code changes that touch multiple files or before testing:
```bash
chown -R comma:comma /data/openpilot
```
### Git
- Remote: `git@git.hanson.xyz:brianhansonxyz/clearpilot.git`
- Branch: `clearpilot`
- Large model files are tracked in git (intentional — this is a backup)
### Samba Share
- Share name: `openpilot` (e.g. `\\comma-3889765b\openpilot`)
- Path: `/data/openpilot`
- Username: `comma`
- Password: `i-like-to-drive-cars`
- Runs as `comma:comma` via force user/group — files created over SMB are owned correctly
- Enabled at boot (`smbd` + `nmbd`)
### Testing Changes
Always use `build_only.sh` to compile, then start the manager separately. Never compile individual targets with scons directly — always use the full build script. Always use full paths with `su - comma` — the login shell drops into `/home/comma` (volatile tmpfs), not `/data/openpilot`. **Always start the manager after a successful build** — don't wait for the user to ask.
```bash
# 1. Fix ownership (we edit as root, openpilot runs as comma)
chown -R comma:comma /data/openpilot
# 2. Build (kills running manager, removes prebuilt, compiles, exits)
# Shows progress spinner on screen. On failure, shows error on screen
# and prints to stderr. Does NOT start the manager.
su - comma -c "bash /data/openpilot/build_only.sh"
# 3. If build succeeded ($? == 0), start openpilot
su - comma -c "bash /data/openpilot/launch_openpilot.sh"
# 4. Review the aggregate session log for errors
cat /data/log2/current/session.log
# 5. Check per-process stdout/stderr logs if needed
ls /data/log2/current/
cat /data/log2/current/gpsd.log
```
### Changing a Service's Publish Rate
SubMaster's `freq_ok` check requires observed rate to fall within
`[0.8 × min_freq, 1.2 × max_freq]` of the value declared in
`cereal/services.py`. Publishing *faster* than declared fails the check
just as surely as publishing too slowly — it trips `all_freq_ok()`
`EventName.commIssue` → "TAKE CONTROL IMMEDIATELY / Communication Issue
Between Processes".
If you change how often a process publishes, you **must** update the rate
in `cereal/services.py` to match. Example (real bug we hit):
- Bumped thermald from 2Hz → 4Hz (DT_TRML 0.5→0.25) for faster fan control
- Bumped gpsd from 1Hz → 2Hz
- manager publishes `managerState` gated by `sm.update()` returning on
`deviceState`, so it picks up thermald's rate automatically
`services.py` still declared `deviceState` and `managerState` as 2Hz
(ceiling 2.4Hz) and `gpsLocation` as 1Hz (ceiling 1.2Hz), so controlsd
fired `commIssue` on every cycle the moment any of these arrived at the
new faster rate.
Fix: update the second tuple element (Hz) in `cereal/services.py` for the
affected service. Cereal will use the updated rate for all consumers.
### Adding New Params
The params system uses a C++ whitelist. Adding a new param name in `manager.py` alone will crash with `UnknownKeyName`. You must:
1. Register the key in `common/params.cc` (alphabetically, with `PERSISTENT` or `CLEAR_ON_*` flag)
2. Add the default value in `selfdrive/manager/manager.py` in `manager_init()`
3. Remove `prebuilt`, `common/params.o`, and `common/libcommon.a` to force rebuild
### Memory Params (paramsMemory)
ClearPilot uses memory params (`/dev/shm/params/d/`) for UI toggles that should reset on boot. Key rules:
- **Registration**: Register the key in `common/params.cc` as `PERSISTENT` (same as FrogPilot pattern — the registration flag does NOT control which path the param lives at)
- **C++ access**: Use `Params{"/dev/shm/params"}` — stored as a class member `paramsMemory` in onroad.h. Do NOT use `Params("/dev/shm/params/d")` — the Params class appends `/d/` internally, so that would resolve to `/dev/shm/params/d/d/`
- **Python access**: Use `Params("/dev/shm/params")`
- **Defaults**: Set in `manager_init()` via `Params("/dev/shm/params").put(key, value)`
- **UI toggles**: Use `ToggleControl` with manual `toggleFlipped` lambda that writes via `Params("/dev/shm/params")`. Do NOT use `ParamControl` for memory params — it reads/writes persistent params only
- **Current memory params**: `TelemetryEnabled` (default "0"), `VpnEnabled` (default "1"), `ModelStandby` (default "0"), `ScreenDisplayMode`, `DashcamState` (default "stopped"), `DashcamFrames` (default "0"), `DashcamShutdown` (default "0")
- **IMPORTANT — method names differ between C++ and Python**: C++ uses camelCase (`putBool`, `getBool`, `getInt`), Python uses snake_case (`put_bool`, `get_bool`, `get_int`). This is a common source of silent failures — the wrong casing compiles/runs but doesn't work.
### Building Native (C++) Processes
- SCons is the build system. Static libraries (`common`, `messaging`, `cereal`, `visionipc`) must be imported as SCons objects, not `-l` flags
- The `--as-needed` linker flag can cause link order issues with static libs — disable it in your SConscript if needed
- OMX encoder object (`omx_encoder.o`) is compiled by the UI build — reference the pre-built `.o` file rather than recompiling (avoids "two environments" scons error)
- `prebuilt` is recreated after every successful build — always remove it before rebuilding
## Bench Mode (Onroad UI Testing)
Bench mode allows testing the onroad UI without a car connected. It runs a fake vehicle simulator (`bench_onroad.py`) as a managed process and disables real car processes (pandad, thermald, controlsd, etc.).
### Usage
**IMPORTANT**: Do NOT use `echo` to write bench params — `echo` appends a newline which causes param parsing to fail silently (e.g. gear stays in park). Always use the `bench_cmd.py` tool.
```bash
# 1. Build first
chown -R comma:comma /data/openpilot
su - comma -c "bash /data/openpilot/build_only.sh"
# 2. Start in bench mode
su - comma -c "bash /data/openpilot/launch_openpilot.sh --bench"
# 3. Wait for UI to be ready (polls RPC every 1s, up to 20s)
su - comma -c "PYTHONPATH=/data/openpilot python3 -m selfdrive.clearpilot.bench_cmd wait_ready"
# 4. Control vehicle state
su - comma -c "PYTHONPATH=/data/openpilot python3 -m selfdrive.clearpilot.bench_cmd gear D"
su - comma -c "PYTHONPATH=/data/openpilot python3 -m selfdrive.clearpilot.bench_cmd speed 20"
su - comma -c "PYTHONPATH=/data/openpilot python3 -m selfdrive.clearpilot.bench_cmd speedlimit 45"
su - comma -c "PYTHONPATH=/data/openpilot python3 -m selfdrive.clearpilot.bench_cmd cruise 55"
su - comma -c "PYTHONPATH=/data/openpilot python3 -m selfdrive.clearpilot.bench_cmd engaged 1"
# 5. Inspect UI widget tree (RPC call, instant response)
su - comma -c "PYTHONPATH=/data/openpilot python3 -m selfdrive.clearpilot.bench_cmd dump"
```
### Debugging Crashes
The UI has a SIGSEGV/SIGABRT crash handler (`selfdrive/ui/main.cc`) that prints a stack trace to stderr, captured in the per-process log:
```bash
# Check for crash traces (use /data/log2/current which is always the active session)
grep -A 30 "CRASH" /data/log2/current/ui.log
# Resolve addresses to source lines
addr2line -e /data/openpilot/selfdrive/ui/ui -f 0xADDRESS
# bench_cmd dump detects crash loops automatically:
# if UI process uptime < 5s, it reports "likely crash looping"
# Check per-process logs
ls /data/log2/current/
cat /data/log2/current/session.log
cat /data/log2/current/gpsd.log
```
### UI Introspection RPC
The UI process runs a ZMQ REP server at `ipc:///tmp/clearpilot_ui_rpc`. Send `"dump"` to get a recursive widget tree showing class name, visibility, geometry, and stacked layout current indices. This is the primary debugging tool for understanding what the UI is displaying.
- `bench_cmd dump` — queries the RPC and prints the widget tree
- `bench_cmd wait_ready` — polls the RPC every second until `ReadyWindow` is visible (up to 10s)
- `ui_dump.py` — standalone dump tool (same as `bench_cmd dump`)
### Architecture
- `launch_openpilot.sh --bench` sets `BENCH_MODE=1` env var
- `manager.py` reads `BENCH_MODE`, blocks real car processes, enables `bench_onroad` process
- `bench_onroad.py` publishes fake `pandaStates` (ignition=true), `carState`, `controlsState` — thermald reads the fake pandaStates to determine ignition and publishes `deviceState.started=true` on its own
- thermald and camerad run normally in bench mode (thermald manages CPU cores needed for camerad)
- Blocked processes in bench mode: pandad, controlsd, radard, plannerd, calibrationd, torqued, paramsd, locationd, sensord, ubloxd, pigeond, dmonitoringmodeld, dmonitoringd, modeld, soundd, loggerd, micd, dashcamd
### Key Files
| File | Role |
|------|------|
| `selfdrive/clearpilot/bench_onroad.py` | Fake vehicle state publisher |
| `selfdrive/clearpilot/bench_cmd.py` | Command tool for setting bench params and querying UI |
| `selfdrive/clearpilot/ui_dump.py` | Standalone UI widget tree dump |
| `selfdrive/manager/process_config.py` | Registers bench_onroad as managed process (enabled=BENCH_MODE) |
| `selfdrive/manager/manager.py` | Blocks conflicting processes in bench mode |
| `launch_openpilot.sh` | Accepts `--bench` flag, exports BENCH_MODE env var |
| `selfdrive/ui/qt/window.cc` | UI RPC server (`ipc:///tmp/clearpilot_ui_rpc`), widget tree dump |
### Resolved Issues
- **SIGSEGV in onroad view (fixed)**: `update_model()` in `ui.cc` dereferenced empty model position data when modeld wasn't running. Fixed by guarding against empty `plan_position.getX()`. The root cause was found using the crash handler + `addr2line`.
- **`showDriverView` overriding transitions (fixed)**: was forcing `slayout` to onroad/home every frame at 20Hz, overriding park/drive logic. Fixed to only act when not in started state.
- **Sidebar appearing during onroad transition (fixed)**: `MainWindow::closeSettings()` was re-enabling the sidebar. Fixed by not calling `closeSettings` during `offroadTransition`.
## Performance Profiling
Use `py-spy` to find CPU hotspots in any Python process. It's installed at `/home/comma/.local/bin/py-spy`. (If missing: `su - comma -c "/usr/local/pyenv/versions/3.11.4/bin/pip install py-spy"`.)
```bash
# Find the target pid
ps -eo pid,cmd | grep -E "selfdrive.controls.controlsd" | grep -v grep
# Record 10s of stacks at 200Hz, raw (folded) format
/home/comma/.local/bin/py-spy record -o /tmp/ctrl.txt --pid <PID> --duration 10 --rate 200 --format raw
# Aggregate: which line of step() is consuming the most samples
awk -F';' '{
for(i=1;i<=NF;i++) if ($i ~ /step \(selfdrive\/controls\/controlsd.py/) step_line=i;
if (step_line && step_line < NF) {
n=split($NF, parts, " "); count=parts[n];
caller = $(step_line+1);
sum[caller] += count;
}
step_line=0;
} END { for (c in sum) printf "%6d %s\n", sum[c], c }' /tmp/ctrl.txt | sort -rn | head -15
# Aggregate by a source file — shows hottest lines in that file
awk -F';' '{
for(i=1;i<=NF;i++) if ($i ~ /carstate\.py:/) {
match($i, /:[0-9]+/); ln = substr($i, RSTART+1, RLENGTH-1);
n=split($NF, parts, " "); count=parts[n];
sum[ln] += count;
}
} END { for (l in sum) printf "%5d line %s\n", sum[l], l }' /tmp/ctrl.txt | sort -rn | head -15
# Quick stack dump (single sample, no recording)
/home/comma/.local/bin/py-spy dump --pid <PID>
```
**Known performance trap — hot `Params` writes**: `Params.put()` does `mkstemp` + `fsync` + `flock` + `rename` + `fsync_dir`. At 100Hz even on tmpfs the `flock` contention is ruinous. Cache the last-written value and skip writes when unchanged. Found this pattern in `carstate.py` and `controlsd.py` — controlsd went from 69% → 28% CPU after gating writes.
## Session Logging
Per-process stderr and an aggregate event log are captured in `/data/log2/current/`.
### Log Directory
- `/data/log2/current/` is always the active session directory
- `init_log_dir()` is called once from `manager_init()` — creates a fresh `/data/log2/current/` real directory
- If a previous `current/` real directory exists (unresolved session), it's renamed using its mtime timestamp
- If a previous `current` symlink exists, it's removed
- Once system time is valid (GPS/NTP), the real directory is renamed to `/data/log2/YYYY-MM-DD-HH-MM-SS/` and `current` becomes a symlink to it
- `LogDirInitialized` param: `"0"` until time resolves, then `"1"`
- Open file handles survive the rename (same inode, same filesystem)
- Session directories older than 30 days are deleted on manager startup
### Per-Process Logs
- Every `PythonProcess` and `NativeProcess` has stderr redirected to `{name}.log` in the session directory
- `DaemonProcess` (athenad) redirects both stdout+stderr (existing behavior)
- Stderr is redirected via `os.dup2` inside the forked child process
### Aggregate Session Log (`session.log`)
A single `session.log` in each session directory records major events:
- Manager start/stop/crash
- Process starts, deaths (with exit codes), watchdog restarts
- Onroad/offroad transitions
### Key Files
| File | Role |
|------|------|
| `selfdrive/manager/process.py` | Log directory creation, stderr redirection, session_log logger |
| `selfdrive/manager/manager.py` | Log rotation cleanup, session event logging |
| `build_only.sh` | Build-only script (no manager start) |
## Dashcam (dashcamd)
### Architecture
`dashcamd` is a native C++ process that captures raw camera frames directly from `camerad` via VisionIPC and encodes to MP4 using the Qualcomm OMX H.264 hardware encoder. This replaces the earlier FrogPilot screen recorder approach (`QWidget::grab()` -> OMX).
- **Codec**: H.264 AVC (hardware accelerated via `OMX.qcom.video.encoder.avc`)
- **Resolution**: 1928x1208 (full camera resolution, no downscaling)
- **Bitrate**: 2500 kbps
- **Container**: MP4 (remuxed via libavformat) + SRT subtitle sidecar
- **Segment length**: 3 minutes per file
- **Save path**: `/data/media/0/videos/YYYYMMDD-HHMMSS/YYYYMMDD-HHMMSS.mp4` (trip directories)
- **GPS subtitles**: companion `.srt` file per segment with 1Hz entries (speed MPH, lat/lon, UTC timestamp)
- **Trip lifecycle**: waits in WAITING state until valid system time + GPS fix + car in drive; records until car parked 10 min or ignition off; then returns to WAITING
- **Graceful shutdown**: thermald sets `DashcamShutdown` param, dashcamd closes segment and acks within 15s
- **Storage**: ~56 MB per 3-minute segment at 2500 kbps (verified: actual bitrate ~2570 kbps)
- **Crash handler**: SIGSEGV/SIGABRT handler writes backtrace to `/tmp/dashcamd_crash.log`
- **Storage device**: WDC SDINDDH4-128G UFS 2.1 — automotive grade, ~384 TB write endurance, no concern for continuous writes
### OmxEncoder
The OMX encoder (`selfdrive/frogpilot/screenrecorder/omx_encoder.cc`) was ported from upstream FrogPilot with the following key properties:
- Each encoder instance calls `OMX_Init()` in constructor and `OMX_Deinit()` in destructor — manages its own OMX lifecycle
- Constructor takes 5 args: `(path, width, height, fps, bitrate)` — no h265/downscale params
- `encoder_close()` calls `av_write_trailer` + ffmpeg faststart remux (`-movflags +faststart`)
- Destructor has null guards and error handling on all OMX state transitions
- ClearPilot addition: `encode_frame_nv12()` for direct NV12 input (dashcamd), alongside original `encode_frame_rgba()` (screen recorder)
### Key Files
| File | Role |
|------|------|
| `selfdrive/clearpilot/dashcamd.cc` | Main dashcam process — VisionIPC -> OMX encoder |
| `selfdrive/clearpilot/SConscript` | Build config for dashcamd |
| `selfdrive/frogpilot/screenrecorder/omx_encoder.cc` | OMX encoder (upstream FrogPilot port + `encode_frame_nv12`) |
| `selfdrive/frogpilot/screenrecorder/omx_encoder.h` | Encoder header |
| `selfdrive/manager/process_config.py` | dashcamd registered as NativeProcess, camerad always_run, encoderd disabled |
| `system/loggerd/deleter.py` | Trip-aware storage rotation (oldest trip first, then segments within active trip) |
### Params
- `DashcamShutdown` (memory param) — set by thermald before power-off, dashcamd acks by clearing it
- `DashcamState` (memory param) — "stopped", "waiting", or "recording" — published every 5s
- `DashcamFrames` (memory param) — per-trip encoded frame count, resets each trip — published every 5s
## Standstill Power Saving
When `carState.standstill` is true:
- **modeld**: skips GPU inference on 19/20 frames (1fps vs 20fps), reports 0 frame drops to avoid triggering `modeldLagging` in controlsd. Runs full 20fps during calibration (`liveCalibration.calStatus != calibrated`)
- **dmonitoringmodeld**: same 1fps throttle, added `carState` subscription
- **Fan controller**: uses offroad clamps (0-30%) instead of onroad (30-100%) at standstill; thermal protection still active via feedforward if temp > 60°C
### Key Files
| File | Role |
|------|------|
| `selfdrive/modeld/modeld.py` | Standstill frame skip logic |
| `selfdrive/modeld/dmonitoringmodeld.py` | Standstill frame skip logic |
| `selfdrive/thermald/fan_controller.py` | Standstill-aware fan clamps |
| `selfdrive/thermald/thermald.py` | Passes standstill to fan controller via carState |
## Display Modes (LFA/LKAS Debug Button)
The Hyundai Tucson's LFA steering wheel button cycles through 5 display modes via `ScreenDisplayMode` param (`/dev/shm/params`, CLEAR_ON_MANAGER_START, default 0).
### Display States
| State | Name | Display | Camera | Path Drawing |
|-------|------|---------|--------|-------------|
| 0 | auto-normal | on | yes | filled (normal) |
| 1 | auto-nightrider | on | black | 2px outline only |
| 2 | normal (manual) | on | yes | filled (normal) |
| 3 | screen off | GPIO off | n/a | n/a |
| 4 | nightrider (manual) | on | black | 2px outline only |
### Auto Day/Night Switching
- `gpsd.py` computes `is_daylight(lat, lon, utc_dt)` using NOAA solar position algorithm
- First calculation immediately on GPS fix + valid clock, then every 30 seconds
- State 0 + sunset → auto-switch to 1; State 1 + sunrise → auto-switch to 0
- States 2/3/4 are never touched by auto logic
- `IsDaylight` param written to `/dev/shm/params` for reference
### Button Behavior
**Onroad (car in drive gear):** 0→4, 1→2, 2→3, 3→4, 4→2 (never back to auto via button)
**Not in drive (parked/off):** any except 3 → 3 (screen off), state 3 → 0 (auto-normal)
**Shift to drive from screen off:** auto-resets to mode 0 (auto-normal) via `controlsd`
**Shift to park from nightrider:** auto-switches to mode 3 (screen off) via `home.cc`
**Tap screen while screen off:** resets to mode 0 (auto-normal) via `window.cc` touch handler
### Nightrider Mode
- Camera feed suppressed (OpenGL clears to black instead of rendering camera texture)
- All HUD elements (speed, alerts, telemetry indicator) still visible
- Path/lane polygons drawn as 2px outlines only (no gradient fill)
- Lane lines, road edges, blind spot paths, adjacent paths all use outline rendering
### Signal Chain
```
Steering wheel LFA button press
-> CAN-FD: cruise_btns_msg_canfd["LFA_BTN"]
-> Edge detection → ButtonEvent(type=FrogPilotButtonType.lkas)
-> controlsd.clearpilot_state_control()
-> Reads ScreenDisplayMode, applies transition table based on driving_gear
-> Writes new ScreenDisplayMode to /dev/shm/params
-> UI reads ScreenDisplayMode in paintEvent() (for camera/nightrider)
and drawHud() (for display power on/off)
```
### Key Files
| File | Role |
|------|------|
| `selfdrive/controls/controlsd.py` | Button state machine, writes ScreenDisplayMode |
| `selfdrive/ui/qt/onroad.cc` | Nightrider rendering, display power control |
| `selfdrive/ui/qt/home.cc` | Display power for park/splash state |
| `system/clearpilot/gpsd.py` | Sunset/sunrise calc, auto day/night transitions |
| `selfdrive/clearpilot/bench_cmd.py` | `debugbutton` command simulates button press |
## Screen Timeout / Display Power
Display power is managed by `Device::updateWakefulness()` in `selfdrive/ui/ui.cc`.
- **Ignition off (offroad)**: screen blanks after `ScreenTimeout` seconds (default 120) of no touch. Tapping wakes it.
- **Ignition on (onroad)**: screen stays on unconditionally — ignition=true short-circuits the timeout check.
- **ScreenDisplayMode 3 override**: `updateWakefulness` checks `ScreenDisplayMode` first — if mode 3, calls `setAwake(false)` unconditionally, preventing ignition-on from overriding screen-off.
- **Debug button (LFA)**: cycles through display modes including screen off (state 3).
- **Park transition**: always shows splash screen; if coming from nightrider mode, auto-switches to screen off (mode 3) via `home.cc`.
- **Touch wake**: tapping screen while in mode 3 resets to mode 0 via `window.cc` event filter.
## Offroad UI (ClearPilot Menu)
The offroad home screen (`selfdrive/ui/qt/home.cc`) is a sidebar settings panel replacing the stock home screen. The original system settings are no longer accessible — the ClearPilot menu is the only settings interface.
### Panels
- **General**: Status window, Reset Calibration, Shutdown Timer, Reboot/Soft Reboot/Power Off
- **Network**: WiFi management, tethering, roaming, hidden networks (APN settings removed)
- **Dashcam**: placeholder for future dashcam footage viewer
- **Debug**: Telemetry logging toggle
### Navigation
- Tapping the splash screen (ReadyWindow) opens the ClearPilot menu
- "← Back" button returns to splash or onroad view
- Sidebar with stock metrics (TEMP, VEHICLE, CONNECT) is hidden
## Device: comma 3x
### Hardware
- Qualcomm Snapdragon SoC (aarch64)
- Serial: comma-3889765b
- Storage: WDC SDINDDH4-128G, 128 GB UFS 2.1
- Connects to the car via comma panda (CAN bus interface)
### Operating System
- **Ubuntu 20.04.6 LTS (Focal Fossa)** on aarch64
- **Kernel**: 4.9.103+ (custom comma.ai PREEMPT build, Feb 2024) — very old, vendor-patched Qualcomm kernel
- **Python**: 3.11.4 via pyenv at `/usr/local/pyenv/versions/3.11.4/` (system python is 3.8, do not use)
- **AGNOS version**: 9.7 (comma's custom OS layer on top of Ubuntu)
- **Display server**: Weston (Wayland compositor) on tty1
- **SELinux**: mounted (enforcement status varies)
### Users
- `comma` (uid=1000) — the user openpilot runs as; member of root, sudo, disk, gpu, gpio groups
- `root` — what we SSH in as; files must be chowned back to comma before running openpilot
### Filesystem / Mount Quirks
| Mount | Device | Type | Notes |
|-------------|-------------|---------|-------|
| `/` | /dev/sda7 | ext4 | Root filesystem, read-write |
| `/data` | /dev/sda12 | ext4 | **Persistent**. Openpilot lives here. Survives reboots. |
| `/home` | overlay | overlayfs | **VOLATILE** — upperdir on tmpfs, changes lost on reboot |
| `/tmp` | tmpfs | tmpfs | Volatile, 150 MB |
| `/var` | tmpfs | tmpfs | Volatile, 128 MB (fstab) / 1.5 GB (actual) |
| `/systemrw` | /dev/sda10 | ext4 | Writable system overlay, noexec |
| `/persist` | /dev/sda2 | ext4 | Persistent config/certs, noexec |
| `/cache` | /dev/sda11 | ext4 | Android-style cache partition |
| `/dsp` | /dev/sde26 | ext4 | **Read-only** Qualcomm DSP firmware |
| `/firmware` | /dev/sde4 | vfat | **Read-only** firmware blobs |
### Hardware Encoding
- **OMX**: `OMX.qcom.video.encoder.avc` (H.264) and `OMX.qcom.video.encoder.hevc` — used by dashcamd and screen recorder
- **V4L2**: Qualcomm VIDC at `/dev/v4l/by-path/platform-aa00000.qcom_vidc-video-index1` — used by encoderd (now disabled). Not accessible from ffmpeg due to permission/driver issues
- **ffmpeg**: v4.2.2, has `h264_v4l2m2m` and `h264_omx` listed but neither works from ffmpeg subprocess (OMX port issues, V4L2 device not found). Use OMX directly via the C++ encoder
### Fan Control
Software-controlled via `thermald` -> `fan_controller.py` -> panda USB -> PWM. Target temp 70°C, PI+feedforward controller. See Standstill Power Saving section for standstill-aware clamps.
## Boot Sequence
```
Power On
-> systemd: comma.service (runs as comma user)
-> /usr/comma/comma.sh (waits for Weston, handles factory reset)
-> /data/continue.sh (exec bridge to openpilot)
-> /data/openpilot/launch_openpilot.sh
-> Kills other instances of itself and manager.py
-> Runs on_start.sh (logo, reverse SSH)
-> exec launch_chffrplus.sh
-> Sources launch_env.sh (thread counts, AGNOS_VERSION)
-> Runs agnos_init (marks boot slot, GPU perms, checks OS update)
-> Sets PYTHONPATH, symlinks /data/pythonpath
-> Runs build.py if no `prebuilt` marker
-> Launches selfdrive/manager/manager.py
-> manager_init() sets default params
-> ensure_running() loop starts all managed processes
```
## Openpilot Architecture
### Process Manager
`selfdrive/manager/manager.py` orchestrates all processes defined in `selfdrive/manager/process_config.py`.
### Always-Running Processes (offroad + onroad)
- `thermald` — thermal management and fan control
- `pandad` — panda CAN bus interface
- `ui` — Qt-based onroad/offroad UI
- `deleter` — storage cleanup (9 GB threshold)
- `statsd`, `timed`, `logmessaged`, `tombstoned` — telemetry/logging
- `manage_athenad` — comma cloud connectivity
- `fleet_manager`, `frogpilot_process` — FrogPilot additions
### Onroad-Only Processes (when driving)
- `controlsd` — main vehicle control loop
- `plannerd` — path planning
- `radard` — radar processing
- `modeld` — driving model inference (throttled to 1fps at standstill)
- `dmonitoringmodeld` — driver monitoring model (throttled to 1fps at standstill)
- `locationd`, `calibrationd`, `paramsd`, `torqued` — localization and calibration
- `sensord` — IMU/sensor data
- `soundd` — alert sounds
- `camerad` — camera capture
- `loggerd` — CAN/sensor log recording (video encoding disabled)
### ClearPilot Processes
- `dashcamd` — raw camera dashcam recording (always runs; manages its own trip lifecycle)
### GPS
- Device has **no u-blox chip** (`/dev/ttyHS0` does not exist) — `ubloxd`/`pigeond` never start
- GPS hardware is a **Quectel EC25 LTE modem** (USB, `lsusb: 2c7c:0125`) with built-in GPS
- GPS is accessed via AT commands through `mmcli`: `mmcli -m any --command='AT+QGPSLOC=2'`
- **`qcomgpsd`** (original openpilot process) uses the modem's diag interface which is broken on this device — the diag recv loop blocks forever after setup. Commented out.
- **`system/clearpilot/gpsd.py`** is the replacement — polls GPS via AT commands at 1Hz, publishes `gpsLocation` cereal messages
- GPS data flows: `gpsd``gpsLocation``locationd``liveLocationKalman``timed` (sets system clock)
- `locationd` checks `UbloxAvailable` param (false on this device) to subscribe to `gpsLocation` instead of `gpsLocationExternal`
- `mmcli` returns `response: '...'` wrapper — `at_cmd()` strips it before parsing (fixed)
- GPS antenna power must be enabled via GPIO: `gpio_set(GPIO.GNSS_PWR_EN, True)`
- System `/usr/sbin/gpsd` daemon may respawn and interfere — should be disabled or killed
### Telemetry
- **Client**: `selfdrive/clearpilot/telemetry.py``tlog(group, data)` sends JSON over ZMQ PUSH
- **Collector**: `selfdrive/clearpilot/telemetryd.py` — diffs against previous state, writes changed values to CSV
- **Toggle**: `TelemetryEnabled` memory param, controlled from Debug panel in ClearPilot menu
- **Auto-disable**: disabled on every manager start; disabled if `/data` free < 5GB
- **Hyundai CAN-FD data**: logged from `selfdrive/car/hyundai/carstate.py` `update_canfd()` — groups: `car`, `cruise`, `speed_limit`, `buttons`
- **GPS data**: logged directly by telemetryd via cereal `gpsLocation` subscription at 1Hz — group: `gps` (latitude, longitude, speed, altitude, bearing, accuracy)
- **CSV location**: `/data/log2/current/telemetry.csv` (or session directory)
- **Onroad overlay**: when telemetry enabled, status bar shows temp, fan %, model FPS, and STANDSTILL indicator
- **Speed limit**: processed by `selfdrive/clearpilot/speed_logic.py` (SpeedState class), converts m/s to display units, writes to memory params. Cruise warning signs appear when cruise set speed exceeds speed limit by threshold (10 mph if limit >= 50, 7 mph if < 50) or is 5+ mph under. Ding sound plays when warning sign appears or speed limit changes while visible (30s cooldown)
### Key Dependencies
- **Python 3.11** (via pyenv) with: numpy, casadi, onnx/onnxruntime, pycapnp, pyzmq, sentry-sdk, sympy, Cython
- **capnp (Cap'n Proto)** — IPC message serialization between all processes
- **ZeroMQ** — IPC transport layer
- **Qt 5** — UI framework (with WebEngine available but not used for rotation reasons)
- **OpenMAX (OMX)** — hardware video encoding
- **libavformat** — MP4 container muxing
- **libyuv** — color space conversion
- **SCons** — build system for native C++ components
+49
View File
@@ -0,0 +1,49 @@
# Dashcam Project
## Status
### Completed (2026-04-11)
- Disabled comma training data video encoding (`encoderd`) — CAN/sensor logs still recorded
- Re-enabled FrogPilot OMX screen recorder (H.264 MP4, 1440x720, 2Mbps, hardware encoded)
- Auto-start/stop recording tied to car ignition (`scene.started`)
- `ScreenRecorderDebug` param for bench testing without car connected
- Hidden all recorder UI elements — invisible to driver
- Videos saved to `/data/media/0/videos/YYYYMMDD-HHMMSS.mp4`, 3-minute segments
- Deleter updated: 9 GB free space threshold, rotates oldest videos first
- Cleaned up offroad UI: replaced stock home screen with grid launcher (Settings + Dashcam buttons)
### Next: Dashcam Footage Viewer
Build a native Qt widget accessible from the offroad home screen "Dashcam" button.
**Requirements:**
- List MP4 files from `/data/media/0/videos/` sorted newest first
- Tap a file to play it back using Qt Multimedia (`QMediaPlayer` + `QVideoWidget`)
- Only accessible when offroad (car in park or off)
- Back button to return to offroad home
- No rotation hacks needed — native Qt widget in existing UI tree handles rotation correctly
**Architecture:**
- New widget class (e.g. `DashcamViewer`) added to `selfdrive/ui/qt/`
- Wire into `HomeWindow`'s `QStackedLayout` alongside `home`, `onroad`, `ready`, `driver_view`
- Dashcam button in `OffroadHome` switches `slayout` to the viewer
- Viewer has a file list view and a playback view (sub-stacked layout)
- Back button returns to `OffroadHome`
- Build: add to `qt_src` list in `selfdrive/ui/SConscript`, link `Qt5Multimedia`
**Previous webview attempts (abandoned):**
- Brian tried QWebEngineView for browser-based playback but the WebEngine subprocess renders independently of Qt's widget tree
- Screen rotation (`view.rotate(90)`, Wayland `wl_surface_set_buffer_transform`) did not work for WebEngine content
- Native Qt widget approach avoids this problem entirely
## Key Files
| File | Role |
|------|------|
| `selfdrive/frogpilot/screenrecorder/screenrecorder.cc` | Recording logic, auto-start/stop |
| `selfdrive/frogpilot/screenrecorder/omx_encoder.cc` | OMX H.264 hardware encoder |
| `selfdrive/ui/qt/onroad.cc` | Timer driving frame capture |
| `selfdrive/ui/qt/home.cc` | Offroad home with Dashcam button |
| `system/loggerd/deleter.py` | Storage rotation |
| `/data/media/0/videos/` | Video output directory |
+46
View File
@@ -0,0 +1,46 @@
# ClearPilot — Feature Goals
Each goal below will be discussed in detail before implementation. Background and specifics to be provided by Brian when we get to each item.
## Dashcam
- [ ] **Dashcam viewer** — on-screen Qt widget for browsing and playing back recorded footage from the offroad home screen (Dashcam button already placed). See `DASHCAM_PROJECT.md` for architecture notes.
- [ ] **Dashcam uploader** — upload footage to a remote server or cloud storage
- [ ] **GPS + speed overlay on dashcam footage** — embed GPS coordinates and vehicle speed into the video stream or as metadata
- [ ] **Dashcam footage archive** — option to mark a trip's footage as archived (kept in storage but hidden from the main UI)
- [ ] **Suspend dashcam / route recording** — on-screen setting to pause recording for a trip and delete footage of the current trip so far (privacy mode)
## Driving Alerts & Safety
- [ ] **Chirp on speed change and over speed limit** — audible alert when speed limit changes or vehicle exceeds the limit
- [ ] **Warn on traffic standstill ahead** — alert when approaching cars ahead too quickly (closing distance warning)
- [ ] **On-screen current speed limit** — display the speed limit as reported by the car's CAN data
- [ ] **Fix on-screen speed value for MPH** — correct the speed display to use the proper value for MPH conversion
## Cruise Control & Driving State
- [ ] **Auto-set speed via CAN bus** — simulate pressing speed up/down buttons on CAN bus to automatically set cruise to the correct speed via UI interaction (stretch goal)
- [ ] **Fix engaged-while-braking state sync** — if openpilot is engaged while brakes are pressed, the system thinks it's active but the car isn't actually in cruise control, causing a sync error that should be recoverable
- [ ] **Fix resume-cruise lateral mode bug** — pressing resume cruise control (rather than enable) causes the car to enter a state where it thinks it's in always-on lateral mode and disables driver monitoring
- [ ] **Lateral assist in turn lanes** — keep lateral assist active when using turn signal in a turn lane (at low/turning speeds) as opposed to cruising speeds, where lateral currently disengages
## Driver Monitoring
- [ ] **Disable driver monitoring on demand** — add a technique to disable DM for 2 minutes via a button or gesture
- [ ] **Hands-on-wheel mode** — add a setting requiring the driver to keep hands on the wheel (configurable via settings)
## UI Modes & Display
- [ ] **Curves-only UI mode** — show only on-screen curve/path depictions without the camera feed (reduces visual clutter, saves processing)
- [ ] **Night mode auto-display-off** — turn off display if device starts at night (determine sunset for current location/datetime or use ambient light levels from car sensors)
- [ ] **Update boot/offroad splash logos** — replace the red pac-man ghost with a blue pac-man ghost for boot and offroad full-screen splash
- [ ] **Dashcam-only reboot mode** — on-screen option to reboot into a mode that provides no driver assist (reverts to stock OEM lane assist) but keeps dashcam running. For lending the car to friends who shouldn't use comma's driving features.
## Connectivity & Data
- [ ] **Offroad weather report screen** — weather display accessible from the offroad home grid (depends on internet connection)
- [ ] **Fix GPS tracking** — GPS tracking feature currently broken, processes commented out in process_config
## Vehicle-Specific (Hyundai Tucson HDA2)
- [ ] **Warn if panoramic roof is open** — if possible to intercept window/roof state from CAN bus, warn when the top roof is left open when the car is turned off
+1
View File
@@ -121,6 +121,7 @@ def objcopy(source, target, env, for_signature):
return '$OBJCOPY -O binary %s %s' % (source[0], target[0]) return '$OBJCOPY -O binary %s %s' % (source[0], target[0])
# Common autogenerated includes # Common autogenerated includes
os.makedirs("obj", exist_ok=True)
git_ver = get_version(BUILDER, BUILD_TYPE) git_ver = get_version(BUILDER, BUILD_TYPE)
with open("obj/gitversion.h", "w") as f: with open("obj/gitversion.h", "w") as f:
f.write(f'const uint8_t gitversion[8] = "{git_ver}";\n') f.write(f'const uint8_t gitversion[8] = "{git_ver}";\n')
+1 -3
View File
@@ -35,6 +35,4 @@ source "$BASEDIR/build_preflight.sh"
cd "$BASEDIR/selfdrive/manager" cd "$BASEDIR/selfdrive/manager"
rm -f "$BASEDIR/prebuilt" rm -f "$BASEDIR/prebuilt"
# Tee output to /tmp/build.log for inspection after the script exits BUILD_ONLY=1 exec ./build.py
BUILD_ONLY=1 ./build.py 2>&1 | tee /tmp/build.log
exit "${PIPESTATUS[0]}"
+3
View File
@@ -12,6 +12,9 @@ struct FrogPilotCarControl @0x81c2f05a394cf4af {
alwaysOnLateral @0 :Bool; alwaysOnLateral @0 :Bool;
speedLimitChanged @1 :Bool; speedLimitChanged @1 :Bool;
trafficModeActive @2 :Bool; trafficModeActive @2 :Bool;
# CLEARPILOT: migrated from paramsMemory to avoid file-read syscalls in modeld/UI/carcontroller
latRequested @3 :Bool; # controlsd's request to enable lat before ramp-up delay
noLatLaneChange @4 :Bool; # lat is temporarily suppressed during a lane change
} }
struct FrogPilotCarState @0xaedffd8f31e7b55d { struct FrogPilotCarState @0xaedffd8f31e7b55d {
+3 -3
View File
@@ -30,7 +30,7 @@ services: dict[str, tuple] = {
"temperatureSensor": (True, 2., 200), "temperatureSensor": (True, 2., 200),
"temperatureSensor2": (True, 2., 200), "temperatureSensor2": (True, 2., 200),
"gpsNMEA": (True, 9.), "gpsNMEA": (True, 9.),
"deviceState": (True, 2., 1), "deviceState": (True, 5., 1), # CLEARPILOT: 5Hz — thermald decimates pandaStates (10Hz) every 2 ticks
"can": (True, 100., 1223), # decimation gives ~5 msgs in a full segment "can": (True, 100., 1223), # decimation gives ~5 msgs in a full segment
"controlsState": (True, 100., 10), "controlsState": (True, 100., 10),
"pandaStates": (True, 10., 1), "pandaStates": (True, 10., 1),
@@ -50,7 +50,7 @@ services: dict[str, tuple] = {
"longitudinalPlan": (True, 20., 5), "longitudinalPlan": (True, 20., 5),
"procLog": (True, 0.5, 15), "procLog": (True, 0.5, 15),
"gpsLocationExternal": (True, 10., 10), "gpsLocationExternal": (True, 10., 10),
"gpsLocation": (True, 1., 1), "gpsLocation": (True, 2., 1), # CLEARPILOT: 2Hz (was 1Hz) — gpsd polls at 2Hz
"ubloxGnss": (True, 10.), "ubloxGnss": (True, 10.),
"qcomGnss": (True, 2.), "qcomGnss": (True, 2.),
"gnssMeasurements": (True, 10., 10), "gnssMeasurements": (True, 10., 10),
@@ -70,7 +70,7 @@ services: dict[str, tuple] = {
"wideRoadEncodeIdx": (False, 20., 1), "wideRoadEncodeIdx": (False, 20., 1),
"wideRoadCameraState": (True, 20., 20), "wideRoadCameraState": (True, 20., 20),
"modelV2": (True, 20., 40), "modelV2": (True, 20., 40),
"managerState": (True, 2., 1), "managerState": (True, 5., 1), # CLEARPILOT: 5Hz — gated by deviceState arrival (see thermald)
"uploaderState": (True, 0., 1), "uploaderState": (True, 0., 1),
"navInstruction": (True, 1., 10), "navInstruction": (True, 1., 10),
"navRoute": (True, 0.), "navRoute": (True, 0.),
+31 -4
View File
@@ -109,6 +109,9 @@ std::unordered_map<std::string, uint32_t> keys = {
{"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION},
{"CurrentBootlog", PERSISTENT}, {"CurrentBootlog", PERSISTENT},
{"CurrentRoute", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"CurrentRoute", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION},
{"DashcamFrames", PERSISTENT},
{"DashcamState", PERSISTENT},
{"DashcamShutdown", CLEAR_ON_MANAGER_START},
{"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION},
{"DisablePowerDown", PERSISTENT}, {"DisablePowerDown", PERSISTENT},
{"DisableUpdates", PERSISTENT}, {"DisableUpdates", PERSISTENT},
@@ -158,6 +161,7 @@ std::unordered_map<std::string, uint32_t> keys = {
{"LastUpdateTime", PERSISTENT}, {"LastUpdateTime", PERSISTENT},
{"LiveParameters", PERSISTENT}, {"LiveParameters", PERSISTENT},
{"LiveTorqueParameters", PERSISTENT | DONT_LOG}, {"LiveTorqueParameters", PERSISTENT | DONT_LOG},
{"LogDirInitialized", CLEAR_ON_MANAGER_START},
{"LongitudinalPersonality", PERSISTENT}, {"LongitudinalPersonality", PERSISTENT},
{"NavDestination", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"NavDestination", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION},
{"NavDestinationWaypoints", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"NavDestinationWaypoints", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION},
@@ -189,12 +193,18 @@ std::unordered_map<std::string, uint32_t> keys = {
{"RecordFrontLock", PERSISTENT}, // for the internal fleet {"RecordFrontLock", PERSISTENT}, // for the internal fleet
{"ReplayControlsState", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"ReplayControlsState", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION},
{"RouteCount", PERSISTENT}, {"RouteCount", PERSISTENT},
{"ShutdownTouchReset", PERSISTENT},
{"SnoozeUpdate", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"SnoozeUpdate", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION},
{"SshEnabled", PERSISTENT}, {"SshEnabled", PERSISTENT},
{"TermsVersion", PERSISTENT}, {"TermsVersion", PERSISTENT},
{"TelemetryEnabled", PERSISTENT},
{"Timezone", PERSISTENT}, {"Timezone", PERSISTENT},
{"TrainingVersion", PERSISTENT}, {"TrainingVersion", PERSISTENT},
{"ModelFps", PERSISTENT},
{"ModelStandby", PERSISTENT},
{"ModelStandbyTs", PERSISTENT},
{"UbloxAvailable", PERSISTENT}, {"UbloxAvailable", PERSISTENT},
{"VpnEnabled", PERSISTENT},
{"UpdateAvailable", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"UpdateAvailable", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION},
{"UpdateFailedCount", CLEAR_ON_MANAGER_START}, {"UpdateFailedCount", CLEAR_ON_MANAGER_START},
{"UpdaterAvailableBranches", PERSISTENT}, {"UpdaterAvailableBranches", PERSISTENT},
@@ -210,6 +220,13 @@ std::unordered_map<std::string, uint32_t> keys = {
// FrogPilot parameters // FrogPilot parameters
{"AccelerationPath", PERSISTENT}, {"AccelerationPath", PERSISTENT},
{"BenchCruiseActive", CLEAR_ON_MANAGER_START},
{"BenchCruiseSpeed", CLEAR_ON_MANAGER_START},
{"ClpUiState", CLEAR_ON_MANAGER_START},
{"BenchEngaged", CLEAR_ON_MANAGER_START},
{"BenchGear", CLEAR_ON_MANAGER_START},
{"BenchSpeed", CLEAR_ON_MANAGER_START},
{"BenchSpeedLimit", CLEAR_ON_MANAGER_START},
{"AccelerationProfile", PERSISTENT}, {"AccelerationProfile", PERSISTENT},
{"AdjacentPath", PERSISTENT}, {"AdjacentPath", PERSISTENT},
{"AdjacentPathMetrics", PERSISTENT}, {"AdjacentPathMetrics", PERSISTENT},
@@ -232,17 +249,27 @@ std::unordered_map<std::string, uint32_t> keys = {
{"CarMake", PERSISTENT}, {"CarMake", PERSISTENT},
{"CarModel", PERSISTENT}, {"CarModel", PERSISTENT},
{"CarCruiseDisplayActual", PERSISTENT},
{"CarSpeedLimit", PERSISTENT}, {"CarSpeedLimit", PERSISTENT},
{"CarSpeedLimitWarning", PERSISTENT}, {"CarSpeedLimitWarning", PERSISTENT},
{"CarSpeedLimitLiteral", PERSISTENT}, {"CarSpeedLimitLiteral", PERSISTENT},
{"CarIsMetric", PERSISTENT},
{"ClearpilotSpeedDisplay", PERSISTENT},
{"ClearpilotSpeedLimitDisplay", PERSISTENT},
{"ClearpilotHasSpeed", PERSISTENT},
{"ClearpilotIsMetric", PERSISTENT},
{"ClearpilotSpeedUnit", PERSISTENT},
{"ClearpilotCruiseWarning", PERSISTENT},
{"ClearpilotCruiseWarningSpeed", PERSISTENT},
{"ClearpilotPlayDing", PERSISTENT},
// {"SpeedLimitLatDesired", PERSISTENT}, // {"SpeedLimitLatDesired", PERSISTENT},
// {"SpeedLimitVTSC", PERSISTENT}, // {"SpeedLimitVTSC", PERSISTENT},
{"CPTLkasButtonAction", PERSISTENT}, {"CPTLkasButtonAction", PERSISTENT},
{"ScreenDisplayMode", PERSISTENT}, {"IsDaylight", CLEAR_ON_MANAGER_START},
{"ScreenDisplayMode", CLEAR_ON_MANAGER_START},
{"RadarDist", PERSISTENT}, {"RadarDist", PERSISTENT},
{"ModelDist", PERSISTENT}, {"ModelDist", PERSISTENT},
@@ -263,6 +290,7 @@ std::unordered_map<std::string, uint32_t> keys = {
{"CEStopLights", PERSISTENT}, {"CEStopLights", PERSISTENT},
{"CEStopLightsLead", PERSISTENT}, {"CEStopLightsLead", PERSISTENT},
{"Compass", PERSISTENT}, {"Compass", PERSISTENT},
{"ClearpilotShowHealthMetrics", PERSISTENT},
{"ConditionalExperimental", PERSISTENT}, {"ConditionalExperimental", PERSISTENT},
{"CrosstrekTorque", PERSISTENT}, {"CrosstrekTorque", PERSISTENT},
{"CurrentHolidayTheme", PERSISTENT}, {"CurrentHolidayTheme", PERSISTENT},
@@ -416,6 +444,7 @@ std::unordered_map<std::string, uint32_t> keys = {
{"ScreenBrightnessOnroad", PERSISTENT}, {"ScreenBrightnessOnroad", PERSISTENT},
{"ScreenManagement", PERSISTENT}, {"ScreenManagement", PERSISTENT},
{"ScreenRecorder", PERSISTENT}, {"ScreenRecorder", PERSISTENT},
{"ScreenRecorderDebug", PERSISTENT},
{"ScreenTimeout", PERSISTENT}, {"ScreenTimeout", PERSISTENT},
{"ScreenTimeoutOnroad", PERSISTENT}, {"ScreenTimeoutOnroad", PERSISTENT},
{"SearchInput", PERSISTENT}, {"SearchInput", PERSISTENT},
@@ -479,8 +508,6 @@ std::unordered_map<std::string, uint32_t> keys = {
{"WheelIcon", PERSISTENT}, {"WheelIcon", PERSISTENT},
{"WheelSpeed", PERSISTENT}, {"WheelSpeed", PERSISTENT},
// Clearpilot
{"no_lat_lane_change", PERSISTENT},
}; };
} // namespace } // namespace
+1 -1
View File
@@ -12,7 +12,7 @@ from openpilot.system.hardware import PC
# time step for each process # time step for each process
DT_CTRL = 0.01 # controlsd DT_CTRL = 0.01 # controlsd
DT_MDL = 0.05 # model DT_MDL = 0.05 # model
DT_TRML = 0.5 # thermald and manager DT_TRML = 0.25 # thermald and manager — 4 Hz
DT_DMON = 0.05 # driver monitoring DT_DMON = 0.05 # driver monitoring
-6
View File
@@ -15,12 +15,6 @@ pkill -9 -f './ui' 2>/dev/null
pkill -9 -f 'selfdrive/ui/text' 2>/dev/null pkill -9 -f 'selfdrive/ui/text' 2>/dev/null
sleep 1 sleep 1
# CLEARPILOT: ensure params persistence dir is owned by comma:comma. Editing
# the tree as root leaves files owned by root in /data/params/d_tmp/, and
# Params writes done as comma will then EACCES on rename. Reset on every
# launch so this never silently breaks again.
sudo chown -R comma:comma /data/params
bash /data/openpilot/system/clearpilot/on_start.sh bash /data/openpilot/system/clearpilot/on_start.sh
# CLEARPILOT: start VPN monitor (kills previous instances, runs as root) # CLEARPILOT: start VPN monitor (kills previous instances, runs as root)
+1 -12
View File
@@ -1,17 +1,7 @@
----- -----
- fix debug notice message - screen off on lkas
- screen mode 1 = no UI, screen mode 2 = off
- speed limit change chirp on cruise - speed limit change chirp on cruise
- fix always on detection, change message
-----
- Better debugger and data recorder
- Represent distance to lead car on primary UI
- Start testing for alert when stopped traffic and approaching > 31 mph
- or not enough time to slow at 31
- special experimental mode override?
----- -----
@@ -21,7 +11,6 @@
- better turning logic - better turning logic
- new settings UI - new settings UI
- experimental mode - experimental mode
- resume from stop
------------ ------------
+1
View File
@@ -166,6 +166,7 @@ Export('base_project_f4', 'base_project_h7', 'build_project')
# Common autogenerated includes # Common autogenerated includes
os.makedirs("board/obj", exist_ok=True)
with open("board/obj/gitversion.h", "w") as f: with open("board/obj/gitversion.h", "w") as f:
f.write(f'const uint8_t gitversion[] = "{get_version(BUILDER, BUILD_TYPE)}";\n') f.write(f'const uint8_t gitversion[] = "{get_version(BUILDER, BUILD_TYPE)}";\n')
+1
View File
@@ -4,3 +4,4 @@ SConscript(['controls/lib/longitudinal_mpc_lib/SConscript'])
SConscript(['locationd/SConscript']) SConscript(['locationd/SConscript'])
SConscript(['modeld/SConscript']) SConscript(['modeld/SConscript'])
SConscript(['ui/SConscript']) SConscript(['ui/SConscript'])
SConscript(['clearpilot/SConscript'])
+3 -1
View File
@@ -32,7 +32,9 @@ def main():
continue continue
cloudlog.info("starting athena daemon") cloudlog.info("starting athena daemon")
proc = Process(name='athenad', target=launcher, args=('selfdrive.athena.athenad', 'athenad')) from openpilot.selfdrive.manager.process import _log_dir
log_path = _log_dir + "/athenad.log"
proc = Process(name='athenad', target=launcher, args=('selfdrive.athena.athenad', 'athenad', log_path))
proc.start() proc.start()
proc.join() proc.join()
cloudlog.event("athenad exited", exitcode=proc.exitcode) cloudlog.event("athenad exited", exitcode=proc.exitcode)
+4 -2
View File
@@ -8,7 +8,6 @@ from openpilot.selfdrive.car.hyundai import hyundaicanfd, hyundaican
from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus
from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR
from openpilot.selfdrive.car.interfaces import CarControllerBase from openpilot.selfdrive.car.interfaces import CarControllerBase
from openpilot.common.params import Params
VisualAlert = car.CarControl.HUDControl.VisualAlert VisualAlert = car.CarControl.HUDControl.VisualAlert
LongCtrlState = car.CarControl.Actuators.LongControlState LongCtrlState = car.CarControl.Actuators.LongControlState
@@ -57,6 +56,7 @@ class CarController(CarControllerBase):
self.car_fingerprint = CP.carFingerprint self.car_fingerprint = CP.carFingerprint
self.last_button_frame = 0 self.last_button_frame = 0
def update(self, CC, CS, now_nanos, frogpilot_variables): def update(self, CC, CS, now_nanos, frogpilot_variables):
actuators = CC.actuators actuators = CC.actuators
hud_control = CC.hudControl hud_control = CC.hudControl
@@ -112,7 +112,9 @@ class CarController(CarControllerBase):
hda2_long = hda2 and self.CP.openpilotLongitudinalControl hda2_long = hda2 and self.CP.openpilotLongitudinalControl
# steering control # steering control
can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, self.CAN, CC.enabled, apply_steer_req, apply_steer)) # CLEARPILOT: no_lat_lane_change comes via frogpilot_variables (set by controlsd in-process)
no_lat_lane_change = int(getattr(frogpilot_variables, 'no_lat_lane_change', False))
can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, self.CAN, CC.enabled, apply_steer_req, apply_steer, no_lat_lane_change))
# prevent LFA from activating on HDA2 by sending "no lane lines detected" to ADAS ECU # prevent LFA from activating on HDA2 by sending "no lane lines detected" to ADAS ECU
if self.frame % 5 == 0 and hda2: if self.frame % 5 == 0 and hda2:
+30 -7
View File
@@ -13,6 +13,7 @@ from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus
from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CAN_GEARS, CAMERA_SCC_CAR, \ from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CAN_GEARS, CAMERA_SCC_CAR, \
CANFD_CAR, Buttons, CarControllerParams CANFD_CAR, Buttons, CarControllerParams
from openpilot.selfdrive.car.interfaces import CarStateBase from openpilot.selfdrive.car.interfaces import CarStateBase
from openpilot.selfdrive.clearpilot.telemetry import tlog
PREV_BUTTON_SAMPLES = 8 PREV_BUTTON_SAMPLES = 8
CLUSTER_SAMPLE_RATE = 20 # frames CLUSTER_SAMPLE_RATE = 20 # frames
@@ -47,6 +48,10 @@ class CarState(CarStateBase):
self.is_metric = False self.is_metric = False
self.buttons_counter = 0 self.buttons_counter = 0
# CLEARPILOT: cache to avoid per-cycle atomic writes to /dev/shm (eats CPU via fsync/flock)
self._prev_car_speed_limit = None
self._prev_car_is_metric = None
self.cruise_info = {} self.cruise_info = {}
# On some cars, CLU15->CF_Clu_VehicleSpeed can oscillate faster than the dash updates. Sample at 5 Hz # On some cars, CLU15->CF_Clu_VehicleSpeed can oscillate faster than the dash updates. Sample at 5 Hz
@@ -209,9 +214,14 @@ class CarState(CarStateBase):
self.lkas_previously_enabled = self.lkas_enabled self.lkas_previously_enabled = self.lkas_enabled
self.lkas_enabled = cp.vl["BCM_PO_11"]["LFA_Pressed"] self.lkas_enabled = cp.vl["BCM_PO_11"]["LFA_Pressed"]
# self.params_memory.put_int("CarSpeedLimitLiteral", self.calculate_speed_limit(cp, cp_cam)) # CLEARPILOT: gate on change — see same fix in update_canfd
self.params_memory.put_float("CarSpeedLimit", self.calculate_speed_limit(cp, cp_cam) * speed_conv) car_speed_limit = self.calculate_speed_limit(cp, cp_cam) * speed_conv
self.params_memory.put_float("CarCruiseDisplayActual", cp_cruise.vl["SCC11"]["VSetDis"]) if car_speed_limit != self._prev_car_speed_limit:
self.params_memory.put_float("CarSpeedLimit", car_speed_limit)
self._prev_car_speed_limit = car_speed_limit
if self.is_metric != self._prev_car_is_metric:
self.params_memory.put("CarIsMetric", "1" if self.is_metric else "0")
self._prev_car_is_metric = self.is_metric
return ret return ret
@@ -415,10 +425,23 @@ class CarState(CarStateBase):
# nonAdaptive = false, # nonAdaptive = false,
# speedCluster = 0 ) # speedCluster = 0 )
# print("Set limit") # CLEARPILOT: gate on change — these writes run 100Hz, each is an atomic fsync/flock transaction
# print(self.calculate_speed_limit(cp, cp_cam)) car_speed_limit = self.calculate_speed_limit(cp, cp_cam) * speed_factor
# self.params_memory.put_float("CarSpeedLimitLiteral", self.calculate_speed_limit(cp, cp_cam)) if car_speed_limit != self._prev_car_speed_limit:
self.params_memory.put_float("CarSpeedLimit", self.calculate_speed_limit(cp, cp_cam) * speed_factor) self.params_memory.put_float("CarSpeedLimit", car_speed_limit)
self._prev_car_speed_limit = car_speed_limit
if self.is_metric != self._prev_car_is_metric:
self.params_memory.put("CarIsMetric", "1" if self.is_metric else "0")
self._prev_car_is_metric = self.is_metric
# CLEARPILOT: telemetry logging — disabled, re-enable when needed
# speed_limit_bus = cp if self.CP.flags & HyundaiFlags.CANFD_HDA2 else cp_cam
# scc = cp_cam.vl["SCC_CONTROL"] if self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC else cp.vl["SCC_CONTROL"]
# cluster = speed_limit_bus.vl["CLUSTER_SPEED_LIMIT"]
# tlog("car", { ... })
# tlog("cruise", { ... })
# tlog("speed_limit", { ... })
# tlog("buttons", { ... })
return ret return ret
+3 -9
View File
@@ -2,7 +2,6 @@ from openpilot.common.numpy_fast import clip
from openpilot.selfdrive.car import CanBusBase from openpilot.selfdrive.car import CanBusBase
from openpilot.selfdrive.car.hyundai.values import HyundaiFlags from openpilot.selfdrive.car.hyundai.values import HyundaiFlags
from openpilot.common.params import Params
class CanBus(CanBusBase): class CanBus(CanBusBase):
def __init__(self, CP, hda2=None, fingerprint=None) -> None: def __init__(self, CP, hda2=None, fingerprint=None) -> None:
@@ -36,12 +35,9 @@ class CanBus(CanBusBase):
return self._cam return self._cam
def create_steering_messages(packer, CP, CAN, enabled, lat_active, apply_steer): def create_steering_messages(packer, CP, CAN, enabled, lat_active, apply_steer, no_lat_lane_change=0):
# CLEARPILOT: no_lat_lane_change is passed in by the caller so we can hoist
# Im sure there is a better way to do this # the Params read out of the 100Hz hot path (was ~5% of carcontroller time)
params_memory = Params("/dev/shm/params")
no_lat_lane_change = params_memory.get_int("no_lat_lane_change", 1)
ret = [] ret = []
values = { values = {
@@ -130,8 +126,6 @@ def create_buttons(packer, CP, CAN, cnt, btn):
def create_buttons_alt(packer, CP, CAN, cnt, btn, template): def create_buttons_alt(packer, CP, CAN, cnt, btn, template):
return return
params_memory = Params("/dev/shm/params")
CarCruiseDisplayActual = params_memory.get_float("CarCruiseDisplayActual")
values = { values = {
"COUNTER": cnt, "COUNTER": cnt,
+9
View File
@@ -484,10 +484,19 @@ class CarInterfaceBase(ABC):
self.silent_steer_warning = True self.silent_steer_warning = True
events.add(EventName.steerTempUnavailableSilent) events.add(EventName.steerTempUnavailableSilent)
else: else:
# CLEARPILOT: log once per instance of this warning
if not getattr(self, '_steer_fault_logged', False):
import sys
print(f"CLP steerTempUnavailable: steerFaultTemporary={cs_out.steerFaultTemporary} "
f"steeringPressed={cs_out.steeringPressed} standstill={cs_out.standstill} "
f"steering_unpressed={self.steering_unpressed} steeringAngleDeg={cs_out.steeringAngleDeg:.1f} "
f"steeringTorque={cs_out.steeringTorque:.1f} vEgo={cs_out.vEgo:.2f}", file=sys.stderr)
self._steer_fault_logged = True
events.add(EventName.steerTempUnavailable) events.add(EventName.steerTempUnavailable)
else: else:
self.no_steer_warning = False self.no_steer_warning = False
self.silent_steer_warning = False self.silent_steer_warning = False
self._steer_fault_logged = False
if cs_out.steerFaultPermanent: if cs_out.steerFaultPermanent:
events.add(EventName.steerUnavailable) events.add(EventName.steerUnavailable)
+16
View File
@@ -0,0 +1,16 @@
Import('env', 'arch', 'common', 'messaging', 'visionipc', 'cereal')
clearpilot_env = env.Clone()
clearpilot_env['CPPPATH'] += ['#selfdrive/frogpilot/screenrecorder/openmax/include/']
# Disable --as-needed so static lib ordering doesn't matter
clearpilot_env['LINKFLAGS'] = [f for f in clearpilot_env.get('LINKFLAGS', []) if f != '-Wl,--as-needed']
if arch == "larch64":
omx_obj = File('#selfdrive/frogpilot/screenrecorder/omx_encoder.o')
clearpilot_env.Program(
'dashcamd',
['dashcamd.cc', omx_obj],
LIBS=[common, 'json11', cereal, visionipc, messaging,
'zmq', 'capnp', 'kj', 'm', 'OpenCL', 'ssl', 'crypto', 'pthread',
'OmxCore', 'avformat', 'avcodec', 'avutil', 'yuv']
)
+147
View File
@@ -0,0 +1,147 @@
#!/usr/bin/env python3
"""
ClearPilot bench command tool. Sets bench params and queries UI state.
Usage:
python3 -m selfdrive.clearpilot.bench_cmd gear D
python3 -m selfdrive.clearpilot.bench_cmd speed 20
python3 -m selfdrive.clearpilot.bench_cmd speedlimit 45
python3 -m selfdrive.clearpilot.bench_cmd cruise 55
python3 -m selfdrive.clearpilot.bench_cmd cruiseactive 0|1|2 (0=disabled, 1=active, 2=paused)
python3 -m selfdrive.clearpilot.bench_cmd engaged 1
python3 -m selfdrive.clearpilot.bench_cmd ding (trigger speed limit ding sound)
python3 -m selfdrive.clearpilot.bench_cmd debugbutton (simulate LKAS debug button press)
python3 -m selfdrive.clearpilot.bench_cmd dump
python3 -m selfdrive.clearpilot.bench_cmd wait_ready
"""
import os
import subprocess
import sys
import time
import zmq
from openpilot.common.params import Params
def check_ui_process():
"""Check if UI process is running and healthy. Returns error string or None if OK."""
try:
result = subprocess.run(["pgrep", "-a", "-f", "./ui"], capture_output=True, text=True)
if result.returncode != 0:
return "ERROR: UI process not running"
# Get the PID and check its uptime
for line in result.stdout.strip().split("\n"):
parts = line.split(None, 1)
if len(parts) >= 2 and "./ui" in parts[1]:
pid = parts[0]
try:
stat = os.stat(f"/proc/{pid}")
uptime = time.time() - stat.st_mtime
if uptime < 5:
return f"ERROR: UI process (pid {pid}) uptime {uptime:.1f}s — likely crash looping. Check: tail /data/log2/$(ls -t /data/log2/ | head -1)/session.log"
except FileNotFoundError:
return "ERROR: UI process disappeared"
except Exception:
pass
return None
def ui_dump():
ctx = zmq.Context()
sock = ctx.socket(zmq.REQ)
sock.setsockopt(zmq.RCVTIMEO, 2000)
sock.connect("ipc:///tmp/clearpilot_ui_rpc")
sock.send_string("dump")
try:
return sock.recv_string()
except zmq.Again:
return None
finally:
sock.close()
ctx.term()
def wait_ready(timeout=20):
"""Wait until the UI shows ReadyWindow, up to timeout seconds."""
start = time.time()
while time.time() - start < timeout:
dump = ui_dump()
if dump and "ReadyWindow" in dump:
# Check it's actually visible
for line in dump.split("\n"):
if "ReadyWindow" in line and "vis=Y" in line:
print("UI ready (ReadyWindow visible)")
return True
time.sleep(1)
print(f"ERROR: UI not ready after {timeout}s")
if dump:
print(dump)
return False
def main():
if len(sys.argv) < 2:
print(__doc__)
return
cmd = sys.argv[1].lower()
params = Params("/dev/shm/params")
param_map = {
"gear": "BenchGear",
"speed": "BenchSpeed",
"speedlimit": "BenchSpeedLimit",
"cruise": "BenchCruiseSpeed",
"cruiseactive": "BenchCruiseActive",
"engaged": "BenchEngaged",
}
if cmd == "dump":
ui_status = check_ui_process()
if ui_status:
print(ui_status)
else:
result = ui_dump()
if result:
print(result)
else:
print("ERROR: UI not responding")
elif cmd == "wait_ready":
wait_ready()
elif cmd == "ding":
params.put("ClearpilotPlayDing", "1")
print("Ding triggered")
elif cmd == "debugbutton":
# Simulate LKAS debug button — same state machine as controlsd.clearpilot_state_control()
current = params.get_int("ScreenDisplayMode")
gear = (params.get("BenchGear") or b"P").decode().strip().upper()
in_drive = gear in ("D", "S", "L")
if in_drive:
transitions = {0: 4, 1: 2, 2: 3, 3: 4, 4: 2}
new_mode = transitions.get(current, 0)
else:
new_mode = 0 if current == 3 else 3
params.put_int("ScreenDisplayMode", new_mode)
mode_names = {0: "auto-normal", 1: "auto-nightrider", 2: "normal", 3: "screen-off", 4: "nightrider"}
print(f"ScreenDisplayMode: {current} ({mode_names.get(current, '?')}) → {new_mode} ({mode_names.get(new_mode, '?')})"
f" [gear={gear}, in_drive={in_drive}]")
elif cmd in param_map:
if len(sys.argv) < 3:
print(f"Usage: bench_cmd {cmd} <value>")
return
value = sys.argv[2]
params.put(param_map[cmd], value)
print(f"{param_map[cmd]} = {value}")
else:
print(f"Unknown command: {cmd}")
print(__doc__)
if __name__ == "__main__":
main()
+137
View File
@@ -0,0 +1,137 @@
#!/usr/bin/env python3
"""
ClearPilot bench onroad simulator.
Publishes fake messages to make the UI go onroad and display
configurable vehicle state. Control values via params in /dev/shm/params:
BenchSpeed - vehicle speed in mph (default: 0)
BenchSpeedLimit - speed limit in mph (default: 0, 0=hidden)
BenchCruiseSpeed - cruise set speed in mph (default: 0, 0=not set)
BenchCruiseActive - 0=disabled, 1=active, 2=paused/standstill (default: 0)
BenchGear - P, D, R, N (default: P)
BenchEngaged - 0 or 1, cruise engaged (default: 0)
Usage:
su - comma -c "PYTHONPATH=/data/openpilot python3 -m selfdrive.clearpilot.bench_onroad"
To stop: Ctrl+C or kill the process. UI returns to offroad.
"""
import time
import cereal.messaging as messaging
from cereal import log, car
from openpilot.common.params import Params
from openpilot.common.conversions import Conversions as CV
from openpilot.selfdrive.clearpilot.speed_logic import SpeedState
def main():
params = Params()
params_mem = Params("/dev/shm/params")
# Set defaults
params_mem.put("BenchSpeed", "0")
params_mem.put("BenchSpeedLimit", "0")
params_mem.put("BenchCruiseSpeed", "0")
params_mem.put("BenchCruiseActive", "0")
params_mem.put("BenchGear", "P")
params_mem.put("BenchEngaged", "0")
# ClearPilot speed processing
speed_state = SpeedState()
# thermald handles deviceState (reads our fake pandaStates for ignition)
pm = messaging.PubMaster([
"pandaStates", "carState", "controlsState",
"driverMonitoringState", "liveCalibration",
])
print("Bench onroad simulator started")
print("Set values in /dev/shm/params/d/Bench*")
print(" BenchSpeed=0 BenchSpeedLimit=0 BenchCruiseSpeed=0 BenchGear=P BenchEngaged=0")
gear_map = {
"P": car.CarState.GearShifter.park,
"D": car.CarState.GearShifter.drive,
"R": car.CarState.GearShifter.reverse,
"N": car.CarState.GearShifter.neutral,
}
frame = 0
try:
while True:
# Read bench params
speed_mph = float((params_mem.get("BenchSpeed", encoding="utf-8") or "0").strip())
speed_limit_mph = float((params_mem.get("BenchSpeedLimit", encoding="utf-8") or "0").strip())
cruise_mph = float((params_mem.get("BenchCruiseSpeed", encoding="utf-8") or "0").strip())
gear_str = (params_mem.get("BenchGear", encoding="utf-8") or "P").strip().upper()
cruise_active_str = (params_mem.get("BenchCruiseActive", encoding="utf-8") or "0").strip()
engaged = (params_mem.get("BenchEngaged", encoding="utf-8") or "0").strip() == "1"
speed_ms = speed_mph * CV.MPH_TO_MS
speed_limit_ms = speed_limit_mph * CV.MPH_TO_MS
cruise_ms = cruise_mph * CV.MPH_TO_MS
gear = gear_map.get(gear_str, car.CarState.GearShifter.park)
# Cruise state: 0=disabled, 1=active, 2=paused
cruise_active = cruise_active_str == "1"
cruise_standstill = cruise_active_str == "2"
# ClearPilot speed processing (~2 Hz at 10 Hz loop)
if frame % 5 == 0:
has_speed = speed_mph > 0
speed_state.update(speed_ms, has_speed, speed_limit_ms, is_metric=False,
cruise_speed_ms=cruise_ms, cruise_active=cruise_active or cruise_standstill,
cruise_standstill=cruise_standstill)
# pandaStates — 10 Hz (thermald reads ignition from this)
if frame % 1 == 0:
dat = messaging.new_message("pandaStates", 1)
dat.pandaStates[0].ignitionLine = True
dat.pandaStates[0].pandaType = log.PandaState.PandaType.tres
pm.send("pandaStates", dat)
# carState — 10 Hz
dat = messaging.new_message("carState")
cs = dat.carState
cs.vEgo = speed_ms
cs.vEgoCluster = speed_ms
cs.gearShifter = gear
cs.standstill = speed_ms < 0.1
cs.cruiseState.available = True
cs.cruiseState.enabled = engaged
cs.cruiseState.speed = cruise_mph * CV.MPH_TO_MS if cruise_mph > 0 else 0
pm.send("carState", dat)
# controlsState — 10 Hz
dat = messaging.new_message("controlsState")
ctl = dat.controlsState
ctl.vCruise = cruise_mph * 1.60934 if cruise_mph > 0 else 255 # km/h or 255=not set
ctl.vCruiseCluster = ctl.vCruise
ctl.enabled = engaged
ctl.active = engaged
pm.send("controlsState", dat)
# driverMonitoringState — low freq
if frame % 10 == 0:
dat = messaging.new_message("driverMonitoringState")
dat.driverMonitoringState.isActiveMode = True
pm.send("driverMonitoringState", dat)
# liveCalibration — low freq
if frame % 50 == 0:
dat = messaging.new_message("liveCalibration")
dat.liveCalibration.calStatus = log.LiveCalibrationData.Status.calibrated
dat.liveCalibration.rpyCalib = [0.0, 0.0, 0.0]
pm.send("liveCalibration", dat)
frame += 1
time.sleep(0.1) # 10 Hz base loop
except KeyboardInterrupt:
print("\nBench simulator stopped")
if __name__ == "__main__":
main()
BIN
View File
Binary file not shown.
+409
View File
@@ -0,0 +1,409 @@
/*
* CLEARPILOT dashcamd — records raw camera footage to MP4 using OMX H.264 hardware encoder.
*
* Connects to camerad via VisionIPC, receives NV12 frames, and feeds them directly
* to the Qualcomm OMX encoder. Produces 3-minute MP4 segments organized by trip.
*
* Trip directory structure:
* /data/media/0/videos/YYYYMMDD-HHMMSS/ (trip directory, named at trip start)
* YYYYMMDD-HHMMSS.mp4 (3-minute segments)
* YYYYMMDD-HHMMSS.srt (GPS subtitle sidecar)
*
* Trip lifecycle state machine:
*
* WAITING:
* - Process starts in this state
* - Waits for valid system time (year >= 2024) AND car in drive gear
* - Transitions to RECORDING when both conditions met
*
* RECORDING:
* - Actively encoding frames, car is in drive
* - Car leaves drive → start 10-min idle timer → IDLE_TIMEOUT
*
* IDLE_TIMEOUT:
* - Car left drive, still recording with timer running
* - Car re-enters drive → cancel timer → RECORDING
* - Timer expires → close trip → WAITING
* - Ignition off → close trip → WAITING
*
* Graceful shutdown (DashcamShutdown param):
* - thermald sets DashcamShutdown="1" before device power-off
* - dashcamd closes current segment, acks, exits
*
* Published params (memory, every 5s):
* - DashcamState: "waiting" or "recording"
* - DashcamFrames: per-trip encoded frame count (resets each trip)
*/
#include <cstdio>
#include <ctime>
#include <string>
#include <errno.h>
#include <signal.h>
#include <sched.h>
#include <execinfo.h>
#include <sys/stat.h>
#include <sys/resource.h>
#include <unistd.h>
#include "cereal/messaging/messaging.h"
#include "cereal/visionipc/visionipc_client.h"
#include "common/params.h"
#include "common/timing.h"
#include "common/swaglog.h"
#include "common/util.h"
#include "selfdrive/frogpilot/screenrecorder/omx_encoder.h"
const std::string VIDEOS_BASE = "/data/media/0/videos";
const int SEGMENT_SECONDS = 180; // 3 minutes
const int SOURCE_FPS = 20;
const int CAMERA_FPS = 10;
const int FRAMES_PER_SEGMENT = SEGMENT_SECONDS * CAMERA_FPS;
const int BITRATE = 2500 * 1024; // 2500 kbps
const double IDLE_TIMEOUT_SECONDS = 600.0; // 10 minutes
ExitHandler do_exit;
enum TripState {
WAITING, // no trip, waiting for valid time + drive gear
RECORDING, // actively recording, car in drive
IDLE_TIMEOUT, // car left drive, recording with 10-min timer
};
static std::string make_timestamp() {
char buf[64];
time_t t = time(NULL);
struct tm tm = *localtime(&t);
snprintf(buf, sizeof(buf), "%04d%02d%02d-%02d%02d%02d",
tm.tm_year + 1900, tm.tm_mon + 1, tm.tm_mday,
tm.tm_hour, tm.tm_min, tm.tm_sec);
return std::string(buf);
}
static bool system_time_valid() {
time_t t = time(NULL);
struct tm tm = *gmtime(&t);
return (tm.tm_year + 1900) >= 2024;
}
static std::string make_utc_timestamp() {
char buf[32];
time_t t = time(NULL);
struct tm tm = *gmtime(&t);
snprintf(buf, sizeof(buf), "%04d-%02d-%02d %02d:%02d:%02d UTC",
tm.tm_year + 1900, tm.tm_mon + 1, tm.tm_mday,
tm.tm_hour, tm.tm_min, tm.tm_sec);
return std::string(buf);
}
// Format SRT timestamp: HH:MM:SS,mmm
static std::string srt_time(int seconds) {
int h = seconds / 3600;
int m = (seconds % 3600) / 60;
int s = seconds % 60;
char buf[16];
snprintf(buf, sizeof(buf), "%02d:%02d:%02d,000", h, m, s);
return std::string(buf);
}
static void crash_handler(int sig) {
FILE *f = fopen("/tmp/dashcamd_crash.log", "w");
if (f) {
fprintf(f, "CRASH: signal %d\n", sig);
void *bt[30];
int n = backtrace(bt, 30);
backtrace_symbols_fd(bt, n, fileno(f));
fclose(f);
}
_exit(1);
}
int main(int argc, char *argv[]) {
signal(SIGSEGV, crash_handler);
signal(SIGABRT, crash_handler);
setpriority(PRIO_PROCESS, 0, -10);
// CLEARPILOT: pin to cores 0-3 (little cluster). Avoids cache/memory-bandwidth
// contention with the RT-pinned processes on the big cluster:
// core 4 = controlsd, core 5 = plannerd/radard, core 7 = modeld.
// OMX offloads actual H.264 work to hardware, so the main thread just copies
// frames and muxes MP4 — fine on the little cluster.
cpu_set_t mask;
CPU_ZERO(&mask);
for (int i = 0; i < 4; i++) CPU_SET(i, &mask);
if (sched_setaffinity(0, sizeof(mask), &mask) != 0) {
LOGW("dashcamd: sched_setaffinity failed (%d), continuing unpinned", errno);
} else {
LOGW("dashcamd: pinned to cores 0-3");
}
// Ensure base output directory exists
mkdir(VIDEOS_BASE.c_str(), 0755);
LOGW("dashcamd: started, connecting to camerad road stream");
VisionIpcClient vipc("camerad", VISION_STREAM_ROAD, false);
while (!do_exit && !vipc.connect(false)) {
usleep(100000);
}
if (do_exit) return 0;
LOGW("dashcamd: vipc connected, waiting for valid frame");
// Wait for a frame with valid dimensions (camerad may still be initializing)
VisionBuf *init_buf = nullptr;
while (!do_exit) {
init_buf = vipc.recv();
if (init_buf != nullptr && init_buf->width > 0 && init_buf->height > 0) break;
usleep(100000);
}
if (do_exit) return 0;
int width = init_buf->width;
int height = init_buf->height;
int y_stride = init_buf->stride;
int uv_stride = y_stride;
LOGW("dashcamd: first valid frame %dx%d stride=%d", width, height, y_stride);
// Subscribe to carState (gear), deviceState (ignition), gpsLocation (subtitles)
SubMaster sm({"carState", "deviceState", "gpsLocation"});
Params params;
Params params_memory("/dev/shm/params");
// Trip state
TripState state = WAITING;
OmxEncoder *encoder = nullptr;
std::string trip_dir;
int frame_count = 0; // per-segment (for rotation)
int trip_frames = 0; // per-trip (published to params)
int recv_count = 0;
uint64_t segment_start_ts = 0;
double idle_timer_start = 0.0;
// SRT subtitle state
FILE *srt_file = nullptr;
int srt_index = 0;
int srt_segment_sec = 0;
double last_srt_write = 0;
// Ignition tracking
bool prev_started = false;
bool started_initialized = false;
// Param publish throttle
int param_check_counter = 0;
double last_param_write = 0;
// Publish initial state
params_memory.put("DashcamState", "waiting");
params_memory.put("DashcamFrames", "0");
LOGW("dashcamd: entering main loop in WAITING state");
// Helper: start a new trip
auto start_new_trip = [&]() {
trip_dir = VIDEOS_BASE + "/" + make_timestamp();
mkdir(trip_dir.c_str(), 0755);
LOGW("dashcamd: new trip %s", trip_dir.c_str());
encoder = new OmxEncoder(trip_dir.c_str(), width, height, CAMERA_FPS, BITRATE);
std::string seg_name = make_timestamp();
LOGW("dashcamd: opening segment %s", seg_name.c_str());
encoder->encoder_open((seg_name + ".mp4").c_str());
std::string srt_path = trip_dir + "/" + seg_name + ".srt";
srt_file = fopen(srt_path.c_str(), "w");
srt_index = 0;
srt_segment_sec = 0;
last_srt_write = 0;
frame_count = 0;
trip_frames = 0;
segment_start_ts = nanos_since_boot();
state = RECORDING;
params_memory.put("DashcamState", "recording");
params_memory.put("DashcamFrames", "0");
};
// Helper: close current trip
auto close_trip = [&]() {
if (srt_file) { fclose(srt_file); srt_file = nullptr; }
if (encoder) {
encoder->encoder_close();
LOGW("dashcamd: segment closed");
delete encoder;
encoder = nullptr;
}
state = WAITING;
frame_count = 0;
trip_frames = 0;
idle_timer_start = 0.0;
LOGW("dashcamd: trip ended, returning to WAITING");
params_memory.put("DashcamState", "waiting");
params_memory.put("DashcamFrames", "0");
};
while (!do_exit) {
VisionBuf *buf = vipc.recv();
if (buf == nullptr) continue;
// Skip frames to match target FPS (SOURCE_FPS -> CAMERA_FPS)
recv_count++;
if (SOURCE_FPS > CAMERA_FPS && (recv_count % (SOURCE_FPS / CAMERA_FPS)) != 0) continue;
sm.update(0);
double now = nanos_since_boot() / 1e9;
// Read vehicle state
bool started = sm.valid("deviceState") &&
sm["deviceState"].getDeviceState().getStarted();
auto gear = sm.valid("carState") ?
sm["carState"].getCarState().getGearShifter() :
cereal::CarState::GearShifter::UNKNOWN;
bool in_drive = (gear == cereal::CarState::GearShifter::DRIVE ||
gear == cereal::CarState::GearShifter::SPORT ||
gear == cereal::CarState::GearShifter::LOW ||
gear == cereal::CarState::GearShifter::MANUMATIC);
// Detect ignition off → close any active trip
if (started_initialized && prev_started && !started) {
LOGW("dashcamd: ignition off");
if (state == RECORDING || state == IDLE_TIMEOUT) {
close_trip();
}
}
prev_started = started;
started_initialized = true;
// Check for graceful shutdown request (every ~1 second)
if (++param_check_counter >= CAMERA_FPS) {
param_check_counter = 0;
if (params_memory.getBool("DashcamShutdown")) {
LOGW("dashcamd: shutdown requested");
if (state == RECORDING || state == IDLE_TIMEOUT) {
close_trip();
}
params_memory.putBool("DashcamShutdown", false);
LOGW("dashcamd: shutdown ack sent, exiting");
break;
}
}
// State machine
switch (state) {
case WAITING: {
bool has_gps = sm.valid("gpsLocation") && sm["gpsLocation"].getGpsLocation().getHasFix();
if (in_drive && system_time_valid() && has_gps) {
start_new_trip();
}
break;
}
case RECORDING:
if (!in_drive) {
idle_timer_start = now;
state = IDLE_TIMEOUT;
LOGW("dashcamd: car left drive, starting 10-min idle timer");
}
break;
case IDLE_TIMEOUT:
if (in_drive) {
idle_timer_start = 0.0;
state = RECORDING;
LOGW("dashcamd: back in drive, resuming trip");
} else if ((now - idle_timer_start) >= IDLE_TIMEOUT_SECONDS) {
LOGW("dashcamd: idle timeout expired");
close_trip();
}
break;
}
// Only encode frames when we have an active recording
if (state != RECORDING && state != IDLE_TIMEOUT) continue;
// Segment rotation
if (frame_count >= FRAMES_PER_SEGMENT) {
if (srt_file) { fclose(srt_file); srt_file = nullptr; }
encoder->encoder_close();
std::string seg_name = make_timestamp();
LOGW("dashcamd: opening segment %s", seg_name.c_str());
encoder->encoder_open((seg_name + ".mp4").c_str());
std::string srt_path = trip_dir + "/" + seg_name + ".srt";
srt_file = fopen(srt_path.c_str(), "w");
srt_index = 0;
srt_segment_sec = 0;
last_srt_write = 0;
frame_count = 0;
segment_start_ts = nanos_since_boot();
}
uint64_t ts = nanos_since_boot() - segment_start_ts;
// Validate buffer before encoding
if (buf->y == nullptr || buf->uv == nullptr || buf->width == 0 || buf->height == 0) {
LOGE("dashcamd: invalid frame buf y=%p uv=%p %zux%zu, skipping", buf->y, buf->uv, buf->width, buf->height);
continue;
}
// Feed NV12 frame directly to OMX encoder
encoder->encode_frame_nv12(buf->y, y_stride, buf->uv, uv_stride, width, height, ts);
frame_count++;
trip_frames++;
// Publish state every 5 seconds
if (now - last_param_write >= 5.0) {
params_memory.put("DashcamFrames", std::to_string(trip_frames));
last_param_write = now;
}
// Write GPS subtitle at most once per second
if (srt_file && (now - last_srt_write) >= 1.0) {
last_srt_write = now;
srt_index++;
double lat = 0, lon = 0, speed_ms = 0;
bool has_gps = sm.valid("gpsLocation") && sm["gpsLocation"].getGpsLocation().getHasFix();
if (has_gps) {
auto gps = sm["gpsLocation"].getGpsLocation();
lat = gps.getLatitude();
lon = gps.getLongitude();
speed_ms = gps.getSpeed();
}
double speed_mph = speed_ms * 2.23694;
std::string utc = make_utc_timestamp();
std::string t_start = srt_time(srt_segment_sec);
std::string t_end = srt_time(srt_segment_sec + 1);
srt_segment_sec++;
if (has_gps) {
const char *deg = "\xC2\xB0"; // UTF-8 degree sign
fprintf(srt_file, "%d\n%s --> %s\n%.0f MPH | %.4f%s%c %.4f%s%c | %s\n\n",
srt_index, t_start.c_str(), t_end.c_str(),
speed_mph,
std::abs(lat), deg, lat >= 0 ? 'N' : 'S',
std::abs(lon), deg, lon >= 0 ? 'E' : 'W',
utc.c_str());
} else {
fprintf(srt_file, "%d\n%s --> %s\nNo GPS | %s\n\n",
srt_index, t_start.c_str(), t_end.c_str(), utc.c_str());
}
fflush(srt_file);
}
}
// Clean exit
if (state == RECORDING || state == IDLE_TIMEOUT) {
close_trip();
}
params_memory.put("DashcamState", "stopped");
params_memory.put("DashcamFrames", "0");
LOGW("dashcamd: stopped");
return 0;
}
+121
View File
@@ -0,0 +1,121 @@
#!/usr/bin/env python3
"""
CLEARPILOT dashcamd — records raw camera footage to MP4 using hardware H.264 encoder.
Connects directly to camerad via VisionIPC, receives NV12 frames, and pipes them
to ffmpeg's h264_v4l2m2m encoder. Produces 3-minute MP4 segments in /data/media/0/videos/.
This replaces the FrogPilot screen recorder approach (QWidget::grab -> OMX) with a
direct camera capture that works regardless of UI state (screen off, alternate modes, etc).
"""
import os
import time
import subprocess
import signal
from pathlib import Path
from datetime import datetime
from cereal.visionipc import VisionIpcClient, VisionStreamType
from openpilot.common.params import Params
from openpilot.common.swaglog import cloudlog
from openpilot.selfdrive import sentry
PROCESS_NAME = "selfdrive.clearpilot.dashcamd"
VIDEOS_DIR = "/data/media/0/videos"
SEGMENT_SECONDS = 180 # 3 minutes
CAMERA_FPS = 20
FRAMES_PER_SEGMENT = SEGMENT_SECONDS * CAMERA_FPS
def make_filename():
return datetime.now().strftime("%Y%m%d-%H%M%S") + ".mp4"
def open_encoder(width, height, filepath):
"""Start an ffmpeg subprocess that accepts raw NV12 on stdin and writes MP4."""
cmd = [
"ffmpeg", "-y", "-nostdin", "-loglevel", "error",
"-f", "rawvideo",
"-pix_fmt", "nv12",
"-s", f"{width}x{height}",
"-r", str(CAMERA_FPS),
"-i", "pipe:0",
"-c:v", "h264_v4l2m2m",
"-b:v", "4M",
"-f", "mp4",
"-movflags", "+faststart",
filepath,
]
return subprocess.Popen(cmd, stdin=subprocess.PIPE)
def main():
sentry.set_tag("daemon", PROCESS_NAME)
cloudlog.bind(daemon=PROCESS_NAME)
os.makedirs(VIDEOS_DIR, exist_ok=True)
params = Params()
# Connect to camerad road stream
cloudlog.info("dashcamd: connecting to camerad road stream")
vipc = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_ROAD, False)
while not vipc.connect(False):
time.sleep(0.1)
width, height = vipc.width, vipc.height
# NV12 frame: Y plane (w*h) + UV plane (w*h/2)
frame_size = width * height * 3 // 2
cloudlog.info(f"dashcamd: connected, {width}x{height}, frame_size={frame_size}")
frame_count = 0
encoder = None
lock_path = None
try:
while True:
buf = vipc.recv()
if buf is None:
continue
# Start new segment if needed
if encoder is None or frame_count >= FRAMES_PER_SEGMENT:
# Close previous segment
if encoder is not None:
encoder.stdin.close()
encoder.wait()
if lock_path and os.path.exists(lock_path):
os.remove(lock_path)
cloudlog.info(f"dashcamd: closed segment, {frame_count} frames")
# Open new segment
filename = make_filename()
filepath = os.path.join(VIDEOS_DIR, filename)
lock_path = filepath + ".lock"
Path(lock_path).touch()
cloudlog.info(f"dashcamd: opening segment {filename}")
encoder = open_encoder(width, height, filepath)
frame_count = 0
# Write raw NV12 frame to ffmpeg stdin
try:
encoder.stdin.write(buf.data[:frame_size])
frame_count += 1
except BrokenPipeError:
cloudlog.error("dashcamd: encoder pipe broken, restarting segment")
encoder = None
except (KeyboardInterrupt, SystemExit):
pass
finally:
if encoder is not None:
encoder.stdin.close()
encoder.wait()
if lock_path and os.path.exists(lock_path):
os.remove(lock_path)
cloudlog.info("dashcamd: stopped")
if __name__ == "__main__":
main()
Binary file not shown.
+114
View File
@@ -0,0 +1,114 @@
"""
ClearPilot speed processing module.
Shared logic for converting raw speed and speed limit data into display-ready
values. Called from controlsd (live mode) and bench_onroad (bench mode).
Reads raw inputs, converts to display units (mph or kph based on car's CAN
unit setting), detects speed limit changes, and writes results to params_memory
for the onroad UI to read.
"""
import math
import time
from openpilot.common.params import Params
from openpilot.common.conversions import Conversions as CV
class SpeedState:
def __init__(self):
self.params_memory = Params("/dev/shm/params")
self.prev_speed_limit = 0
# Ding state tracking
self.last_ding_time = 0.0
self.prev_warning = ""
self.prev_warning_speed_limit = 0
# Cache last-written param values — each put() is mkstemp+fsync+flock+rename.
# Sentinel None so the first call always writes.
self._w_has_speed = None
self._w_speed_display = None
self._w_speed_limit_display = None
self._w_speed_unit = None
self._w_is_metric = None
self._w_cruise_warning = None
self._w_cruise_warning_speed = None
def _put_if_changed(self, key, value, attr):
if getattr(self, attr) != value:
self.params_memory.put(key, value)
setattr(self, attr, value)
def update(self, speed_ms: float, has_speed: bool, speed_limit_ms: float, is_metric: bool,
cruise_speed_ms: float = 0.0, cruise_active: bool = False, cruise_standstill: bool = False):
"""
Convert raw m/s values to display-ready strings and write to params_memory.
"""
now = time.monotonic()
if is_metric:
speed_display = speed_ms * CV.MS_TO_KPH
speed_limit_display = speed_limit_ms * CV.MS_TO_KPH
cruise_display = cruise_speed_ms * CV.MS_TO_KPH
unit = "km/h"
else:
speed_display = speed_ms * CV.MS_TO_MPH
speed_limit_display = speed_limit_ms * CV.MS_TO_MPH
cruise_display = cruise_speed_ms * CV.MS_TO_MPH
unit = "mph"
speed_int = int(math.floor(speed_display))
speed_limit_int = int(round(speed_limit_display))
cruise_int = int(round(cruise_display))
self.prev_speed_limit = speed_limit_int
# Write display-ready values to params_memory (gated on change)
self._put_if_changed("ClearpilotHasSpeed", "1" if has_speed and speed_int > 0 else "0", "_w_has_speed")
self._put_if_changed("ClearpilotSpeedDisplay", str(speed_int) if has_speed and speed_int > 0 else "", "_w_speed_display")
self._put_if_changed("ClearpilotSpeedLimitDisplay", str(speed_limit_int) if speed_limit_int > 0 else "0", "_w_speed_limit_display")
self._put_if_changed("ClearpilotSpeedUnit", unit, "_w_speed_unit")
self._put_if_changed("ClearpilotIsMetric", "1" if is_metric else "0", "_w_is_metric")
# Cruise warning logic
warning = ""
warning_speed = ""
cruise_engaged = cruise_active and not cruise_standstill
if speed_limit_int >= 20 and cruise_engaged and cruise_int > 0:
# Tiers (warning fires at >= limit + threshold):
# limit >= 50: +9 over ok, warn at +10 (e.g. 60 → warn at 70)
# limit 26-49: +6 over ok, warn at +7 (e.g. 35 → warn at 42)
# limit <= 25: +8 over ok, warn at +9 (e.g. 25 → warn at 34, so 33 is ok)
if speed_limit_int >= 50:
over_threshold = 10
elif speed_limit_int <= 25:
over_threshold = 9
else:
over_threshold = 7
if cruise_int >= speed_limit_int + over_threshold:
warning = "over"
warning_speed = str(cruise_int)
elif cruise_int <= speed_limit_int - 5:
warning = "under"
warning_speed = str(cruise_int)
self._put_if_changed("ClearpilotCruiseWarning", warning, "_w_cruise_warning")
self._put_if_changed("ClearpilotCruiseWarningSpeed", warning_speed, "_w_cruise_warning_speed")
# Ding logic: play when warning sign appears or speed limit changes while visible
should_ding = False
if warning:
if not self.prev_warning:
# Warning sign just appeared
should_ding = True
elif speed_limit_int != self.prev_warning_speed_limit:
# Speed limit changed while warning sign is visible
should_ding = True
if should_ding and now - self.last_ding_time >= 30:
self.params_memory.put("ClearpilotPlayDing", "1")
self.last_ding_time = now
self.prev_warning = warning
self.prev_warning_speed_limit = speed_limit_int if warning else 0
+53
View File
@@ -0,0 +1,53 @@
"""
ClearPilot telemetry client library.
Usage from any process:
from openpilot.selfdrive.clearpilot.telemetry import tlog
tlog("canbus", {"speed": 45.2, "speed_limit": 60})
Sends JSON packets over ZMQ PUSH to telemetryd, which diffs and writes CSV.
Only sends when TelemetryEnabled memory param is set — zero cost when disabled.
"""
import json
import os
import time
import zmq
TELEMETRY_SOCK = "ipc:///tmp/clearpilot_telemetry"
_PARAM_PATH = "/dev/shm/params/d/TelemetryEnabled"
_ctx = None
_sock = None
_last_check = 0
_enabled = False
def tlog(group: str, data: dict):
"""Log a telemetry packet. Only changed values will be written to CSV by telemetryd."""
global _ctx, _sock, _last_check, _enabled
# Check param at most once per second to avoid filesystem overhead
now = time.monotonic()
if now - _last_check > 1.0:
_last_check = now
try:
with open(_PARAM_PATH, 'r') as f:
_enabled = f.read().strip() == "1"
except (FileNotFoundError, IOError):
_enabled = False
if not _enabled:
return
if _sock is None:
_ctx = zmq.Context.instance()
_sock = _ctx.socket(zmq.PUSH)
_sock.setsockopt(zmq.LINGER, 0)
_sock.setsockopt(zmq.SNDHWM, 100)
_sock.connect(TELEMETRY_SOCK)
msg = json.dumps({"ts": time.time(), "group": group, "data": data})
try:
_sock.send_string(msg, zmq.NOBLOCK)
except zmq.Again:
pass # drop if collector isn't running or queue full
+147
View File
@@ -0,0 +1,147 @@
#!/usr/bin/env python3
"""
ClearPilot telemetry collector.
Receives telemetry packets from any process via ZMQ, diffs against previous
state per group, and writes only changed values to CSV.
Controlled by TelemetryEnabled param — when toggled on, the first packet
from each group writes all values (full dump). When toggled off, stops writing.
CSV format: timestamp,group,key,value
"""
import csv
import json
import os
import shutil
import time
import zmq
import cereal.messaging as messaging
from openpilot.common.params import Params
from openpilot.selfdrive.clearpilot.telemetry import TELEMETRY_SOCK
from openpilot.selfdrive.manager.process import _log_dir, session_log
MIN_DISK_FREE_GB = 5
DISK_CHECK_INTERVAL = 10 # seconds
def main():
params = Params("/dev/shm/params")
ctx = zmq.Context.instance()
sock = ctx.socket(zmq.PULL)
sock.setsockopt(zmq.RCVHWM, 1000)
sock.bind(TELEMETRY_SOCK)
# GPS subscriber for location telemetry
sm = messaging.SubMaster(['gpsLocation'])
last_gps_log = 0
csv_path = os.path.join(_log_dir, "telemetry.csv")
state: dict[str, dict] = {} # group -> {key: last_value}
was_enabled = False
writer = None
f = None
last_disk_check = 0
while True:
# Check enable state every iteration (cheap param read)
enabled = params.get("TelemetryEnabled") == b"1"
# Check disk space every 10 seconds while enabled
if enabled and (time.monotonic() - last_disk_check) > DISK_CHECK_INTERVAL:
last_disk_check = time.monotonic()
disk = shutil.disk_usage("/data")
free_gb = disk.free / (1024 ** 3)
if free_gb < MIN_DISK_FREE_GB:
session_log.warning("telemetry disabled: disk free %.1f GB < %d GB", free_gb, MIN_DISK_FREE_GB)
params.put("TelemetryEnabled", "0")
enabled = False
# Toggled on: open CSV, clear state so first packet is a full dump
if enabled and not was_enabled:
f = open(csv_path, "a", newline="")
writer = csv.writer(f)
if os.path.getsize(csv_path) == 0:
writer.writerow(["timestamp", "group", "key", "value"])
state.clear() # force full dump on first packet per group
f.flush()
# Toggled off: close file
if not enabled and was_enabled:
if f:
f.close()
f = None
writer = None
was_enabled = enabled
# GPS telemetry at most 1Hz — fed through the same diff logic
if enabled and writer is not None:
sm.update(0)
now = time.monotonic()
if sm.updated['gpsLocation'] and (now - last_gps_log) >= 1.0:
gps = sm['gpsLocation']
gps_data = {
"latitude": f"{gps.latitude:.7f}",
"longitude": f"{gps.longitude:.7f}",
"speed": f"{gps.speed:.2f}",
"altitude": f"{gps.altitude:.1f}",
"bearing": f"{gps.bearingDeg:.1f}",
"accuracy": f"{gps.accuracy:.1f}",
}
ts = time.time()
if "gps" not in state:
state["gps"] = {}
prev_gps = state["gps"]
gps_changed = False
for key, value in gps_data.items():
if key not in prev_gps or prev_gps[key] != value:
writer.writerow([f"{ts:.6f}", "gps", key, value])
prev_gps[key] = value
gps_changed = True
if gps_changed:
f.flush()
last_gps_log = now
# Always drain the socket (even when disabled) to avoid backpressure
try:
raw = sock.recv_string(zmq.NOBLOCK)
except zmq.Again:
time.sleep(0.01)
continue
except zmq.ZMQError:
time.sleep(0.01)
continue
if not enabled or writer is None:
continue
try:
pkt = json.loads(raw)
except json.JSONDecodeError:
continue
ts = pkt.get("ts", 0)
group = pkt.get("group", "")
data = pkt.get("data", {})
if group not in state:
state[group] = {}
prev = state[group]
changed = False
for key, value in data.items():
str_val = str(value)
if key not in prev or prev[key] != str_val:
writer.writerow([f"{ts:.6f}", group, key, str_val])
prev[key] = str_val
changed = True
if changed:
f.flush()
if __name__ == "__main__":
main()
Binary file not shown.

Before

Width:  |  Height:  |  Size: 1.4 KiB

After

Width:  |  Height:  |  Size: 2.5 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 35 KiB

After

Width:  |  Height:  |  Size: 1.4 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 24 KiB

After

Width:  |  Height:  |  Size: 7.5 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 53 KiB

After

Width:  |  Height:  |  Size: 24 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.4 KiB

+12
View File
@@ -0,0 +1,12 @@
#!/usr/bin/env python3
"""Query the UI process for its current widget tree. Usage: python3 -m selfdrive.clearpilot.ui_dump"""
import zmq
ctx = zmq.Context()
sock = ctx.socket(zmq.REQ)
sock.setsockopt(zmq.RCVTIMEO, 2000)
sock.connect("ipc:///tmp/clearpilot_ui_rpc")
sock.send_string("dump")
try:
print(sock.recv_string())
except zmq.Again:
print("ERROR: UI not responding (timeout)")
+96 -34
View File
@@ -37,6 +37,8 @@ from openpilot.system.version import get_short_branch
from openpilot.selfdrive.frogpilot.controls.lib.frogpilot_functions import CRUISING_SPEED, PROBABILITY, MovingAverageCalculator from openpilot.selfdrive.frogpilot.controls.lib.frogpilot_functions import CRUISING_SPEED, PROBABILITY, MovingAverageCalculator
from openpilot.selfdrive.frogpilot.controls.lib.model_manager import RADARLESS_MODELS from openpilot.selfdrive.frogpilot.controls.lib.model_manager import RADARLESS_MODELS
from openpilot.selfdrive.clearpilot.telemetry import tlog
from openpilot.selfdrive.clearpilot.speed_logic import SpeedState
from openpilot.selfdrive.frogpilot.controls.lib.speed_limit_controller import SpeedLimitController from openpilot.selfdrive.frogpilot.controls.lib.speed_limit_controller import SpeedLimitController
SOFT_DISABLE_TIME = 3 # seconds SOFT_DISABLE_TIME = 3 # seconds
@@ -47,7 +49,7 @@ CAMERA_OFFSET = 0.04
REPLAY = "REPLAY" in os.environ REPLAY = "REPLAY" in os.environ
SIMULATION = "SIMULATION" in os.environ SIMULATION = "SIMULATION" in os.environ
TESTING_CLOSET = "TESTING_CLOSET" in os.environ TESTING_CLOSET = "TESTING_CLOSET" in os.environ
IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd"} IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd", "telemetryd", "dashcamd"}
ThermalStatus = log.DeviceState.ThermalStatus ThermalStatus = log.DeviceState.ThermalStatus
State = log.ControlsState.OpenpilotState State = log.ControlsState.OpenpilotState
@@ -77,7 +79,13 @@ class Controls:
self.params_storage = Params("/persist/params") self.params_storage = Params("/persist/params")
self.params_memory.put_bool("CPTLkasButtonAction", False) self.params_memory.put_bool("CPTLkasButtonAction", False)
self.params_memory.put_bool("ScreenDisplayMode", 0) self.params_memory.put_int("ScreenDisplayMode", 0)
# CLEARPILOT: speed-limit/cruise-warning state machine + park→drive auto-reset
self.speed_state = SpeedState()
self.speed_state_frame = 0
self.was_driving_gear = False
self.driving_gear = False
self.radarless_model = self.params.get("Model", encoding='utf-8') in RADARLESS_MODELS self.radarless_model = self.params.get("Model", encoding='utf-8') in RADARLESS_MODELS
@@ -107,8 +115,8 @@ class Controls:
self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration',
'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'liveLocationKalman', 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'liveLocationKalman',
'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters',
'testJoystick', 'frogpilotPlan'] + self.camera_packets + self.sensor_packets, 'testJoystick', 'frogpilotPlan', 'gpsLocation'] + self.camera_packets + self.sensor_packets,
ignore_alive=ignore, ignore_avg_freq=ignore+['radarState', 'testJoystick'], ignore_valid=['testJoystick', ], ignore_alive=ignore + ['gpsLocation'], ignore_avg_freq=ignore+['radarState', 'testJoystick', 'gpsLocation'], ignore_valid=['testJoystick', 'gpsLocation'],
frequency=int(1/DT_CTRL)) frequency=int(1/DT_CTRL))
self.joystick_mode = self.params.get_bool("JoystickDebugMode") self.joystick_mode = self.params.get_bool("JoystickDebugMode")
@@ -441,6 +449,13 @@ class Controls:
# All events here should at least have NO_ENTRY and SOFT_DISABLE. # All events here should at least have NO_ENTRY and SOFT_DISABLE.
num_events = len(self.events) num_events = len(self.events)
# CLEARPILOT: compute model standby suppression early — used by multiple checks below
try:
standby_ts = float(self.params_memory.get("ModelStandbyTs") or "0")
except (ValueError, TypeError):
standby_ts = 0
model_suppress = (time.monotonic() - standby_ts) < 2.0
not_running = {p.name for p in self.sm['managerState'].processes if not p.running and p.shouldBeRunning} not_running = {p.name for p in self.sm['managerState'].processes if not p.running and p.shouldBeRunning}
if self.sm.recv_frame['managerState'] and (not_running - IGNORE_PROCESSES): if self.sm.recv_frame['managerState'] and (not_running - IGNORE_PROCESSES):
self.events.add(EventName.processNotRunning) self.events.add(EventName.processNotRunning)
@@ -454,9 +469,11 @@ class Controls:
elif not self.sm.all_freq_ok(self.camera_packets): elif not self.sm.all_freq_ok(self.camera_packets):
self.events.add(EventName.cameraFrameRate) self.events.add(EventName.cameraFrameRate)
if not REPLAY and self.rk.lagging: if not REPLAY and self.rk.lagging:
import sys
print(f"CLP controlsdLagging: remaining={self.rk.remaining:.4f} standstill={CS.standstill} vEgo={CS.vEgo:.2f}", file=sys.stderr)
self.events.add(EventName.controlsdLagging) self.events.add(EventName.controlsdLagging)
if not self.radarless_model: if not self.radarless_model:
if len(self.sm['radarState'].radarErrors) or (not self.rk.lagging and not self.sm.all_checks(['radarState'])): if not model_suppress and (len(self.sm['radarState'].radarErrors) or (not self.rk.lagging and not self.sm.all_checks(['radarState']))):
self.events.add(EventName.radarFault) self.events.add(EventName.radarFault)
if not self.sm.valid['pandaStates']: if not self.sm.valid['pandaStates']:
self.events.add(EventName.usbError) self.events.add(EventName.usbError)
@@ -468,13 +485,16 @@ class Controls:
# generic catch-all. ideally, a more specific event should be added above instead # generic catch-all. ideally, a more specific event should be added above instead
has_disable_events = self.events.contains(ET.NO_ENTRY) and (self.events.contains(ET.SOFT_DISABLE) or self.events.contains(ET.IMMEDIATE_DISABLE)) has_disable_events = self.events.contains(ET.NO_ENTRY) and (self.events.contains(ET.SOFT_DISABLE) or self.events.contains(ET.IMMEDIATE_DISABLE))
no_system_errors = (not has_disable_events) or (len(self.events) == num_events) no_system_errors = (not has_disable_events) or (len(self.events) == num_events)
if (not self.sm.all_checks() or self.card.can_rcv_timeout) and no_system_errors: # CLEARPILOT: fire commIssue ONLY when messages actually aren't flowing (not_alive)
# or CAN RX is timing out. Don't fire on self-declared valid=False — that's the
# polling-pattern / all_checks cascade that paramsd/torqued/plannerd/frogpilot
# propagate even while their publish rate and content are fine.
comms_really_broken = (not self.sm.all_alive()) or self.card.can_rcv_timeout
if comms_really_broken and no_system_errors and not model_suppress:
if not self.sm.all_alive(): if not self.sm.all_alive():
self.events.add(EventName.commIssue) self.events.add(EventName.commIssue)
elif not self.sm.all_freq_ok(): else:
self.events.add(EventName.commIssueAvgFreq) self.events.add(EventName.commIssue) # can_rcv_timeout path
else: # invalid or can_rcv_timeout.
self.events.add(EventName.commIssue)
logs = { logs = {
'invalid': [s for s, valid in self.sm.valid.items() if not valid], 'invalid': [s for s, valid in self.sm.valid.items() if not valid],
@@ -489,13 +509,13 @@ class Controls:
self.logged_comm_issue = None self.logged_comm_issue = None
if not (self.CP.notCar and self.joystick_mode): if not (self.CP.notCar and self.joystick_mode):
if not self.sm['liveLocationKalman'].posenetOK: if not self.sm['liveLocationKalman'].posenetOK and not model_suppress:
self.events.add(EventName.posenetInvalid) self.events.add(EventName.posenetInvalid)
if not self.sm['liveLocationKalman'].deviceStable: if not self.sm['liveLocationKalman'].deviceStable:
self.events.add(EventName.deviceFalling) self.events.add(EventName.deviceFalling)
if not self.sm['liveLocationKalman'].inputsOK: if not self.sm['liveLocationKalman'].inputsOK and not model_suppress:
self.events.add(EventName.locationdTemporaryError) self.events.add(EventName.locationdTemporaryError)
if not self.sm['liveParameters'].valid and not TESTING_CLOSET and (not SIMULATION or REPLAY): if not self.sm['liveParameters'].valid and not TESTING_CLOSET and (not SIMULATION or REPLAY) and not model_suppress:
self.events.add(EventName.paramsdTemporaryError) self.events.add(EventName.paramsdTemporaryError)
# conservative HW alert. if the data or frequency are off, locationd will throw an error # conservative HW alert. if the data or frequency are off, locationd will throw an error
@@ -541,7 +561,7 @@ class Controls:
self.distance_traveled = 0 self.distance_traveled = 0
self.distance_traveled += CS.vEgo * DT_CTRL self.distance_traveled += CS.vEgo * DT_CTRL
if self.sm['modelV2'].frameDropPerc > 20: if self.sm['modelV2'].frameDropPerc > 20 and not model_suppress:
self.events.add(EventName.modeldLagging) self.events.add(EventName.modeldLagging)
@@ -628,6 +648,14 @@ class Controls:
# Check if openpilot is engaged and actuators are enabled # Check if openpilot is engaged and actuators are enabled
self.enabled = self.state in ENABLED_STATES self.enabled = self.state in ENABLED_STATES
self.active = self.state in ACTIVE_STATES self.active = self.state in ACTIVE_STATES
# CLEARPILOT: engagement telemetry disabled — was running at 100Hz, causing CPU load
# tlog("engage", {
# "state": self.state.name if hasattr(self.state, 'name') else str(self.state),
# "enabled": self.enabled, "active": self.active,
# "cruise_enabled": CS.cruiseState.enabled, "cruise_available": CS.cruiseState.available,
# "brakePressed": CS.brakePressed,
# })
if self.active: if self.active:
self.current_alert_types.append(ET.WARNING) self.current_alert_types.append(ET.WARNING)
@@ -637,6 +665,25 @@ class Controls:
def state_control(self, CS): def state_control(self, CS):
"""Given the state, this function returns a CarControl packet""" """Given the state, this function returns a CarControl packet"""
# CLEARPILOT: short-circuit while parked. Skip LaC/LoC PID, MPC, model_v2
# reads, lane-change logic — none of it matters when the car isn't moving.
# publish_logs still runs and still triggers carcontroller.apply via
# card.controls_update, so the sendcan heartbeats / tester-present messages
# keep flowing at 100Hz and the car doesn't fault. Saves ~30% controlsd CPU
# in park.
if CS.gearShifter == car.CarState.GearShifter.park:
CC = car.CarControl.new_message()
CC.enabled = False
CC.latActive = False
CC.longActive = False
CC.actuators.longControlState = self.LoC.long_control_state
self.LaC.reset()
self.LoC.reset(v_pid=CS.vEgo)
self.frogpilot_variables.no_lat_lane_change = False
self.FPCC.noLatLaneChange = False
lac_log = log.ControlsState.LateralDebugState.new_message()
return CC, lac_log
# Update VehicleModel # Update VehicleModel
lp = self.sm['liveParameters'] lp = self.sm['liveParameters']
x = max(lp.stiffnessFactor, 0.1) x = max(lp.stiffnessFactor, 0.1)
@@ -676,9 +723,11 @@ class Controls:
if model_v2.meta.laneChangeState == LaneChangeState.laneChangeStarting and clearpilot_disable_lat_on_lane_change: if model_v2.meta.laneChangeState == LaneChangeState.laneChangeStarting and clearpilot_disable_lat_on_lane_change:
CC.latActive = False CC.latActive = False
self.params_memory.put_bool("no_lat_lane_change", True) self.frogpilot_variables.no_lat_lane_change = True
self.FPCC.noLatLaneChange = True
else: else:
self.params_memory.put_bool("no_lat_lane_change", False) self.frogpilot_variables.no_lat_lane_change = False
self.FPCC.noLatLaneChange = False
if CS.leftBlinker or CS.rightBlinker: if CS.leftBlinker or CS.rightBlinker:
self.last_blinker_frame = self.sm.frame self.last_blinker_frame = self.sm.frame
@@ -1235,30 +1284,43 @@ class Controls:
def update_clearpilot_events(self, CS): def update_clearpilot_events(self, CS):
if (len(CS.buttonEvents) > 0): if (len(CS.buttonEvents) > 0):
print (CS.buttonEvents) print (CS.buttonEvents)
if any(be.pressed and be.type == FrogPilotButtonType.lkas for be in CS.buttonEvents):
# Uncomment to alert when lkas button pressed self.events.add(EventName.clpDebug)
# if any(be.pressed and be.type == FrogPilotButtonType.lkas for be in CS.buttonEvents):
# self.events.add(EventName.clpDebug)
def clearpilot_state_control(self, CC, CS): def clearpilot_state_control(self, CC, CS):
# CLEARPILOT: auto-reset display when shifting into drive from screen-off
if self.driving_gear and not self.was_driving_gear:
if self.params_memory.get_int("ScreenDisplayMode") == 3:
self.params_memory.put_int("ScreenDisplayMode", 0)
self.was_driving_gear = self.driving_gear
if any(be.pressed and be.type == FrogPilotButtonType.lkas for be in CS.buttonEvents): if any(be.pressed and be.type == FrogPilotButtonType.lkas for be in CS.buttonEvents):
current = self.params_memory.get_int("ScreenDisplayMode")
# Uncomment for debug testing. if self.driving_gear:
# if self.params_memory.get_bool("CPTLkasButtonAction"): # Onroad: 0→4, 1→2, 2→3, 3→4, 4→2 (never back to auto via button)
# self.params_memory.put_bool("CPTLkasButtonAction", False) transitions = {0: 4, 1: 2, 2: 3, 3: 4, 4: 2}
# else: new_mode = transitions.get(current, 0)
# self.params_memory.put_bool("CPTLkasButtonAction", True) else:
# Not in drive: any except 3 → 3, state 3 → 0
new_mode = 0 if current == 3 else 3
# Rotate display mode. These are mostly used in the frontend ui app. self.params_memory.put_int("ScreenDisplayMode", new_mode)
max_display_mode = 2
current_display_mode = self.params_memory.get_int("ScreenDisplayMode")
current_display_mode = current_display_mode + 1
if current_display_mode > max_display_mode:
current_display_mode = 0
self.params_memory.put_int("ScreenDisplayMode", current_display_mode)
# Leftovers # ClearPilot speed processing (~2 Hz at 100 Hz loop) — drives speed-limit sign
# self.params_memory.put_int("SpeedLimitLatDesired", CC.actuators.speed * CV.MS_TO_MPH ) # and cruise over/under warning sign via memory params read by the UI.
self.speed_state_frame += 1
if self.speed_state_frame % 50 == 0:
gps = self.sm['gpsLocation']
has_gps = self.sm.valid['gpsLocation'] and gps.hasFix
speed_ms = gps.speed if has_gps else 0.0
speed_limit_ms = self.params_memory.get_float("CarSpeedLimit")
is_metric = (self.params_memory.get("CarIsMetric", encoding="utf-8") or "0") == "1"
cruise_speed_ms = CS.cruiseState.speed
cruise_active = CS.cruiseState.enabled
cruise_standstill = CS.cruiseState.standstill
self.speed_state.update(speed_ms, has_gps, speed_limit_ms, is_metric,
cruise_speed_ms, cruise_active, cruise_standstill)
return CC return CC
def main(): def main():
+1 -1
View File
@@ -778,8 +778,8 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = {
ET.SOFT_DISABLE: soft_disable_alert("Sensor Data Invalid"), ET.SOFT_DISABLE: soft_disable_alert("Sensor Data Invalid"),
}, },
# CLEARPILOT: alert suppressed — event still fires for screen toggle and future actions
EventName.clpDebug: { EventName.clpDebug: {
ET.PERMANENT: clp_debug_notice,
}, },
EventName.noGps: { EventName.noGps: {
+4
View File
@@ -34,6 +34,10 @@ def plannerd_thread():
while True: while True:
sm.update() sm.update()
if sm.updated['modelV2']: if sm.updated['modelV2']:
# CLEARPILOT: skip planning while parked. The downstream consumer (controlsd)
# already short-circuits in park, so longitudinalPlan/uiPlan staleness is fine.
if sm['carState'].gearShifter == car.CarState.GearShifter.park:
continue
longitudinal_planner.update(sm) longitudinal_planner.update(sm)
longitudinal_planner.publish(sm, pm) longitudinal_planner.publish(sm, pm)
publish_ui_plan(sm, pm, longitudinal_planner) publish_ui_plan(sm, pm, longitudinal_planner)
@@ -58,6 +58,9 @@ class FrogPilotPlanner:
self.params = Params() self.params = Params()
self.params_memory = Params("/dev/shm/params") self.params_memory = Params("/dev/shm/params")
# CLEARPILOT: track valid transitions so we only log when it flips, not every cycle
self._dbg_prev_valid = True
self.cem = ConditionalExperimentalMode() self.cem = ConditionalExperimentalMode()
self.lead_one = Lead() self.lead_one = Lead()
self.mtsc = MapTurnSpeedController() self.mtsc = MapTurnSpeedController()
@@ -242,7 +245,18 @@ class FrogPilotPlanner:
def publish(self, sm, pm): def publish(self, sm, pm):
frogpilot_plan_send = messaging.new_message('frogpilotPlan') frogpilot_plan_send = messaging.new_message('frogpilotPlan')
frogpilot_plan_send.valid = sm.all_checks(service_list=['carState', 'controlsState']) valid = sm.all_checks(service_list=['carState', 'controlsState'])
# CLEARPILOT: log on transition into invalid — stderr goes to our plannerd.log
if valid != self._dbg_prev_valid and not valid:
import sys
print(
"CLP frogpilotPlan valid=False: "
f"carState(a={sm.alive['carState']},v={sm.valid['carState']},f={sm.freq_ok['carState']}) "
f"controlsState(a={sm.alive['controlsState']},v={sm.valid['controlsState']},f={sm.freq_ok['controlsState']})",
file=sys.stderr, flush=True
)
self._dbg_prev_valid = valid
frogpilot_plan_send.valid = valid
frogpilotPlan = frogpilot_plan_send.frogpilotPlan frogpilotPlan = frogpilot_plan_send.frogpilotPlan
frogpilotPlan.accelerationJerk = A_CHANGE_COST * (float(self.jerk) if self.lead_one.status else 1) frogpilotPlan.accelerationJerk = A_CHANGE_COST * (float(self.jerk) if self.lead_one.status else 1)
+3 -1
View File
@@ -85,7 +85,9 @@ def frogpilot_thread():
frogpilot_planner = FrogPilotPlanner(CP) frogpilot_planner = FrogPilotPlanner(CP)
frogpilot_planner.update_frogpilot_params() frogpilot_planner.update_frogpilot_params()
if sm.updated['modelV2']: # CLEARPILOT: skip planner work while parked.
parked = sm['carState'].gearShifter == car.CarState.GearShifter.park
if sm.updated['modelV2'] and not parked:
frogpilot_planner.update(sm['carState'], sm['controlsState'], sm['frogpilotCarControl'], sm['frogpilotNavigation'], frogpilot_planner.update(sm['carState'], sm['controlsState'], sm['frogpilotCarControl'], sm['frogpilotNavigation'],
sm['liveLocationKalman'], sm['modelV2'], sm['radarState']) sm['liveLocationKalman'], sm['modelV2'], sm['radarState'])
frogpilot_planner.publish(sm, pm) frogpilot_planner.publish(sm, pm)
+341 -400
View File
@@ -35,120 +35,19 @@ int ABGRToNV12(const uint8_t* src_abgr,
int halfwidth = (width + 1) >> 1; int halfwidth = (width + 1) >> 1;
void (*ABGRToUVRow)(const uint8_t* src_abgr0, int src_stride_abgr, void (*ABGRToUVRow)(const uint8_t* src_abgr0, int src_stride_abgr,
uint8_t* dst_u, uint8_t* dst_v, int width) = uint8_t* dst_u, uint8_t* dst_v, int width) =
ABGRToUVRow_C; ABGRToUVRow_NEON;
void (*ABGRToYRow)(const uint8_t* src_abgr, uint8_t* dst_y, int width) = void (*ABGRToYRow)(const uint8_t* src_abgr, uint8_t* dst_y, int width) =
ABGRToYRow_C; ABGRToYRow_NEON;
void (*MergeUVRow_)(const uint8_t* src_u, const uint8_t* src_v, uint8_t* dst_uv, int width) = MergeUVRow_C; void (*MergeUVRow_)(const uint8_t* src_u, const uint8_t* src_v, uint8_t* dst_uv, int width) = MergeUVRow_NEON;
if (!src_abgr || !dst_y || !dst_uv || width <= 0 || height == 0) { if (!src_abgr || !dst_y || !dst_uv || width <= 0 || height == 0) {
return -1; return -1;
} }
if (height < 0) { // Negative height means invert the image. if (height < 0) {
height = -height; height = -height;
src_abgr = src_abgr + (height - 1) * src_stride_abgr; src_abgr = src_abgr + (height - 1) * src_stride_abgr;
src_stride_abgr = -src_stride_abgr; src_stride_abgr = -src_stride_abgr;
}
#if defined(HAS_ABGRTOYROW_SSSE3) && defined(HAS_ABGRTOUVROW_SSSE3)
if (TestCpuFlag(kCpuHasSSSE3)) {
ABGRToUVRow = ABGRToUVRow_Any_SSSE3;
ABGRToYRow = ABGRToYRow_Any_SSSE3;
if (IS_ALIGNED(width, 16)) {
ABGRToUVRow = ABGRToUVRow_SSSE3;
ABGRToYRow = ABGRToYRow_SSSE3;
}
} }
#endif
#if defined(HAS_ABGRTOYROW_AVX2) && defined(HAS_ABGRTOUVROW_AVX2)
if (TestCpuFlag(kCpuHasAVX2)) {
ABGRToUVRow = ABGRToUVRow_Any_AVX2;
ABGRToYRow = ABGRToYRow_Any_AVX2;
if (IS_ALIGNED(width, 32)) {
ABGRToUVRow = ABGRToUVRow_AVX2;
ABGRToYRow = ABGRToYRow_AVX2;
}
}
#endif
#if defined(HAS_ABGRTOYROW_NEON)
if (TestCpuFlag(kCpuHasNEON)) {
ABGRToYRow = ABGRToYRow_Any_NEON;
if (IS_ALIGNED(width, 8)) {
ABGRToYRow = ABGRToYRow_NEON;
}
}
#endif
#if defined(HAS_ABGRTOUVROW_NEON)
if (TestCpuFlag(kCpuHasNEON)) {
ABGRToUVRow = ABGRToUVRow_Any_NEON;
if (IS_ALIGNED(width, 16)) {
ABGRToUVRow = ABGRToUVRow_NEON;
}
}
#endif
#if defined(HAS_ABGRTOYROW_MMI) && defined(HAS_ABGRTOUVROW_MMI)
if (TestCpuFlag(kCpuHasMMI)) {
ABGRToYRow = ABGRToYRow_Any_MMI;
ABGRToUVRow = ABGRToUVRow_Any_MMI;
if (IS_ALIGNED(width, 8)) {
ABGRToYRow = ABGRToYRow_MMI;
}
if (IS_ALIGNED(width, 16)) {
ABGRToUVRow = ABGRToUVRow_MMI;
}
}
#endif
#if defined(HAS_ABGRTOYROW_MSA) && defined(HAS_ABGRTOUVROW_MSA)
if (TestCpuFlag(kCpuHasMSA)) {
ABGRToYRow = ABGRToYRow_Any_MSA;
ABGRToUVRow = ABGRToUVRow_Any_MSA;
if (IS_ALIGNED(width, 16)) {
ABGRToYRow = ABGRToYRow_MSA;
}
if (IS_ALIGNED(width, 32)) {
ABGRToUVRow = ABGRToUVRow_MSA;
}
}
#endif
#if defined(HAS_MERGEUVROW_SSE2)
if (TestCpuFlag(kCpuHasSSE2)) {
MergeUVRow_ = MergeUVRow_Any_SSE2;
if (IS_ALIGNED(halfwidth, 16)) {
MergeUVRow_ = MergeUVRow_SSE2;
}
}
#endif
#if defined(HAS_MERGEUVROW_AVX2)
if (TestCpuFlag(kCpuHasAVX2)) {
MergeUVRow_ = MergeUVRow_Any_AVX2;
if (IS_ALIGNED(halfwidth, 32)) {
MergeUVRow_ = MergeUVRow_AVX2;
}
}
#endif
#if defined(HAS_MERGEUVROW_NEON)
if (TestCpuFlag(kCpuHasNEON)) {
MergeUVRow_ = MergeUVRow_Any_NEON;
if (IS_ALIGNED(halfwidth, 16)) {
MergeUVRow_ = MergeUVRow_NEON;
}
}
#endif
#if defined(HAS_MERGEUVROW_MMI)
if (TestCpuFlag(kCpuHasMMI)) {
MergeUVRow_ = MergeUVRow_Any_MMI;
if (IS_ALIGNED(halfwidth, 8)) {
MergeUVRow_ = MergeUVRow_MMI;
}
}
#endif
#if defined(HAS_MERGEUVROW_MSA)
if (TestCpuFlag(kCpuHasMSA)) {
MergeUVRow_ = MergeUVRow_Any_MSA;
if (IS_ALIGNED(halfwidth, 16)) {
MergeUVRow_ = MergeUVRow_MSA;
}
}
#endif
{ {
// Allocate a rows of uv.
align_buffer_64(row_u, ((halfwidth + 31) & ~31) * 2); align_buffer_64(row_u, ((halfwidth + 31) & ~31) * 2);
uint8_t* row_v = row_u + ((halfwidth + 31) & ~31); uint8_t* row_v = row_u + ((halfwidth + 31) & ~31);
@@ -182,9 +81,9 @@ extern ExitHandler do_exit;
// ***** OMX callback functions ***** // ***** OMX callback functions *****
void OmxEncoder::wait_for_state(OMX_STATETYPE state_) { void OmxEncoder::wait_for_state(OMX_STATETYPE state_) {
std::unique_lock lk(this->state_lock); std::unique_lock lk(state_lock);
while (this->state != state_) { while (state != state_) {
this->state_cv.wait(lk); state_cv.wait(lk);
} }
} }
@@ -236,270 +135,203 @@ static const char* omx_color_fomat_name(uint32_t format) __attribute__((unused))
static const char* omx_color_fomat_name(uint32_t format) { static const char* omx_color_fomat_name(uint32_t format) {
switch (format) { switch (format) {
case OMX_COLOR_FormatUnused: return "OMX_COLOR_FormatUnused"; case OMX_COLOR_FormatUnused: return "OMX_COLOR_FormatUnused";
case OMX_COLOR_FormatMonochrome: return "OMX_COLOR_FormatMonochrome";
case OMX_COLOR_Format8bitRGB332: return "OMX_COLOR_Format8bitRGB332";
case OMX_COLOR_Format12bitRGB444: return "OMX_COLOR_Format12bitRGB444";
case OMX_COLOR_Format16bitARGB4444: return "OMX_COLOR_Format16bitARGB4444";
case OMX_COLOR_Format16bitARGB1555: return "OMX_COLOR_Format16bitARGB1555";
case OMX_COLOR_Format16bitRGB565: return "OMX_COLOR_Format16bitRGB565";
case OMX_COLOR_Format16bitBGR565: return "OMX_COLOR_Format16bitBGR565";
case OMX_COLOR_Format18bitRGB666: return "OMX_COLOR_Format18bitRGB666";
case OMX_COLOR_Format18bitARGB1665: return "OMX_COLOR_Format18bitARGB1665";
case OMX_COLOR_Format19bitARGB1666: return "OMX_COLOR_Format19bitARGB1666";
case OMX_COLOR_Format24bitRGB888: return "OMX_COLOR_Format24bitRGB888";
case OMX_COLOR_Format24bitBGR888: return "OMX_COLOR_Format24bitBGR888";
case OMX_COLOR_Format24bitARGB1887: return "OMX_COLOR_Format24bitARGB1887";
case OMX_COLOR_Format25bitARGB1888: return "OMX_COLOR_Format25bitARGB1888";
case OMX_COLOR_Format32bitBGRA8888: return "OMX_COLOR_Format32bitBGRA8888";
case OMX_COLOR_Format32bitARGB8888: return "OMX_COLOR_Format32bitARGB8888";
case OMX_COLOR_FormatYUV411Planar: return "OMX_COLOR_FormatYUV411Planar";
case OMX_COLOR_FormatYUV411PackedPlanar: return "OMX_COLOR_FormatYUV411PackedPlanar";
case OMX_COLOR_FormatYUV420Planar: return "OMX_COLOR_FormatYUV420Planar";
case OMX_COLOR_FormatYUV420PackedPlanar: return "OMX_COLOR_FormatYUV420PackedPlanar";
case OMX_COLOR_FormatYUV420SemiPlanar: return "OMX_COLOR_FormatYUV420SemiPlanar"; case OMX_COLOR_FormatYUV420SemiPlanar: return "OMX_COLOR_FormatYUV420SemiPlanar";
case OMX_COLOR_FormatYUV422Planar: return "OMX_COLOR_FormatYUV422Planar";
case OMX_COLOR_FormatYUV422PackedPlanar: return "OMX_COLOR_FormatYUV422PackedPlanar";
case OMX_COLOR_FormatYUV422SemiPlanar: return "OMX_COLOR_FormatYUV422SemiPlanar";
case OMX_COLOR_FormatYCbYCr: return "OMX_COLOR_FormatYCbYCr";
case OMX_COLOR_FormatYCrYCb: return "OMX_COLOR_FormatYCrYCb";
case OMX_COLOR_FormatCbYCrY: return "OMX_COLOR_FormatCbYCrY";
case OMX_COLOR_FormatCrYCbY: return "OMX_COLOR_FormatCrYCbY";
case OMX_COLOR_FormatYUV444Interleaved: return "OMX_COLOR_FormatYUV444Interleaved";
case OMX_COLOR_FormatRawBayer8bit: return "OMX_COLOR_FormatRawBayer8bit";
case OMX_COLOR_FormatRawBayer10bit: return "OMX_COLOR_FormatRawBayer10bit";
case OMX_COLOR_FormatRawBayer8bitcompressed: return "OMX_COLOR_FormatRawBayer8bitcompressed";
case OMX_COLOR_FormatL2: return "OMX_COLOR_FormatL2";
case OMX_COLOR_FormatL4: return "OMX_COLOR_FormatL4";
case OMX_COLOR_FormatL8: return "OMX_COLOR_FormatL8";
case OMX_COLOR_FormatL16: return "OMX_COLOR_FormatL16";
case OMX_COLOR_FormatL24: return "OMX_COLOR_FormatL24";
case OMX_COLOR_FormatL32: return "OMX_COLOR_FormatL32";
case OMX_COLOR_FormatYUV420PackedSemiPlanar: return "OMX_COLOR_FormatYUV420PackedSemiPlanar";
case OMX_COLOR_FormatYUV422PackedSemiPlanar: return "OMX_COLOR_FormatYUV422PackedSemiPlanar";
case OMX_COLOR_Format18BitBGR666: return "OMX_COLOR_Format18BitBGR666";
case OMX_COLOR_Format24BitARGB6666: return "OMX_COLOR_Format24BitARGB6666";
case OMX_COLOR_Format24BitABGR6666: return "OMX_COLOR_Format24BitABGR6666";
case OMX_COLOR_FormatAndroidOpaque: return "OMX_COLOR_FormatAndroidOpaque";
case OMX_TI_COLOR_FormatYUV420PackedSemiPlanar: return "OMX_TI_COLOR_FormatYUV420PackedSemiPlanar";
case OMX_QCOM_COLOR_FormatYVU420SemiPlanar: return "OMX_QCOM_COLOR_FormatYVU420SemiPlanar";
case OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka: return "OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka";
case OMX_SEC_COLOR_FormatNV12Tiled: return "OMX_SEC_COLOR_FormatNV12Tiled";
case OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar32m: return "OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar32m"; case OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar32m: return "OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar32m";
case QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka: return "QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka";
case QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka: return "QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka";
case QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView: return "QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView";
case QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed: return "QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed";
case QOMX_COLOR_Format32bitRGBA8888: return "QOMX_COLOR_Format32bitRGBA8888"; case QOMX_COLOR_Format32bitRGBA8888: return "QOMX_COLOR_Format32bitRGBA8888";
case QOMX_COLOR_Format32bitRGBA8888Compressed: return "QOMX_COLOR_Format32bitRGBA8888Compressed"; default: return "unkn";
default:
return "unkn";
} }
} }
// ***** encoder functions ***** // ***** encoder functions *****
OmxEncoder::OmxEncoder(const char* path, int width, int height, int fps, int bitrate, bool h265, bool downscale) { OmxEncoder::OmxEncoder(const char* path, int width, int height, int fps, int bitrate) {
this->path = path; this->path = path;
this->width = width; this->width = width;
this->height = height; this->height = height;
this->fps = fps; this->fps = fps;
this->remuxing = !h265;
this->downscale = downscale; OMX_ERRORTYPE err = OMX_Init();
if (this->downscale) { if (err != OMX_ErrorNone) {
this->y_ptr2 = (uint8_t *)malloc(this->width*this->height); LOGE("OMX_Init failed: %x", err);
this->u_ptr2 = (uint8_t *)malloc(this->width*this->height/4); return;
this->v_ptr2 = (uint8_t *)malloc(this->width*this->height/4);
} }
auto component = (OMX_STRING)(h265 ? "OMX.qcom.video.encoder.hevc" : "OMX.qcom.video.encoder.avc"); OMX_STRING component = (OMX_STRING)("OMX.qcom.video.encoder.avc");
int err = OMX_GetHandle(&this->handle, component, this, &omx_callbacks); err = OMX_GetHandle(&handle, component, this, &omx_callbacks);
if (err != OMX_ErrorNone) { if (err != OMX_ErrorNone) {
LOGE("error getting codec: %x", err); LOGE("Error getting codec: %x", err);
OMX_Deinit();
return;
} }
// setup input port // setup input port
OMX_PARAM_PORTDEFINITIONTYPE in_port = {0}; OMX_PARAM_PORTDEFINITIONTYPE in_port = {0};
in_port.nSize = sizeof(in_port); in_port.nSize = sizeof(in_port);
in_port.nPortIndex = (OMX_U32) PORT_INDEX_IN; in_port.nPortIndex = (OMX_U32) PORT_INDEX_IN;
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); OMX_CHECK(OMX_GetParameter(handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port));
in_port.format.video.nFrameWidth = this->width; in_port.format.video.nFrameWidth = width;
in_port.format.video.nFrameHeight = this->height; in_port.format.video.nFrameHeight = height;
in_port.format.video.nStride = VENUS_Y_STRIDE(COLOR_FMT_NV12, this->width); in_port.format.video.nStride = VENUS_Y_STRIDE(COLOR_FMT_NV12, width);
in_port.format.video.nSliceHeight = this->height; in_port.format.video.nSliceHeight = height;
in_port.nBufferSize = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, this->width, this->height); in_port.nBufferSize = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, width, height);
in_port.format.video.xFramerate = (this->fps * 65536); in_port.format.video.xFramerate = (fps * 65536);
in_port.format.video.eCompressionFormat = OMX_VIDEO_CodingUnused; in_port.format.video.eCompressionFormat = OMX_VIDEO_CodingUnused;
in_port.format.video.eColorFormat = (OMX_COLOR_FORMATTYPE)QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m; in_port.format.video.eColorFormat = (OMX_COLOR_FORMATTYPE)QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m;
OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); OMX_CHECK(OMX_SetParameter(handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port));
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); OMX_CHECK(OMX_GetParameter(handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port));
this->in_buf_headers.resize(in_port.nBufferCountActual); in_buf_headers.resize(in_port.nBufferCountActual);
// setup output port // setup output port
OMX_PARAM_PORTDEFINITIONTYPE out_port;
OMX_PARAM_PORTDEFINITIONTYPE out_port = {0}; memset(&out_port, 0, sizeof(OMX_PARAM_PORTDEFINITIONTYPE));
out_port.nSize = sizeof(out_port); out_port.nSize = sizeof(out_port);
out_port.nVersion.s.nVersionMajor = 1;
out_port.nVersion.s.nVersionMinor = 0;
out_port.nVersion.s.nRevision = 0;
out_port.nVersion.s.nStep = 0;
out_port.nPortIndex = (OMX_U32) PORT_INDEX_OUT; out_port.nPortIndex = (OMX_U32) PORT_INDEX_OUT;
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR)&out_port));
out_port.format.video.nFrameWidth = this->width; OMX_ERRORTYPE error = OMX_GetParameter(handle, OMX_IndexParamPortDefinition, (OMX_PTR)&out_port);
out_port.format.video.nFrameHeight = this->height; if (error != OMX_ErrorNone) {
LOGE("Error getting output port parameters: 0x%08x", error);
return;
}
out_port.format.video.nFrameWidth = width;
out_port.format.video.nFrameHeight = height;
out_port.format.video.xFramerate = 0; out_port.format.video.xFramerate = 0;
out_port.format.video.nBitrate = bitrate; out_port.format.video.nBitrate = bitrate;
if (h265) { out_port.format.video.eCompressionFormat = OMX_VIDEO_CodingAVC;
out_port.format.video.eCompressionFormat = OMX_VIDEO_CodingHEVC;
} else {
out_port.format.video.eCompressionFormat = OMX_VIDEO_CodingAVC;
}
out_port.format.video.eColorFormat = OMX_COLOR_FormatUnused; out_port.format.video.eColorFormat = OMX_COLOR_FormatUnused;
OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port)); error = OMX_SetParameter(handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port);
if (error != OMX_ErrorNone) {
LOGE("Error setting output port parameters: 0x%08x", error);
return;
}
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port)); error = OMX_GetParameter(handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port);
this->out_buf_headers.resize(out_port.nBufferCountActual); if (error != OMX_ErrorNone) {
LOGE("Error getting updated output port parameters: 0x%08x", error);
return;
}
out_buf_headers.resize(out_port.nBufferCountActual);
OMX_VIDEO_PARAM_BITRATETYPE bitrate_type = {0}; OMX_VIDEO_PARAM_BITRATETYPE bitrate_type = {0};
bitrate_type.nSize = sizeof(bitrate_type); bitrate_type.nSize = sizeof(bitrate_type);
bitrate_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT; bitrate_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT;
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type)); OMX_CHECK(OMX_GetParameter(handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type));
bitrate_type.eControlRate = OMX_Video_ControlRateVariable; bitrate_type.eControlRate = OMX_Video_ControlRateVariable;
bitrate_type.nTargetBitrate = bitrate; bitrate_type.nTargetBitrate = bitrate;
OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type)); OMX_CHECK(OMX_SetParameter(handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type));
if (h265) { // setup h264
// setup HEVC OMX_VIDEO_PARAM_AVCTYPE avc = {0};
#ifndef QCOM2 avc.nSize = sizeof(avc);
OMX_VIDEO_PARAM_HEVCTYPE hevc_type = {0}; avc.nPortIndex = (OMX_U32) PORT_INDEX_OUT;
OMX_INDEXTYPE index_type = (OMX_INDEXTYPE) OMX_IndexParamVideoHevc; OMX_CHECK(OMX_GetParameter(handle, OMX_IndexParamVideoAvc, &avc));
#else
OMX_VIDEO_PARAM_PROFILELEVELTYPE hevc_type = {0};
OMX_INDEXTYPE index_type = OMX_IndexParamVideoProfileLevelCurrent;
#endif
hevc_type.nSize = sizeof(hevc_type);
hevc_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT;
OMX_CHECK(OMX_GetParameter(this->handle, index_type, (OMX_PTR) &hevc_type));
hevc_type.eProfile = OMX_VIDEO_HEVCProfileMain; avc.nBFrames = 0;
hevc_type.eLevel = OMX_VIDEO_HEVCHighTierLevel5; avc.nPFrames = 15;
OMX_CHECK(OMX_SetParameter(this->handle, index_type, (OMX_PTR) &hevc_type)); avc.eProfile = OMX_VIDEO_AVCProfileHigh;
} else { avc.eLevel = OMX_VIDEO_AVCLevel31;
// setup h264
OMX_VIDEO_PARAM_AVCTYPE avc = { 0 };
avc.nSize = sizeof(avc);
avc.nPortIndex = (OMX_U32) PORT_INDEX_OUT;
OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamVideoAvc, &avc));
avc.nBFrames = 0; avc.nAllowedPictureTypes |= OMX_VIDEO_PictureTypeB;
avc.nPFrames = 15; avc.eLoopFilterMode = OMX_VIDEO_AVCLoopFilterEnable;
avc.eProfile = OMX_VIDEO_AVCProfileHigh; avc.nRefFrames = 1;
avc.eLevel = OMX_VIDEO_AVCLevel31; avc.bUseHadamard = OMX_TRUE;
avc.bEntropyCodingCABAC = OMX_TRUE;
avc.bWeightedPPrediction = OMX_TRUE;
avc.bconstIpred = OMX_TRUE;
avc.nAllowedPictureTypes |= OMX_VIDEO_PictureTypeB; OMX_CHECK(OMX_SetParameter(handle, OMX_IndexParamVideoAvc, &avc));
avc.eLoopFilterMode = OMX_VIDEO_AVCLoopFilterEnable;
avc.nRefFrames = 1; OMX_CHECK(OMX_SendCommand(handle, OMX_CommandStateSet, OMX_StateIdle, NULL));
avc.bUseHadamard = OMX_TRUE;
avc.bEntropyCodingCABAC = OMX_TRUE;
avc.bWeightedPPrediction = OMX_TRUE;
avc.bconstIpred = OMX_TRUE;
OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamVideoAvc, &avc)); for (OMX_BUFFERHEADERTYPE* &buf : in_buf_headers) {
OMX_CHECK(OMX_AllocateBuffer(handle, &buf, PORT_INDEX_IN, this, in_port.nBufferSize));
} }
OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL)); for (OMX_BUFFERHEADERTYPE* &buf : out_buf_headers) {
OMX_CHECK(OMX_AllocateBuffer(handle, &buf, PORT_INDEX_OUT, this, out_port.nBufferSize));
for (auto &buf : this->in_buf_headers) {
OMX_CHECK(OMX_AllocateBuffer(this->handle, &buf, PORT_INDEX_IN, this,
in_port.nBufferSize));
}
for (auto &buf : this->out_buf_headers) {
OMX_CHECK(OMX_AllocateBuffer(this->handle, &buf, PORT_INDEX_OUT, this,
out_port.nBufferSize));
} }
wait_for_state(OMX_StateIdle); wait_for_state(OMX_StateIdle);
OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateExecuting, NULL)); OMX_CHECK(OMX_SendCommand(handle, OMX_CommandStateSet, OMX_StateExecuting, NULL));
wait_for_state(OMX_StateExecuting); wait_for_state(OMX_StateExecuting);
// give omx all the output buffers // give omx all the output buffers
for (auto &buf : this->out_buf_headers) { for (OMX_BUFFERHEADERTYPE* &buf : out_buf_headers) {
OMX_CHECK(OMX_FillThisBuffer(this->handle, buf)); OMX_CHECK(OMX_FillThisBuffer(handle, buf));
} }
// fill the input free queue // fill the input free queue
for (auto &buf : this->in_buf_headers) { for (OMX_BUFFERHEADERTYPE* &buf : in_buf_headers) {
this->free_in.push(buf); free_in.push(buf);
} }
} }
void OmxEncoder::handle_out_buf(OmxEncoder *e, OMX_BUFFERHEADERTYPE *out_buf) { void OmxEncoder::handle_out_buf(OmxEncoder *encoder, OMX_BUFFERHEADERTYPE *out_buf) {
int err; int err;
uint8_t *buf_data = out_buf->pBuffer + out_buf->nOffset; uint8_t *buf_data = out_buf->pBuffer + out_buf->nOffset;
if (out_buf->nFlags & OMX_BUFFERFLAG_CODECCONFIG) { if (out_buf->nFlags & OMX_BUFFERFLAG_CODECCONFIG) {
if (e->codec_config_len < out_buf->nFilledLen) { if (encoder->codec_config_len < out_buf->nFilledLen) {
e->codec_config = (uint8_t *)realloc(e->codec_config, out_buf->nFilledLen); encoder->codec_config = (uint8_t *)realloc(encoder->codec_config, out_buf->nFilledLen);
} }
e->codec_config_len = out_buf->nFilledLen; encoder->codec_config_len = out_buf->nFilledLen;
memcpy(e->codec_config, buf_data, out_buf->nFilledLen); memcpy(encoder->codec_config, buf_data, out_buf->nFilledLen);
#ifdef QCOM2 #ifdef QCOM2
out_buf->nTimeStamp = 0; out_buf->nTimeStamp = 0;
#endif #endif
} }
if (e->of) { if (encoder->of) {
fwrite(buf_data, out_buf->nFilledLen, 1, e->of); fwrite(buf_data, out_buf->nFilledLen, 1, encoder->of);
} }
if (e->remuxing) { if (!encoder->wrote_codec_config && encoder->codec_config_len > 0) {
if (!e->wrote_codec_config && e->codec_config_len > 0) { // extradata will be freed by av_free() in avcodec_free_context()
// extradata will be freed by av_free() in avcodec_free_context() encoder->out_stream->codecpar->extradata = (uint8_t*)av_mallocz(encoder->codec_config_len + AV_INPUT_BUFFER_PADDING_SIZE);
e->codec_ctx->extradata = (uint8_t*)av_mallocz(e->codec_config_len + AV_INPUT_BUFFER_PADDING_SIZE); encoder->out_stream->codecpar->extradata_size = encoder->codec_config_len;
e->codec_ctx->extradata_size = e->codec_config_len; memcpy(encoder->out_stream->codecpar->extradata, encoder->codec_config, encoder->codec_config_len);
memcpy(e->codec_ctx->extradata, e->codec_config, e->codec_config_len);
err = avcodec_parameters_from_context(e->out_stream->codecpar, e->codec_ctx); err = avformat_write_header(encoder->ofmt_ctx, NULL);
assert(err >= 0); assert(err >= 0);
err = avformat_write_header(e->ofmt_ctx, NULL);
assert(err >= 0);
e->wrote_codec_config = true; encoder->wrote_codec_config = true;
}
if (out_buf->nTimeStamp > 0) {
// input timestamps are in microseconds
AVRational in_timebase = {1, 1000000};
AVPacket pkt;
av_init_packet(&pkt);
pkt.data = buf_data;
pkt.size = out_buf->nFilledLen;
enum AVRounding rnd = static_cast<enum AVRounding>(AV_ROUND_NEAR_INF|AV_ROUND_PASS_MINMAX);
pkt.pts = pkt.dts = av_rescale_q_rnd(out_buf->nTimeStamp, in_timebase, encoder->out_stream->time_base, rnd);
pkt.duration = av_rescale_q(1, AVRational{1, encoder->fps}, encoder->out_stream->time_base);
if (out_buf->nFlags & OMX_BUFFERFLAG_SYNCFRAME) {
pkt.flags |= AV_PKT_FLAG_KEY;
} }
if (out_buf->nTimeStamp > 0) { err = av_write_frame(encoder->ofmt_ctx, &pkt);
// input timestamps are in microseconds if (err < 0) { LOGW("ts encoder write issue"); }
AVRational in_timebase = {1, 1000000};
AVPacket pkt; av_packet_unref(&pkt);
av_init_packet(&pkt);
pkt.data = buf_data;
pkt.size = out_buf->nFilledLen;
enum AVRounding rnd = static_cast<enum AVRounding>(AV_ROUND_NEAR_INF|AV_ROUND_PASS_MINMAX);
pkt.pts = pkt.dts = av_rescale_q_rnd(out_buf->nTimeStamp, in_timebase, e->ofmt_ctx->streams[0]->time_base, rnd);
pkt.duration = av_rescale_q(50*1000, in_timebase, e->ofmt_ctx->streams[0]->time_base);
if (out_buf->nFlags & OMX_BUFFERFLAG_SYNCFRAME) {
pkt.flags |= AV_PKT_FLAG_KEY;
}
err = av_write_frame(e->ofmt_ctx, &pkt);
if (err < 0) { LOGW("ts encoder write issue"); }
av_free_packet(&pkt);
}
} }
// give omx back the buffer // give omx back the buffer
@@ -508,134 +340,186 @@ void OmxEncoder::handle_out_buf(OmxEncoder *e, OMX_BUFFERHEADERTYPE *out_buf) {
out_buf->nTimeStamp = 0; out_buf->nTimeStamp = 0;
} }
#endif #endif
OMX_CHECK(OMX_FillThisBuffer(e->handle, out_buf)); OMX_CHECK(OMX_FillThisBuffer(encoder->handle, out_buf));
} }
int OmxEncoder::encode_frame_rgba(const uint8_t *ptr, int in_width, int in_height, uint64_t ts) { int OmxEncoder::encode_frame_rgba(const uint8_t *ptr, int in_width, int in_height, uint64_t ts) {
int err; if (!is_open) {
if (!this->is_open) {
return -1; return -1;
} }
// this sometimes freezes... put it outside the encoder lock so we can still trigger rotates...
// THIS IS A REALLY BAD IDEA, but apparently the race has to happen 30 times to trigger this
OMX_BUFFERHEADERTYPE* in_buf = nullptr; OMX_BUFFERHEADERTYPE* in_buf = nullptr;
while (!this->free_in.try_pop(in_buf, 20)) { while (!free_in.try_pop(in_buf, 20)) {
if (do_exit) { if (do_exit) {
return -1; return -1;
} }
} }
int ret = this->counter; int ret = counter;
uint8_t *in_buf_ptr = in_buf->pBuffer; uint8_t *in_buf_ptr = in_buf->pBuffer;
uint8_t *in_y_ptr = in_buf_ptr; uint8_t *in_y_ptr = in_buf_ptr;
int in_y_stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, this->width); int in_y_stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, width);
int in_uv_stride = VENUS_UV_STRIDE(COLOR_FMT_NV12, this->width); int in_uv_stride = VENUS_UV_STRIDE(COLOR_FMT_NV12, width);
uint8_t *in_uv_ptr = in_buf_ptr + (in_y_stride * VENUS_Y_SCANLINES(COLOR_FMT_NV12, this->height)); uint8_t *in_uv_ptr = in_buf_ptr + (in_y_stride * VENUS_Y_SCANLINES(COLOR_FMT_NV12, height));
err = ABGRToNV12(ptr, this->width*4, int err = ABGRToNV12(ptr, width * 4, in_y_ptr, in_y_stride, in_uv_ptr, in_uv_stride, width, height);
in_y_ptr, in_y_stride,
in_uv_ptr, in_uv_stride,
this->width, this->height);
assert(err == 0); assert(err == 0);
in_buf->nFilledLen = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, this->width, this->height); in_buf->nFilledLen = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, width, height);
in_buf->nFlags = OMX_BUFFERFLAG_ENDOFFRAME; in_buf->nFlags = OMX_BUFFERFLAG_ENDOFFRAME;
in_buf->nOffset = 0; in_buf->nOffset = 0;
in_buf->nTimeStamp = ts/1000LL; // OMX_TICKS, in microseconds in_buf->nTimeStamp = ts / 1000LL; // OMX_TICKS, in microseconds
this->last_t = in_buf->nTimeStamp; last_t = in_buf->nTimeStamp;
OMX_CHECK(OMX_EmptyThisBuffer(this->handle, in_buf)); OMX_CHECK(OMX_EmptyThisBuffer(handle, in_buf));
// pump output // pump output
while (true) { while (true) {
OMX_BUFFERHEADERTYPE *out_buf; OMX_BUFFERHEADERTYPE *out_buf;
if (!this->done_out.try_pop(out_buf)) { if (!done_out.try_pop(out_buf)) {
break; break;
} }
handle_out_buf(this, out_buf); handle_out_buf(this, out_buf);
} }
this->dirty = true; dirty = true;
this->counter++; counter++;
return ret;
}
// CLEARPILOT: encode raw NV12 frames directly (no RGBA conversion needed)
int OmxEncoder::encode_frame_nv12(const uint8_t *y_ptr, int y_stride, const uint8_t *uv_ptr, int uv_stride,
int in_width, int in_height, uint64_t ts) {
if (!is_open) {
return -1;
}
OMX_BUFFERHEADERTYPE* in_buf = nullptr;
while (!free_in.try_pop(in_buf, 20)) {
if (do_exit) {
return -1;
}
}
int ret = counter;
uint8_t *in_buf_ptr = in_buf->pBuffer;
int venus_y_stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, width);
int venus_uv_stride = VENUS_UV_STRIDE(COLOR_FMT_NV12, width);
uint8_t *dst_y = in_buf_ptr;
uint8_t *dst_uv = in_buf_ptr + (venus_y_stride * VENUS_Y_SCANLINES(COLOR_FMT_NV12, height));
// Copy Y plane row by row (source stride may differ from VENUS stride)
for (int row = 0; row < in_height; row++) {
memcpy(dst_y + row * venus_y_stride, y_ptr + row * y_stride, in_width);
}
// Copy UV plane row by row
int uv_height = in_height / 2;
for (int row = 0; row < uv_height; row++) {
memcpy(dst_uv + row * venus_uv_stride, uv_ptr + row * uv_stride, in_width);
}
in_buf->nFilledLen = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, width, height);
in_buf->nFlags = OMX_BUFFERFLAG_ENDOFFRAME;
in_buf->nOffset = 0;
in_buf->nTimeStamp = ts / 1000LL;
last_t = in_buf->nTimeStamp;
OMX_CHECK(OMX_EmptyThisBuffer(handle, in_buf));
while (true) {
OMX_BUFFERHEADERTYPE *out_buf;
if (!done_out.try_pop(out_buf)) {
break;
}
handle_out_buf(this, out_buf);
}
dirty = true;
counter++;
return ret; return ret;
} }
void OmxEncoder::encoder_open(const char* filename) { void OmxEncoder::encoder_open(const char* filename) {
int err; if (!filename || strlen(filename) == 0) {
return;
}
if (strlen(filename) + path.size() + 2 > sizeof(vid_path)) {
return;
}
struct stat st = {0}; struct stat st = {0};
if (stat(this->path.c_str(), &st) == -1) { if (stat(path.c_str(), &st) == -1) {
mkdir(this->path.c_str(), 0755); if (mkdir(path.c_str(), 0755) == -1) {
} return;
snprintf(this->vid_path, sizeof(this->vid_path), "%s/%s", this->path.c_str(), filename);
printf("encoder_open %s remuxing:%d\n", this->vid_path, this->remuxing);
if (this->remuxing) {
avformat_alloc_output_context2(&this->ofmt_ctx, NULL, NULL, this->vid_path);
assert(this->ofmt_ctx);
this->out_stream = avformat_new_stream(this->ofmt_ctx, NULL);
assert(this->out_stream);
// set codec correctly
av_register_all();
AVCodec *codec = NULL;
codec = avcodec_find_encoder(AV_CODEC_ID_H264);
assert(codec);
this->codec_ctx = avcodec_alloc_context3(codec);
assert(this->codec_ctx);
this->codec_ctx->width = this->width;
this->codec_ctx->height = this->height;
this->codec_ctx->pix_fmt = AV_PIX_FMT_YUV420P;
this->codec_ctx->time_base = (AVRational){ 1, this->fps };
err = avio_open(&this->ofmt_ctx->pb, this->vid_path, AVIO_FLAG_WRITE);
assert(err >= 0);
this->wrote_codec_config = false;
} else {
this->of = fopen(this->vid_path, "wb");
assert(this->of);
#ifndef QCOM2
if (this->codec_config_len > 0) {
fwrite(this->codec_config, this->codec_config_len, 1, this->of);
} }
#endif
} }
// create camera lock file snprintf(vid_path, sizeof(vid_path), "%s/%s", path.c_str(), filename);
snprintf(this->lock_path, sizeof(this->lock_path), "%s/%s.lock", this->path.c_str(), filename);
int lock_fd = HANDLE_EINTR(open(this->lock_path, O_RDWR | O_CREAT, 0664)); if (avformat_alloc_output_context2(&ofmt_ctx, NULL, NULL, vid_path) < 0 || !ofmt_ctx) {
assert(lock_fd >= 0); return;
}
out_stream = avformat_new_stream(ofmt_ctx, NULL);
if (!out_stream) {
avformat_free_context(ofmt_ctx);
ofmt_ctx = nullptr;
return;
}
out_stream->time_base = AVRational{1, fps};
out_stream->codecpar->codec_id = AV_CODEC_ID_H264;
out_stream->codecpar->codec_type = AVMEDIA_TYPE_VIDEO;
out_stream->codecpar->width = width;
out_stream->codecpar->height = height;
int err = avio_open(&ofmt_ctx->pb, vid_path, AVIO_FLAG_WRITE);
if (err < 0) {
avformat_free_context(ofmt_ctx);
ofmt_ctx = nullptr;
return;
}
wrote_codec_config = false;
snprintf(lock_path, sizeof(lock_path), "%s/%s.lock", path.c_str(), filename);
int lock_fd = HANDLE_EINTR(open(lock_path, O_RDWR | O_CREAT, 0664));
if (lock_fd < 0) {
avio_closep(&ofmt_ctx->pb);
avformat_free_context(ofmt_ctx);
ofmt_ctx = nullptr;
return;
}
close(lock_fd); close(lock_fd);
this->is_open = true; is_open = true;
this->counter = 0; counter = 0;
} }
void OmxEncoder::encoder_close() { void OmxEncoder::encoder_close() {
if (this->is_open) { if (!is_open) return;
if (this->dirty) {
// drain output only if there could be frames in the encoder
OMX_BUFFERHEADERTYPE* in_buf = this->free_in.pop(); if (dirty) {
OMX_BUFFERHEADERTYPE* in_buf = free_in.pop();
if (in_buf) {
in_buf->nFilledLen = 0; in_buf->nFilledLen = 0;
in_buf->nOffset = 0; in_buf->nOffset = 0;
in_buf->nFlags = OMX_BUFFERFLAG_EOS; in_buf->nFlags = OMX_BUFFERFLAG_EOS;
in_buf->nTimeStamp = this->last_t + 1000000LL/this->fps; in_buf->nTimeStamp = last_t + 1000000LL / fps;
OMX_CHECK(OMX_EmptyThisBuffer(this->handle, in_buf)); OMX_CHECK(OMX_EmptyThisBuffer(handle, in_buf));
while (true) { while (true) {
OMX_BUFFERHEADERTYPE *out_buf = this->done_out.pop(); OMX_BUFFERHEADERTYPE *out_buf = done_out.pop();
if (!out_buf) break;
handle_out_buf(this, out_buf); handle_out_buf(this, out_buf);
@@ -643,55 +527,112 @@ void OmxEncoder::encoder_close() {
break; break;
} }
} }
this->dirty = false;
} }
dirty = false;
if (this->remuxing) { }
av_write_trailer(this->ofmt_ctx);
avcodec_free_context(&this->codec_ctx); if (out_stream) {
avio_closep(&this->ofmt_ctx->pb); out_stream->nb_frames = counter;
avformat_free_context(this->ofmt_ctx); out_stream->duration = av_rescale_q(counter, AVRational{1, fps}, out_stream->time_base);
} else { }
fclose(this->of);
this->of = nullptr; if (ofmt_ctx) {
} av_write_trailer(ofmt_ctx);
unlink(this->lock_path); ofmt_ctx->duration = out_stream ? out_stream->duration : 0;
avio_closep(&ofmt_ctx->pb);
avformat_free_context(ofmt_ctx);
ofmt_ctx = nullptr;
out_stream = nullptr;
}
if (lock_path[0] != '\0') {
unlink(lock_path);
}
is_open = false;
// Remux with faststart for streaming/seeking support
if (strlen(vid_path) > 0) {
char fixed_path[1024];
snprintf(fixed_path, sizeof(fixed_path), "%s.fixed.mp4", vid_path);
char cmd[2048];
snprintf(cmd, sizeof(cmd), "ffmpeg -y -i \"%s\" -c copy -movflags +faststart \"%s\" && mv \"%s\" \"%s\"",
vid_path, fixed_path, fixed_path, vid_path);
int ret = system(cmd);
if (ret != 0) {
LOGW("ffmpeg faststart remux failed with exit code %d", ret);
}
} }
this->is_open = false;
} }
OmxEncoder::~OmxEncoder() { OmxEncoder::~OmxEncoder() {
assert(!this->is_open); if (is_open) {
LOGE("OmxEncoder closed with is_open=true, calling encoder_close()");
OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL)); encoder_close();
wait_for_state(OMX_StateIdle);
OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateLoaded, NULL));
for (auto &buf : this->in_buf_headers) {
OMX_CHECK(OMX_FreeBuffer(this->handle, PORT_INDEX_IN, buf));
} }
for (auto &buf : this->out_buf_headers) { if (!handle) {
OMX_CHECK(OMX_FreeBuffer(this->handle, PORT_INDEX_OUT, buf)); LOGE("OMX handle is null in destructor, skipping teardown.");
return;
}
OMX_ERRORTYPE err;
err = OMX_SendCommand(handle, OMX_CommandStateSet, OMX_StateIdle, NULL);
if (err != OMX_ErrorNone) {
LOGE("Failed to set OMX state to Idle: %x", err);
} else {
wait_for_state(OMX_StateIdle);
}
err = OMX_SendCommand(handle, OMX_CommandStateSet, OMX_StateLoaded, NULL);
if (err != OMX_ErrorNone) {
LOGE("Failed to set OMX state to Loaded: %x", err);
}
for (OMX_BUFFERHEADERTYPE *buf : in_buf_headers) {
if (buf) {
err = OMX_FreeBuffer(handle, PORT_INDEX_IN, buf);
if (err != OMX_ErrorNone) {
LOGE("Failed to free input buffer: %x", err);
}
}
}
for (OMX_BUFFERHEADERTYPE *buf : out_buf_headers) {
if (buf) {
err = OMX_FreeBuffer(handle, PORT_INDEX_OUT, buf);
if (err != OMX_ErrorNone) {
LOGE("Failed to free output buffer: %x", err);
}
}
} }
wait_for_state(OMX_StateLoaded); wait_for_state(OMX_StateLoaded);
OMX_CHECK(OMX_FreeHandle(this->handle)); err = OMX_FreeHandle(handle);
if (err != OMX_ErrorNone) {
LOGE("Failed to free OMX handle: %x", err);
}
handle = nullptr;
err = OMX_Deinit();
if (err != OMX_ErrorNone) {
LOGE("OMX_Deinit failed: %x", err);
}
OMX_BUFFERHEADERTYPE *out_buf; OMX_BUFFERHEADERTYPE *out_buf;
while (this->free_in.try_pop(out_buf)); while (free_in.try_pop(out_buf));
while (this->done_out.try_pop(out_buf)); while (done_out.try_pop(out_buf));
if (this->codec_config) { if (codec_config) {
free(this->codec_config); free(codec_config);
codec_config = nullptr;
} }
if (this->downscale) { in_buf_headers.clear();
free(this->y_ptr2); out_buf_headers.clear();
free(this->u_ptr2);
free(this->v_ptr2);
}
} }
@@ -12,13 +12,15 @@ extern "C" {
#include "common/queue.h" #include "common/queue.h"
// OmxEncoder, lossey codec using hardware hevc // OmxEncoder, lossey codec using hardware H.264
class OmxEncoder { class OmxEncoder {
public: public:
OmxEncoder(const char* path, int width, int height, int fps, int bitrate, bool h265, bool downscale); OmxEncoder(const char* path, int width, int height, int fps, int bitrate);
~OmxEncoder(); ~OmxEncoder();
int encode_frame_rgba(const uint8_t *ptr, int in_width, int in_height, uint64_t ts); int encode_frame_rgba(const uint8_t *ptr, int in_width, int in_height, uint64_t ts);
int encode_frame_nv12(const uint8_t *y_ptr, int y_stride, const uint8_t *uv_ptr, int uv_stride,
int in_width, int in_height, uint64_t ts);
void encoder_open(const char* filename); void encoder_open(const char* filename);
void encoder_close(); void encoder_close();
@@ -42,31 +44,26 @@ private:
int counter = 0; int counter = 0;
std::string path; std::string path;
FILE *of; FILE *of = nullptr;
size_t codec_config_len; size_t codec_config_len = 0;
uint8_t *codec_config = NULL; uint8_t *codec_config = nullptr;
bool wrote_codec_config; bool wrote_codec_config = false;
std::mutex state_lock; std::mutex state_lock;
std::condition_variable state_cv; std::condition_variable state_cv;
OMX_STATETYPE state = OMX_StateLoaded; OMX_STATETYPE state = OMX_StateLoaded;
OMX_HANDLETYPE handle; OMX_HANDLETYPE handle = nullptr;
std::vector<OMX_BUFFERHEADERTYPE *> in_buf_headers; std::vector<OMX_BUFFERHEADERTYPE *> in_buf_headers;
std::vector<OMX_BUFFERHEADERTYPE *> out_buf_headers; std::vector<OMX_BUFFERHEADERTYPE *> out_buf_headers;
uint64_t last_t; uint64_t last_t = 0;
SafeQueue<OMX_BUFFERHEADERTYPE *> free_in; SafeQueue<OMX_BUFFERHEADERTYPE *> free_in;
SafeQueue<OMX_BUFFERHEADERTYPE *> done_out; SafeQueue<OMX_BUFFERHEADERTYPE *> done_out;
AVFormatContext *ofmt_ctx; AVFormatContext *ofmt_ctx = nullptr;
AVCodecContext *codec_ctx; AVStream *out_stream = nullptr;
AVStream *out_stream;
bool remuxing;
bool downscale;
uint8_t *y_ptr2, *u_ptr2, *v_ptr2;
}; };
@@ -27,7 +27,7 @@ ScreenRecorder::ScreenRecorder(QWidget *parent) : QPushButton(parent), image_que
void ScreenRecorder::initializeEncoder() { void ScreenRecorder::initializeEncoder() {
const std::string path = "/data/media/0/videos"; const std::string path = "/data/media/0/videos";
encoder = std::make_unique<OmxEncoder>(path.c_str(), recording_width, recording_height, 60, 2 * 1024 * 1024, false, false); encoder = std::make_unique<OmxEncoder>(path.c_str(), recording_width, recording_height, 60, 2 * 1024 * 1024);
} }
ScreenRecorder::~ScreenRecorder() { ScreenRecorder::~ScreenRecorder() {
@@ -132,13 +132,20 @@ void ScreenRecorder::stop() {
} }
void ScreenRecorder::update_screen() { void ScreenRecorder::update_screen() {
if (!uiState()->scene.started) { bool car_on = uiState()->scene.started || uiState()->scene.screen_recorder_debug;
if (!car_on) {
if (recording) { if (recording) {
stop(); stop();
} }
return; return;
} }
if (!recording) return;
// CLEARPILOT: auto-start recording when car is on (or debug flag set)
if (!recording) {
start();
return;
}
if (milliseconds() - started > 1000 * 60 * 3) { if (milliseconds() - started > 1000 * 60 * 3) {
stop(); stop();
+8 -1
View File
@@ -284,7 +284,14 @@ def main() -> NoReturn:
# 4Hz driven by cameraOdometry # 4Hz driven by cameraOdometry
if sm.frame % 5 == 0: if sm.frame % 5 == 0:
calibrator.send_data(pm, sm.all_checks()) # CLEARPILOT: publish valid based on calibration status, not upstream sm.all_checks().
# The original gate cascaded upstream freq glitches into liveCalibration.valid=False,
# which kept locationd.filterInitialized False, which fed garbage into paramsd, which
# corrupted steerRatio and caused erratic steering (and controlsd commIssue banners).
# "valid" here semantically means "the calibration data is trustworthy" — a question
# about convergence, not input freshness.
cal_valid = calibrator.cal_status == log.LiveCalibrationData.Status.calibrated
calibrator.send_data(pm, cal_valid)
if __name__ == "__main__": if __name__ == "__main__":
+7 -1
View File
@@ -308,12 +308,18 @@ void Localizer::input_fake_gps_observations(double current_time) {
} }
void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset) { void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset) {
// CLEARPILOT: GPS disabled as a Kalman input. gpsd still publishes real GPS for
// UI / dashcam / clock / night-mode; only locationd ignores it. Falls through to
// determine_gps_mode() which is openpilot's existing no-GPS path (fake observations
// to bound position uncertainty). To re-enable, set this to false.
const bool clearpilot_disable_gps = true;
bool gps_unreasonable = (Vector2d(log.getHorizontalAccuracy(), log.getVerticalAccuracy()).norm() >= SANE_GPS_UNCERTAINTY); bool gps_unreasonable = (Vector2d(log.getHorizontalAccuracy(), log.getVerticalAccuracy()).norm() >= SANE_GPS_UNCERTAINTY);
bool gps_accuracy_insane = ((log.getVerticalAccuracy() <= 0) || (log.getSpeedAccuracy() <= 0) || (log.getBearingAccuracyDeg() <= 0)); bool gps_accuracy_insane = ((log.getVerticalAccuracy() <= 0) || (log.getSpeedAccuracy() <= 0) || (log.getBearingAccuracyDeg() <= 0));
bool gps_lat_lng_alt_insane = ((std::abs(log.getLatitude()) > 90) || (std::abs(log.getLongitude()) > 180) || (std::abs(log.getAltitude()) > ALTITUDE_SANITY_CHECK)); bool gps_lat_lng_alt_insane = ((std::abs(log.getLatitude()) > 90) || (std::abs(log.getLongitude()) > 180) || (std::abs(log.getAltitude()) > ALTITUDE_SANITY_CHECK));
bool gps_vel_insane = (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK); bool gps_vel_insane = (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK);
if (!log.getHasFix() || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane) { if (clearpilot_disable_gps || !log.getHasFix() || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane) {
//this->gps_valid = false; //this->gps_valid = false;
this->determine_gps_mode(current_time); this->determine_gps_mode(current_time);
return; return;
+6 -23
View File
@@ -56,19 +56,12 @@ def build(spinner: Spinner, dirty: bool = False, minimal: bool = False) -> None:
if scons.returncode == 0: if scons.returncode == 0:
Path('/data/openpilot/prebuilt').touch() Path('/data/openpilot/prebuilt').touch()
# CLEARPILOT: update prebuilt spinner if the new build is newer. # CLEARPILOT: update prebuilt spinner if the new build is newer
# Write to a temp path then os.replace so we can swap a binary that's
# currently executing (the in-process spinner holds the old one open).
new_spinner = Path(BASEDIR) / "selfdrive/ui/_spinner" new_spinner = Path(BASEDIR) / "selfdrive/ui/_spinner"
old_spinner = Path(BASEDIR) / "selfdrive/ui/qt/spinner" old_spinner = Path(BASEDIR) / "selfdrive/ui/qt/spinner"
if new_spinner.exists() and (not old_spinner.exists() or new_spinner.stat().st_mtime > old_spinner.stat().st_mtime): if new_spinner.exists() and (not old_spinner.exists() or new_spinner.stat().st_mtime > old_spinner.stat().st_mtime):
import shutil import shutil
try: shutil.copy2(str(new_spinner), str(old_spinner))
tmp_spinner = old_spinner.with_name(old_spinner.name + ".new")
shutil.copy2(str(new_spinner), str(tmp_spinner))
os.replace(str(tmp_spinner), str(old_spinner))
except OSError as e:
print(f"CLP failed to update prebuilt spinner: {e}", file=sys.stderr)
break break
@@ -85,23 +78,13 @@ def build(spinner: Spinner, dirty: bool = False, minimal: bool = False) -> None:
# Show TextWindow # Show TextWindow
spinner.close() spinner.close()
if not os.getenv("CI"): if not os.getenv("CI"):
msg = "openpilot failed to build\n \n" + error_s # CLEARPILOT: BUILD_ONLY mode shows error on screen but doesn't block
t = TextWindow("openpilot failed to build\n \n" + error_s)
if os.getenv("BUILD_ONLY"): if os.getenv("BUILD_ONLY"):
# CLEARPILOT: BUILD_ONLY mode — spawn the text window fully detached
# (own session, /dev/null stdio) so it stays on screen after this
# script exits and doesn't hold our stdout/stderr pipes open.
print(error_s, file=sys.stderr) print(error_s, file=sys.stderr)
devnull = open(os.devnull, 'r+b')
subprocess.Popen(
["./text", msg],
cwd=os.path.join(BASEDIR, "selfdrive", "ui"),
stdin=devnull, stdout=devnull, stderr=devnull,
start_new_session=True,
close_fds=True,
)
else: else:
with TextWindow(msg) as t: t.wait_for_exit()
t.wait_for_exit() t.close()
exit(1) exit(1)
# enforce max cache size # enforce max cache size
+62 -1
View File
@@ -16,7 +16,7 @@ from openpilot.common.text_window import TextWindow
from openpilot.common.time import system_time_valid from openpilot.common.time import system_time_valid
from openpilot.system.hardware import HARDWARE, PC from openpilot.system.hardware import HARDWARE, PC
from openpilot.selfdrive.manager.helpers import unblock_stdout, write_onroad_params, save_bootlog from openpilot.selfdrive.manager.helpers import unblock_stdout, write_onroad_params, save_bootlog
from openpilot.selfdrive.manager.process import ensure_running from openpilot.selfdrive.manager.process import ensure_running, init_log_dir, update_log_dir_timestamp, session_log
from openpilot.selfdrive.manager.process_config import managed_processes from openpilot.selfdrive.manager.process_config import managed_processes
from openpilot.selfdrive.athena.registration import register, UNREGISTERED_DONGLE_ID from openpilot.selfdrive.athena.registration import register, UNREGISTERED_DONGLE_ID
from openpilot.common.swaglog import cloudlog, add_file_handler from openpilot.common.swaglog import cloudlog, add_file_handler
@@ -51,7 +51,29 @@ def frogpilot_boot_functions(frogpilot_functions):
except Exception as e: except Exception as e:
print(f"An unexpected error occurred: {e}") print(f"An unexpected error occurred: {e}")
def cleanup_old_logs(max_age_days=30):
"""CLEARPILOT: delete session log directories older than max_age_days."""
import shutil
log_base = "/data/log2"
if not os.path.exists(log_base):
return
cutoff = time.time() - (max_age_days * 86400)
for entry in os.listdir(log_base):
if entry == "current":
continue
path = os.path.join(log_base, entry)
if os.path.isdir(path):
if os.path.getmtime(path) < cutoff:
try:
shutil.rmtree(path)
except OSError:
pass
def manager_init(frogpilot_functions) -> None: def manager_init(frogpilot_functions) -> None:
init_log_dir()
cleanup_old_logs()
frogpilot_boot = threading.Thread(target=frogpilot_boot_functions, args=(frogpilot_functions,)) frogpilot_boot = threading.Thread(target=frogpilot_boot_functions, args=(frogpilot_functions,))
frogpilot_boot.start() frogpilot_boot.start()
@@ -60,6 +82,27 @@ def manager_init(frogpilot_functions) -> None:
params = Params() params = Params()
params_storage = Params("/persist/params") params_storage = Params("/persist/params")
params.clear_all(ParamKeyType.CLEAR_ON_MANAGER_START) params.clear_all(ParamKeyType.CLEAR_ON_MANAGER_START)
# CLEARPILOT: always start with telemetry disabled, VPN enabled (memory params)
params_memory = Params("/dev/shm/params")
params_memory.put("TelemetryEnabled", "0")
params_memory.put("VpnEnabled", "1")
params_memory.put("DashcamFrames", "0")
params_memory.put("DashcamState", "stopped")
params_memory.put("DashcamShutdown", "0")
params_memory.put("ModelFps", "20")
params_memory.put("ModelStandby", "0")
params_memory.put("ShutdownTouchReset", "0")
params_memory.put("ModelStandbyTs", "0")
params_memory.put("CarIsMetric", "0")
params_memory.put("ClearpilotSpeedDisplay", "")
params_memory.put("ClearpilotSpeedLimitDisplay", "0")
params_memory.put("ClearpilotHasSpeed", "0")
params_memory.put("ClearpilotIsMetric", "0")
params_memory.put("ClearpilotSpeedUnit", "mph")
params_memory.put("ClearpilotCruiseWarning", "")
params_memory.put("ClearpilotCruiseWarningSpeed", "")
params_memory.put("ClearpilotPlayDing", "0")
params.clear_all(ParamKeyType.CLEAR_ON_ONROAD_TRANSITION) params.clear_all(ParamKeyType.CLEAR_ON_ONROAD_TRANSITION)
params.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION) params.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION)
if is_release_branch(): if is_release_branch():
@@ -135,6 +178,7 @@ def manager_init(frogpilot_functions) -> None:
("DisableOpenpilotLongitudinal", "0"), ("DisableOpenpilotLongitudinal", "0"),
("DisableVTSCSmoothing", "0"), ("DisableVTSCSmoothing", "0"),
("DisengageVolume", "100"), ("DisengageVolume", "100"),
("TelemetryEnabled", "0"),
("DragonPilotTune", "0"), ("DragonPilotTune", "0"),
("DriverCamera", "0"), ("DriverCamera", "0"),
("DynamicPathWidth", "0"), ("DynamicPathWidth", "0"),
@@ -229,6 +273,7 @@ def manager_init(frogpilot_functions) -> None:
("ScreenBrightnessOnroad", "101"), ("ScreenBrightnessOnroad", "101"),
("ScreenManagement", "1"), ("ScreenManagement", "1"),
("ScreenRecorder", "1"), ("ScreenRecorder", "1"),
("ScreenRecorderDebug", "1"),
("ScreenTimeout", "30"), ("ScreenTimeout", "30"),
("ScreenTimeoutOnroad", "30"), ("ScreenTimeoutOnroad", "30"),
("SearchInput", "0"), ("SearchInput", "0"),
@@ -365,6 +410,7 @@ def manager_thread(frogpilot_functions) -> None:
cloudlog.bind(daemon="manager") cloudlog.bind(daemon="manager")
cloudlog.info("manager start") cloudlog.info("manager start")
cloudlog.info({"environ": os.environ}) cloudlog.info({"environ": os.environ})
session_log.info("manager starting")
params = Params() params = Params()
params_memory = Params("/dev/shm/params") params_memory = Params("/dev/shm/params")
@@ -374,6 +420,14 @@ def manager_thread(frogpilot_functions) -> None:
ignore += ["manage_athenad", "uploader"] ignore += ["manage_athenad", "uploader"]
if os.getenv("NOBOARD") is not None: if os.getenv("NOBOARD") is not None:
ignore.append("pandad") ignore.append("pandad")
# CLEARPILOT: bench mode — disable real car processes, enable bench simulator
if os.getenv("BENCH_MODE") is not None:
ignore += ["pandad", "controlsd", "radard", "plannerd",
"calibrationd", "torqued", "paramsd", "locationd", "sensord",
"ubloxd", "pigeond", "dmonitoringmodeld", "dmonitoringd",
"modeld", "soundd", "loggerd", "micd",
"dashcamd"]
session_log.info("bench mode enabled")
ignore += [x for x in os.getenv("BLOCK", "").split(",") if len(x) > 0] ignore += [x for x in os.getenv("BLOCK", "").split(",") if len(x) > 0]
sm = messaging.SubMaster(['deviceState', 'carParams'], poll='deviceState') sm = messaging.SubMaster(['deviceState', 'carParams'], poll='deviceState')
@@ -395,6 +449,7 @@ def manager_thread(frogpilot_functions) -> None:
if started and not started_prev: if started and not started_prev:
params.clear_all(ParamKeyType.CLEAR_ON_ONROAD_TRANSITION) params.clear_all(ParamKeyType.CLEAR_ON_ONROAD_TRANSITION)
session_log.info("onroad transition")
if openpilot_crashed: if openpilot_crashed:
os.remove(os.path.join(sentry.CRASHES_DIR, 'error.txt')) os.remove(os.path.join(sentry.CRASHES_DIR, 'error.txt'))
@@ -402,6 +457,7 @@ def manager_thread(frogpilot_functions) -> None:
elif not started and started_prev: elif not started and started_prev:
params.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION) params.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION)
params_memory.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION) params_memory.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION)
session_log.info("offroad transition")
# update onroad params, which drives boardd's safety setter thread # update onroad params, which drives boardd's safety setter thread
if started != started_prev: if started != started_prev:
@@ -411,6 +467,9 @@ def manager_thread(frogpilot_functions) -> None:
ensure_running(managed_processes.values(), started, params=params, CP=sm['carParams'], not_run=ignore) ensure_running(managed_processes.values(), started, params=params, CP=sm['carParams'], not_run=ignore)
# CLEARPILOT: rename log directory once system time is valid
update_log_dir_timestamp()
running = ' '.join("{}{}\u001b[0m".format("\u001b[32m" if p.proc.is_alive() else "\u001b[31m", p.name) running = ' '.join("{}{}\u001b[0m".format("\u001b[32m" if p.proc.is_alive() else "\u001b[31m", p.name)
for p in managed_processes.values() if p.proc) for p in managed_processes.values() if p.proc)
print(running) print(running)
@@ -428,6 +487,7 @@ def manager_thread(frogpilot_functions) -> None:
shutdown = True shutdown = True
params.put("LastManagerExitReason", f"{param} {datetime.datetime.now()}") params.put("LastManagerExitReason", f"{param} {datetime.datetime.now()}")
cloudlog.warning(f"Shutting down manager - {param} set") cloudlog.warning(f"Shutting down manager - {param} set")
session_log.info("manager shutting down: %s", param)
if shutdown: if shutdown:
break break
@@ -479,6 +539,7 @@ if __name__ == "__main__":
except Exception: except Exception:
add_file_handler(cloudlog) add_file_handler(cloudlog)
cloudlog.exception("Manager failed to start") cloudlog.exception("Manager failed to start")
session_log.critical("manager failed to start: %s", traceback.format_exc())
try: try:
managed_processes['ui'].stop() managed_processes['ui'].stop()
+130 -7
View File
@@ -2,6 +2,7 @@ import importlib
import os import os
import signal import signal
import struct import struct
import sys
import datetime import datetime
import time import time
import subprocess import subprocess
@@ -17,17 +18,117 @@ import openpilot.selfdrive.sentry as sentry
from openpilot.common.basedir import BASEDIR from openpilot.common.basedir import BASEDIR
from openpilot.common.params import Params from openpilot.common.params import Params
from openpilot.common.swaglog import cloudlog from openpilot.common.swaglog import cloudlog
from openpilot.common.time import system_time_valid
WATCHDOG_FN = "/dev/shm/wd_" WATCHDOG_FN = "/dev/shm/wd_"
ENABLE_WATCHDOG = os.getenv("NO_WATCHDOG") is None ENABLE_WATCHDOG = os.getenv("NO_WATCHDOG") is None
timestamp = datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") # CLEARPILOT: logging directory and session log
_log_dir = f"/data/log2/{timestamp}" # init_log_dir() must be called once from manager_init() before any process starts.
os.makedirs(_log_dir, exist_ok=True) # Until then, _log_dir and session_log are usable but write to a NullHandler.
import logging
_log_dir = "/data/log2/current"
_time_resolved = False
_session_handler = None
session_log = logging.getLogger("clearpilot.session")
session_log.setLevel(logging.DEBUG)
session_log.addHandler(logging.NullHandler())
def init_log_dir():
"""Create /data/log2/current as a real directory for this session.
Called once from manager_init(). Previous current (if a real dir) is
renamed to a timestamp or boot-monotonic name before we create a fresh one."""
global _log_dir, _time_resolved, _session_handler
log_base = "/data/log2"
current = os.path.join(log_base, "current")
os.makedirs(log_base, exist_ok=True)
# If 'current' is a symlink, just remove the symlink
if os.path.islink(current):
os.unlink(current)
# If 'current' is a real directory (leftover from previous session that
# never got time-resolved), rename it out of the way
elif os.path.isdir(current):
# Use mtime of session.log (or the dir itself) for the rename
session_file = os.path.join(current, "session.log")
mtime = os.path.getmtime(session_file) if os.path.exists(session_file) else os.path.getmtime(current)
ts = datetime.datetime.fromtimestamp(mtime).strftime('%Y-%m-%d-%H-%M-%S')
dest = os.path.join(log_base, ts)
# Avoid collision
if os.path.exists(dest):
dest = dest + f"-{int(time.monotonic())}"
try:
os.rename(current, dest)
except OSError:
pass
os.makedirs(current, exist_ok=True)
_log_dir = current
_time_resolved = False
# Set up session log file handler
_session_handler = logging.FileHandler(os.path.join(_log_dir, "session.log"))
_session_handler.setFormatter(logging.Formatter("%(asctime)s %(levelname)s %(message)s"))
# Remove NullHandler and add file handler
session_log.handlers.clear()
session_log.addHandler(_session_handler)
session_log.info("session started, log dir: %s", _log_dir)
def update_log_dir_timestamp():
"""Rename /data/log2/current to a real timestamp and replace with a symlink
once system time is valid."""
global _log_dir, _time_resolved, _session_handler
if _time_resolved:
return
if not system_time_valid():
return
log_base = "/data/log2"
current = os.path.join(log_base, "current")
ts_name = datetime.datetime.now().strftime('%Y-%m-%d-%H-%M-%S')
new_dir = os.path.join(log_base, ts_name)
try:
os.rename(current, new_dir)
# Create symlink: current -> YYYY-MM-DD-HH-MM-SS
os.symlink(ts_name, current)
_log_dir = new_dir
_time_resolved = True
# Re-point session log handler (open files follow the inode, but
# new opens should go through the symlink — update handler for clarity)
session_log.removeHandler(_session_handler)
_session_handler.close()
_session_handler = logging.FileHandler(os.path.join(_log_dir, "session.log"))
_session_handler.setFormatter(logging.Formatter("%(asctime)s %(levelname)s %(message)s"))
session_log.addHandler(_session_handler)
session_log.info("log directory renamed to %s", _log_dir)
# Signal via param that the directory has been time-resolved
try:
from openpilot.common.params import Params
Params().put("LogDirInitialized", "1")
except Exception:
pass
except OSError:
pass
def launcher(proc: str, name: str) -> None: def launcher(proc: str, name: str, log_path: str) -> None:
# CLEARPILOT: redirect stderr to per-process log file
try:
log_file = open(log_path, 'a')
os.dup2(log_file.fileno(), sys.stderr.fileno())
os.dup2(log_file.fileno(), sys.stdout.fileno())
except Exception as e:
print(f"CLEARPILOT: stderr redirect failed for {name}: {e}", file=sys.stderr)
try: try:
# import the process # import the process
mod = importlib.import_module(proc) mod = importlib.import_module(proc)
@@ -53,9 +154,17 @@ def launcher(proc: str, name: str) -> None:
raise raise
def nativelauncher(pargs: list[str], cwd: str, name: str) -> None: def nativelauncher(pargs: list[str], cwd: str, name: str, log_path: str) -> None:
os.environ['MANAGER_DAEMON'] = name os.environ['MANAGER_DAEMON'] = name
# CLEARPILOT: redirect stderr and stdout to per-process log file
try:
log_file = open(log_path, 'a')
os.dup2(log_file.fileno(), sys.stderr.fileno())
os.dup2(log_file.fileno(), sys.stdout.fileno())
except Exception as e:
print(f"CLEARPILOT: stderr redirect failed for {name}: {e}", file=sys.stderr)
# exec the process # exec the process
os.chdir(cwd) os.chdir(cwd)
os.execvp(pargs[0], pargs) os.execvp(pargs[0], pargs)
@@ -110,6 +219,7 @@ class ManagerProcess(ABC):
if dt > self.watchdog_max_dt: if dt > self.watchdog_max_dt:
if (self.watchdog_seen or self.always_watchdog and self.proc.exitcode is not None) and ENABLE_WATCHDOG: if (self.watchdog_seen or self.always_watchdog and self.proc.exitcode is not None) and ENABLE_WATCHDOG:
cloudlog.error(f"Watchdog timeout for {self.name} (exitcode {self.proc.exitcode}) restarting ({started=})") cloudlog.error(f"Watchdog timeout for {self.name} (exitcode {self.proc.exitcode}) restarting ({started=})")
session_log.warning("watchdog timeout for %s (exitcode %s), restarting", self.name, self.proc.exitcode)
self.restart() self.restart()
else: else:
self.watchdog_seen = True self.watchdog_seen = True
@@ -139,6 +249,10 @@ class ManagerProcess(ABC):
ret = self.proc.exitcode ret = self.proc.exitcode
cloudlog.info(f"{self.name} is dead with {ret}") cloudlog.info(f"{self.name} is dead with {ret}")
if ret is not None and ret != 0:
session_log.error("process %s died with exit code %s", self.name, ret)
elif ret == 0:
session_log.info("process %s stopped (exit 0)", self.name)
if self.proc.exitcode is not None: if self.proc.exitcode is not None:
self.shutting_down = False self.shutting_down = False
@@ -198,9 +312,13 @@ class NativeProcess(ManagerProcess):
global _log_dir global _log_dir
log_path = _log_dir+"/"+self.name+".log" log_path = _log_dir+"/"+self.name+".log"
# CLEARPILOT: ensure log file exists even if child redirect fails
open(log_path, 'a').close()
cwd = os.path.join(BASEDIR, self.cwd) cwd = os.path.join(BASEDIR, self.cwd)
cloudlog.info(f"starting process {self.name}") cloudlog.info(f"starting process {self.name}")
self.proc = Process(name=self.name, target=self.launcher, args=(self.cmdline, cwd, self.name)) session_log.info("starting %s", self.name)
self.proc = Process(name=self.name, target=self.launcher, args=(self.cmdline, cwd, self.name, log_path))
self.proc.start() self.proc.start()
self.watchdog_seen = False self.watchdog_seen = False
self.shutting_down = False self.shutting_down = False
@@ -231,8 +349,12 @@ class PythonProcess(ManagerProcess):
global _log_dir global _log_dir
log_path = _log_dir+"/"+self.name+".log" log_path = _log_dir+"/"+self.name+".log"
# CLEARPILOT: ensure log file exists even if child redirect fails
open(log_path, 'a').close()
cloudlog.info(f"starting python {self.module}") cloudlog.info(f"starting python {self.module}")
self.proc = Process(name=self.name, target=self.launcher, args=(self.module, self.name)) session_log.info("starting %s", self.name)
self.proc = Process(name=self.name, target=self.launcher, args=(self.module, self.name, log_path))
self.proc.start() self.proc.start()
self.watchdog_seen = False self.watchdog_seen = False
self.shutting_down = False self.shutting_down = False
@@ -276,6 +398,7 @@ class DaemonProcess(ManagerProcess):
pass pass
cloudlog.info(f"starting daemon {self.name}") cloudlog.info(f"starting daemon {self.name}")
session_log.info("starting daemon %s", self.name)
proc = subprocess.Popen(['python', '-m', self.module], proc = subprocess.Popen(['python', '-m', self.module],
stdin=open('/dev/null'), stdin=open('/dev/null'),
stdout=open(log_path, 'a'), stdout=open(log_path, 'a'),
+16 -4
View File
@@ -7,6 +7,7 @@ from openpilot.selfdrive.manager.process import PythonProcess, NativeProcess, Da
WEBCAM = os.getenv("USE_WEBCAM") is not None WEBCAM = os.getenv("USE_WEBCAM") is not None
BENCH_MODE = os.getenv("BENCH_MODE") is not None
def driverview(started: bool, params: Params, CP: car.CarParams) -> bool: def driverview(started: bool, params: Params, CP: car.CarParams) -> bool:
return started or params.get_bool("IsDriverViewEnabled") return started or params.get_bool("IsDriverViewEnabled")
@@ -51,10 +52,14 @@ def allow_uploads(started, params, CP: car.CarParams) -> bool:
allow_uploads = not (params.get_bool("DeviceManagement") and params.get_bool("NoUploads")) allow_uploads = not (params.get_bool("DeviceManagement") and params.get_bool("NoUploads"))
return allow_uploads return allow_uploads
# ClearPilot functions
def dashcam_should_run(started, params, CP: car.CarParams) -> bool:
return True # CLEARPILOT: dashcamd manages its own trip lifecycle
procs = [ procs = [
DaemonProcess("manage_athenad", "selfdrive.athena.manage_athenad", "AthenadPid"), DaemonProcess("manage_athenad", "selfdrive.athena.manage_athenad", "AthenadPid"),
NativeProcess("camerad", "system/camerad", ["./camerad"], driverview), NativeProcess("camerad", "system/camerad", ["./camerad"], always_run),
NativeProcess("logcatd", "system/logcatd", ["./logcatd"], allow_logging), NativeProcess("logcatd", "system/logcatd", ["./logcatd"], allow_logging),
NativeProcess("proclogd", "system/proclogd", ["./proclogd"], allow_logging), NativeProcess("proclogd", "system/proclogd", ["./proclogd"], allow_logging),
PythonProcess("logmessaged", "system.logmessaged", allow_logging), PythonProcess("logmessaged", "system.logmessaged", allow_logging),
@@ -62,8 +67,9 @@ procs = [
PythonProcess("timed", "system.timed", always_run, enabled=not PC), PythonProcess("timed", "system.timed", always_run, enabled=not PC),
PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(not PC or WEBCAM)), PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(not PC or WEBCAM)),
NativeProcess("encoderd", "system/loggerd", ["./encoderd"], allow_logging), # CLEARPILOT: disabled video encoding (camera .hevc files) — CAN/sensor logs still recorded via loggerd
NativeProcess("stream_encoderd", "system/loggerd", ["./encoderd", "--stream"], notcar), # NativeProcess("encoderd", "system/loggerd", ["./encoderd"], allow_logging),
# NativeProcess("stream_encoderd", "system/loggerd", ["./encoderd", "--stream"], notcar),
NativeProcess("loggerd", "system/loggerd", ["./loggerd"], allow_logging), NativeProcess("loggerd", "system/loggerd", ["./loggerd"], allow_logging),
NativeProcess("modeld", "selfdrive/modeld", ["./modeld"], only_onroad), NativeProcess("modeld", "selfdrive/modeld", ["./modeld"], only_onroad),
#NativeProcess("mapsd", "selfdrive/navd", ["./mapsd"], only_onroad), #NativeProcess("mapsd", "selfdrive/navd", ["./mapsd"], only_onroad),
@@ -78,7 +84,8 @@ procs = [
PythonProcess("controlsd", "selfdrive.controls.controlsd", only_onroad), PythonProcess("controlsd", "selfdrive.controls.controlsd", only_onroad),
PythonProcess("deleter", "system.loggerd.deleter", always_run), PythonProcess("deleter", "system.loggerd.deleter", always_run),
PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", driverview, enabled=(not PC or WEBCAM)), PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", driverview, enabled=(not PC or WEBCAM)),
# PythonProcess("qcomgpsd", "system.qcomgpsd.qcomgpsd", qcomgps, enabled=TICI), # Fixme # PythonProcess("qcomgpsd", "system.qcomgpsd.qcomgpsd", qcomgps, enabled=TICI),
PythonProcess("gpsd", "system.clearpilot.gpsd", qcomgps, enabled=TICI),
# PythonProcess("ugpsd", "system.ugpsd", only_onroad, enabled=TICI), # PythonProcess("ugpsd", "system.ugpsd", only_onroad, enabled=TICI),
#PythonProcess("navd", "selfdrive.navd.navd", only_onroad), #PythonProcess("navd", "selfdrive.navd.navd", only_onroad),
PythonProcess("pandad", "selfdrive.boardd.pandad", always_run), PythonProcess("pandad", "selfdrive.boardd.pandad", always_run),
@@ -101,6 +108,11 @@ procs = [
# FrogPilot processes # FrogPilot processes
PythonProcess("fleet_manager", "selfdrive.frogpilot.fleetmanager.fleet_manager", always_run), PythonProcess("fleet_manager", "selfdrive.frogpilot.fleetmanager.fleet_manager", always_run),
PythonProcess("frogpilot_process", "selfdrive.frogpilot.frogpilot_process", always_run), PythonProcess("frogpilot_process", "selfdrive.frogpilot.frogpilot_process", always_run),
# ClearPilot processes
NativeProcess("dashcamd", "selfdrive/clearpilot", ["./dashcamd"], dashcam_should_run),
PythonProcess("telemetryd", "selfdrive.clearpilot.telemetryd", always_run),
PythonProcess("bench_onroad", "selfdrive.clearpilot.bench_onroad", always_run, enabled=BENCH_MODE),
] ]
managed_processes = {p.name: p for p in procs} managed_processes = {p.name: p for p in procs}
+13 -3
View File
@@ -7,7 +7,7 @@ import ctypes
import numpy as np import numpy as np
from pathlib import Path from pathlib import Path
from cereal import messaging from cereal import car, messaging
from cereal.messaging import PubMaster, SubMaster from cereal.messaging import PubMaster, SubMaster
from cereal.visionipc import VisionIpcClient, VisionStreamType, VisionBuf from cereal.visionipc import VisionIpcClient, VisionStreamType, VisionBuf
from openpilot.common.swaglog import cloudlog from openpilot.common.swaglog import cloudlog
@@ -128,10 +128,15 @@ def main():
assert vipc_client.is_connected() assert vipc_client.is_connected()
cloudlog.warning(f"connected with buffer size: {vipc_client.buffer_len}") cloudlog.warning(f"connected with buffer size: {vipc_client.buffer_len}")
sm = SubMaster(["liveCalibration"]) sm = SubMaster(["liveCalibration", "carState"])
pm = PubMaster(["driverStateV2"]) pm = PubMaster(["driverStateV2"])
calib = np.zeros(CALIB_LEN, dtype=np.float32) calib = np.zeros(CALIB_LEN, dtype=np.float32)
# CLEARPILOT: cache last model output to serve while gear is in park —
# mirrors the same trick modeld uses. Skips DSP inference on the driver
# camera when the car is stationary; downstream dmonitoringd still gets
# a fresh publish each frame.
last_model_output = None
# last = 0 # last = 0
while True: while True:
@@ -143,8 +148,13 @@ def main():
if sm.updated["liveCalibration"]: if sm.updated["liveCalibration"]:
calib[:] = np.array(sm["liveCalibration"].rpyCalib) calib[:] = np.array(sm["liveCalibration"].rpyCalib)
parked = sm["carState"].gearShifter == car.CarState.GearShifter.park
t1 = time.perf_counter() t1 = time.perf_counter()
model_output, dsp_execution_time = model.run(buf, calib) if parked and last_model_output is not None:
model_output, dsp_execution_time = last_model_output
else:
model_output, dsp_execution_time = model.run(buf, calib)
last_model_output = (model_output, dsp_execution_time)
t2 = time.perf_counter() t2 = time.perf_counter()
pm.send("driverStateV2", get_driverstate_packet(model_output, vipc_client.frame_id, vipc_client.timestamp_sof, t2 - t1, dsp_execution_time)) pm.send("driverStateV2", get_driverstate_packet(model_output, vipc_client.frame_id, vipc_client.timestamp_sof, t2 - t1, dsp_execution_time))
+29 -6
View File
@@ -134,11 +134,15 @@ def main(demo=False):
setproctitle(PROCESS_NAME) setproctitle(PROCESS_NAME)
config_realtime_process(7, 54) config_realtime_process(7, 54)
import time as _time
cloudlog.warning("setting up CL context") cloudlog.warning("setting up CL context")
_t0 = _time.monotonic()
cl_context = CLContext() cl_context = CLContext()
cloudlog.warning("CL context ready; loading model") _t1 = _time.monotonic()
cloudlog.warning("CL context ready in %.3fs; loading model", _t1 - _t0)
model = ModelState(cl_context) model = ModelState(cl_context)
cloudlog.warning("models loaded, modeld starting") _t2 = _time.monotonic()
cloudlog.warning("model loaded in %.3fs (total init %.3fs), modeld starting", _t2 - _t1, _t2 - _t0)
# visionipc clients # visionipc clients
while True: while True:
@@ -179,6 +183,10 @@ def main(demo=False):
model_transform_main = np.zeros((3, 3), dtype=np.float32) model_transform_main = np.zeros((3, 3), dtype=np.float32)
model_transform_extra = np.zeros((3, 3), dtype=np.float32) model_transform_extra = np.zeros((3, 3), dtype=np.float32)
live_calib_seen = False live_calib_seen = False
# CLEARPILOT: cache last model output to serve while gear is in park — saves
# GPU inference cost while still giving downstream a constant publish rate so
# freq_ok / valid checks don't cascade.
last_model_output = None
nav_features = np.zeros(ModelConstants.NAV_FEATURE_LEN, dtype=np.float32) nav_features = np.zeros(ModelConstants.NAV_FEATURE_LEN, dtype=np.float32)
nav_instructions = np.zeros(ModelConstants.NAV_INSTRUCTION_LEN, dtype=np.float32) nav_instructions = np.zeros(ModelConstants.NAV_INSTRUCTION_LEN, dtype=np.float32)
buf_main, buf_extra = None, None buf_main, buf_extra = None, None
@@ -233,6 +241,12 @@ def main(demo=False):
meta_extra = meta_main meta_extra = meta_main
sm.update(0) sm.update(0)
# CLEARPILOT: constant 20fps. Variable-rate + standby logic removed — the
# variable-rate path caused freq_ok cascades in downstream consumers
# (calibrationd/locationd/paramsd). Running at the camera's native rate is
# simpler and keeps the full-stack localization chain happy.
desire = DH.desire desire = DH.desire
is_rhd = sm["driverMonitoringState"].isRHD is_rhd = sm["driverMonitoringState"].isRHD
frame_id = sm["roadCameraState"].frameId frame_id = sm["roadCameraState"].frameId
@@ -304,12 +318,21 @@ def main(demo=False):
**({'radar_tracks': radar_tracks,} if DISABLE_RADAR else {}), **({'radar_tracks': radar_tracks,} if DISABLE_RADAR else {}),
} }
mt1 = time.perf_counter() # CLEARPILOT: in park, serve the cached last model output instead of running
model_output = model.run(buf_main, buf_extra, model_transform_main, model_transform_extra, inputs, prepare_only) # GPU inference. First cycle (no cache yet) still runs once so we have
mt2 = time.perf_counter() # something to serve. Out-of-park resumes fresh inference every frame.
model_execution_time = mt2 - mt1 parked = sm['carState'].gearShifter == car.CarState.GearShifter.park
if parked and last_model_output is not None:
model_output = last_model_output
model_execution_time = 0.0
else:
mt1 = time.perf_counter()
model_output = model.run(buf_main, buf_extra, model_transform_main, model_transform_extra, inputs, prepare_only)
mt2 = time.perf_counter()
model_execution_time = mt2 - mt1
if model_output is not None: if model_output is not None:
last_model_output = model_output
modelv2_send = messaging.new_message('modelV2') modelv2_send = messaging.new_message('modelV2')
posenet_send = messaging.new_message('cameraOdometry') posenet_send = messaging.new_message('cameraOdometry')
fill_model_msg(modelv2_send, model_output, publish_state, meta_main.frame_id, meta_extra.frame_id, frame_id, frame_drop_ratio, fill_model_msg(modelv2_send, model_output, publish_state, meta_main.frame_id, meta_extra.frame_id, frame_id, frame_drop_ratio,
+22 -2
View File
@@ -21,6 +21,7 @@ def dmonitoringd_thread():
v_cruise_last = 0 v_cruise_last = 0
driver_engaged = False driver_engaged = False
dbg_prev_valid = True # CLEARPILOT: track valid transitions
# 10Hz <- dmonitoringmodeld # 10Hz <- dmonitoringmodeld
while True: while True:
@@ -43,7 +44,18 @@ def dmonitoringd_thread():
# Get data from dmonitoringmodeld # Get data from dmonitoringmodeld
events = Events() events = Events()
if sm.all_checks() and len(sm['liveCalibration'].rpyCalib): # CLEARPILOT: narrow update_states gate. The original sm.all_checks() also
# required modelV2 fresh (stops at standstill in two-state modeld) and
# liveCalibration.valid (calibrationd cascades its own freq_ok to valid, which
# flaps). Both made DM freeze pose → face_detected stuck False → awareness
# decayed to 0 within 6s of engagement. Narrow the gate to the subs
# update_states actually reads, and only to alive+valid (skip freq_ok and
# skip liveCalibration.valid). rpyCalib presence is sufficient to know
# calibration has produced output.
if (sm.alive['driverStateV2'] and sm.valid['driverStateV2'] and
sm.alive['carState'] and sm.valid['carState'] and
sm.alive['controlsState'] and sm.valid['controlsState'] and
sm.alive['liveCalibration'] and len(sm['liveCalibration'].rpyCalib) > 0):
driver_status.update_states(sm['driverStateV2'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['controlsState'].enabled) driver_status.update_states(sm['driverStateV2'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['controlsState'].enabled)
# Block engaging after max number of distrations # Block engaging after max number of distrations
@@ -54,8 +66,16 @@ def dmonitoringd_thread():
# Update events from driver state # Update events from driver state
driver_status.update_events(events, driver_engaged, sm['controlsState'].enabled, sm['carState'].standstill) driver_status.update_events(events, driver_engaged, sm['controlsState'].enabled, sm['carState'].standstill)
# CLEARPILOT: log on transition to invalid so we can see which sub caused the cascade
dm_valid = sm.all_checks()
if dm_valid != dbg_prev_valid and not dm_valid:
import sys
bad = [s for s in sm.alive if not (sm.alive[s] and sm.valid[s] and sm.freq_ok.get(s, True))]
details = [f"{s}(a={sm.alive[s]},v={sm.valid[s]},f={sm.freq_ok[s]})" for s in bad]
print(f"CLP driverMonitoringState valid=False: {' '.join(details)}", file=sys.stderr, flush=True)
dbg_prev_valid = dm_valid
# build driverMonitoringState packet # build driverMonitoringState packet
dat = messaging.new_message('driverMonitoringState', valid=sm.all_checks()) dat = messaging.new_message('driverMonitoringState', valid=dm_valid)
dat.driverMonitoringState = { dat.driverMonitoringState = {
"events": events.to_msg(), "events": events.to_msg(),
"faceDetected": driver_status.face_detected, "faceDetected": driver_status.face_detected,
+24 -4
View File
@@ -6,9 +6,11 @@ from openpilot.common.numpy_fast import interp
from openpilot.common.swaglog import cloudlog from openpilot.common.swaglog import cloudlog
from openpilot.selfdrive.controls.lib.pid import PIDController from openpilot.selfdrive.controls.lib.pid import PIDController
class BaseFanController(ABC): class BaseFanController(ABC):
@abstractmethod @abstractmethod
def update(self, cur_temp: float, ignition: bool) -> int: def update(self, cur_temp: float, ignition: bool, standstill: bool = False,
is_parked: bool = True, cruise_engaged: bool = False) -> int:
pass pass
@@ -20,9 +22,27 @@ class TiciFanController(BaseFanController):
self.last_ignition = False self.last_ignition = False
self.controller = PIDController(k_p=0, k_i=4e-3, k_f=1, rate=(1 / DT_TRML)) self.controller = PIDController(k_p=0, k_i=4e-3, k_f=1, rate=(1 / DT_TRML))
def update(self, cur_temp: float, ignition: bool) -> int: def update(self, cur_temp: float, ignition: bool, standstill: bool = False,
self.controller.neg_limit = -(100 if ignition else 30) is_parked: bool = True, cruise_engaged: bool = False) -> int:
self.controller.pos_limit = -(30 if ignition else 0) # CLEARPILOT fan range rules:
# parked → 0-100% (full, no floor)
# in drive + cruise engaged (any speed, inc standstill) → 30-100%
# in drive + cruise off + standstill → 10-100%
# in drive + cruise off + moving → 30-100%
# In the PID output, neg_limit is how negative it can go (= max fan as %),
# pos_limit is how positive (= negative of min fan %).
if is_parked:
self.controller.neg_limit = -100
self.controller.pos_limit = 0
elif cruise_engaged:
self.controller.neg_limit = -100
self.controller.pos_limit = -30
elif standstill:
self.controller.neg_limit = -100
self.controller.pos_limit = -10
else:
self.controller.neg_limit = -100
self.controller.pos_limit = -30
if ignition != self.last_ignition: if ignition != self.last_ignition:
self.controller.reset() self.controller.reset()
+10 -7
View File
@@ -36,12 +36,9 @@ class PowerMonitoring:
# Reset capacity if it's low # Reset capacity if it's low
self.car_battery_capacity_uWh = max((CAR_BATTERY_CAPACITY_uWh / 10), int(car_battery_capacity_uWh)) self.car_battery_capacity_uWh = max((CAR_BATTERY_CAPACITY_uWh / 10), int(car_battery_capacity_uWh))
# FrogPilot variables # CLEARPILOT: hardcoded 30 minute shutdown timer (not user-configurable)
device_management = self.params.get_bool("DeviceManagement") self.device_shutdown_time = 1800
device_shutdown_setting = self.params.get_int("DeviceShutdown") if device_management else 33 self.low_voltage_shutdown = VBATT_PAUSE_CHARGING
# If the toggle is set for < 1 hour, configure by 15 minute increments
self.device_shutdown_time = (device_shutdown_setting - 3) * 3600 if device_shutdown_setting >= 4 else device_shutdown_setting * (60 * 15)
self.low_voltage_shutdown = self.params.get_float("LowVoltageShutdown") if device_management else VBATT_PAUSE_CHARGING
# Calculation tick # Calculation tick
def calculate(self, voltage: int | None, ignition: bool): def calculate(self, voltage: int | None, ignition: bool):
@@ -125,7 +122,13 @@ class PowerMonitoring:
offroad_time > VOLTAGE_SHUTDOWN_MIN_OFFROAD_TIME_S) offroad_time > VOLTAGE_SHUTDOWN_MIN_OFFROAD_TIME_S)
should_shutdown |= offroad_time > self.device_shutdown_time should_shutdown |= offroad_time > self.device_shutdown_time
should_shutdown |= low_voltage_shutdown should_shutdown |= low_voltage_shutdown
should_shutdown |= (self.car_battery_capacity_uWh <= 0) # CLEARPILOT: removed `car_battery_capacity_uWh <= 0` trigger. That's a virtual
# capacity counter floor-limited to 3e6 µWh on boot which drains in ~12 min at
# typical device power. With a short drive that doesn't fully recharge (charges
# at 45W, cap 30e6 µWh = 36 min to full), a quick store stop could trip shutdown
# well before the intended 30-min idle timer. The real protection we want here
# is the car battery voltage check (kept above) — the virtual counter is now
# retained only for telemetry.
should_shutdown &= not ignition should_shutdown &= not ignition
should_shutdown &= (not self.params.get_bool("DisablePowerDown")) should_shutdown &= (not self.params.get_bool("DisablePowerDown"))
should_shutdown &= in_car should_shutdown &= in_car
+33 -3
View File
@@ -10,7 +10,7 @@ from pathlib import Path
import psutil import psutil
import cereal.messaging as messaging import cereal.messaging as messaging
from cereal import log from cereal import car, log
from cereal.services import SERVICE_LIST from cereal.services import SERVICE_LIST
from openpilot.common.dict_helpers import strip_deprecated_keys from openpilot.common.dict_helpers import strip_deprecated_keys
from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.filter_simple import FirstOrderFilter
@@ -164,7 +164,7 @@ def hw_state_thread(end_event, hw_queue):
def thermald_thread(end_event, hw_queue) -> None: def thermald_thread(end_event, hw_queue) -> None:
pm = messaging.PubMaster(['deviceState', 'frogpilotDeviceState']) pm = messaging.PubMaster(['deviceState', 'frogpilotDeviceState'])
sm = messaging.SubMaster(["peripheralState", "gpsLocationExternal", "controlsState", "pandaStates"], poll="pandaStates") sm = messaging.SubMaster(["peripheralState", "gpsLocationExternal", "controlsState", "pandaStates", "carState"], poll="pandaStates")
count = 0 count = 0
@@ -197,7 +197,9 @@ def thermald_thread(end_event, hw_queue) -> None:
engaged_prev = False engaged_prev = False
params = Params() params = Params()
params_memory = Params("/dev/shm/params")
power_monitor = PowerMonitoring() power_monitor = PowerMonitoring()
last_touch_reset = "0" # CLEARPILOT: track last seen touch reset value
HARDWARE.initialize_hardware() HARDWARE.initialize_hardware()
thermal_config = HARDWARE.get_thermal_config() thermal_config = HARDWARE.get_thermal_config()
@@ -290,7 +292,18 @@ def thermald_thread(end_event, hw_queue) -> None:
msg.deviceState.maxTempC = all_comp_temp msg.deviceState.maxTempC = all_comp_temp
if fan_controller is not None: if fan_controller is not None:
msg.deviceState.fanSpeedPercentDesired = fan_controller.update(all_comp_temp, onroad_conditions["ignition"]) # CLEARPILOT: fan rules based on gear (parked vs drive) and cruise-engaged state
if sm.seen['carState']:
cs = sm['carState']
standstill = cs.standstill
is_parked = cs.gearShifter == car.CarState.GearShifter.park
else:
standstill = False
is_parked = True # default safe: assume parked, no fan floor
cruise_engaged = sm['controlsState'].enabled if sm.seen['controlsState'] else False
msg.deviceState.fanSpeedPercentDesired = fan_controller.update(
all_comp_temp, onroad_conditions["ignition"], standstill,
is_parked=is_parked, cruise_engaged=cruise_engaged)
is_offroad_for_5_min = (started_ts is None) and ((not started_seen) or (off_ts is None) or (time.monotonic() - off_ts > 60 * 5)) is_offroad_for_5_min = (started_ts is None) and ((not started_seen) or (off_ts is None) or (time.monotonic() - off_ts > 60 * 5))
if is_offroad_for_5_min and offroad_comp_temp > OFFROAD_DANGER_TEMP: if is_offroad_for_5_min and offroad_comp_temp > OFFROAD_DANGER_TEMP:
@@ -408,9 +421,26 @@ def thermald_thread(end_event, hw_queue) -> None:
statlog.sample("som_power_draw", som_power_draw) statlog.sample("som_power_draw", som_power_draw)
msg.deviceState.somPowerDrawW = som_power_draw msg.deviceState.somPowerDrawW = som_power_draw
# CLEARPILOT: screen tap resets shutdown timer (off_ts) while offroad
touch_reset = params_memory.get("ShutdownTouchReset")
if touch_reset is not None and touch_reset != last_touch_reset and off_ts is not None:
off_ts = time.monotonic()
cloudlog.info("shutdown timer reset by screen touch")
last_touch_reset = touch_reset
# Check if we need to shut down # Check if we need to shut down
if power_monitor.should_shutdown(onroad_conditions["ignition"], in_car, off_ts, started_seen): if power_monitor.should_shutdown(onroad_conditions["ignition"], in_car, off_ts, started_seen):
cloudlog.warning(f"shutting device down, offroad since {off_ts}") cloudlog.warning(f"shutting device down, offroad since {off_ts}")
# CLEARPILOT: signal dashcamd to close recording gracefully before power-off
params_memory.put_bool("DashcamShutdown", True)
deadline = time.monotonic() + 15.0
while time.monotonic() < deadline:
if not params_memory.get_bool("DashcamShutdown"):
cloudlog.info("dashcamd shutdown ack received")
break
time.sleep(0.5)
else:
cloudlog.warning("dashcamd shutdown ack timeout, proceeding")
params.put_bool("DoShutdown", True) params.put_bool("DoShutdown", True)
msg.deviceState.started = started_ts is not None msg.deviceState.started = started_ts is not None
+2 -3
View File
@@ -39,7 +39,7 @@ qt_src = ["main.cc", "qt/sidebar.cc", "qt/onroad.cc", "qt/body.cc",
"qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc", "qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc",
"qt/offroad/software_settings.cc", "qt/offroad/onboarding.cc", "qt/offroad/software_settings.cc", "qt/offroad/onboarding.cc",
"qt/offroad/driverview.cc", "qt/offroad/experimental_mode.cc", "qt/offroad/driverview.cc", "qt/offroad/experimental_mode.cc",
"../frogpilot/screenrecorder/omx_encoder.cc", "../frogpilot/screenrecorder/screenrecorder.cc", "../frogpilot/screenrecorder/omx_encoder.cc", # kept for dashcamd .o dependency
"qt/ready.cc"] "qt/ready.cc"]
# build translation files # build translation files
@@ -77,8 +77,7 @@ qt_env.Program("_text", ["qt/text.cc"], LIBS=qt_libs)
qt_env.Program("_spinner", ["qt/spinner.cc"], LIBS=qt_libs) qt_env.Program("_spinner", ["qt/spinner.cc"], LIBS=qt_libs)
# Clearpilot # Clearpilot tools
# Create clearpilot tools
qt_env.Program("/data/openpilot/system/clearpilot/tools/qt_shell", ["/data/openpilot/system/clearpilot/tools/qt_shell.cc"], LIBS=qt_libs) qt_env.Program("/data/openpilot/system/clearpilot/tools/qt_shell", ["/data/openpilot/system/clearpilot/tools/qt_shell.cc"], LIBS=qt_libs)
# build main UI # build main UI
+25
View File
@@ -1,4 +1,9 @@
#include <sys/resource.h> #include <sys/resource.h>
#include <csignal>
#include <cstdio>
#include <cstdlib>
#include <execinfo.h>
#include <unistd.h>
#include <QApplication> #include <QApplication>
#include <QTranslator> #include <QTranslator>
@@ -8,7 +13,27 @@
#include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/util.h"
#include "selfdrive/ui/qt/window.h" #include "selfdrive/ui/qt/window.h"
// CLEARPILOT: crash handler — prints stack trace to stderr on SIGSEGV/SIGABRT
static void crash_handler(int sig) {
const char *sig_name = (sig == SIGSEGV) ? "SIGSEGV" : (sig == SIGABRT) ? "SIGABRT" : "SIGNAL";
fprintf(stderr, "\n=== CRASH: %s (signal %d) ===\n", sig_name, sig);
void *frames[64];
int count = backtrace(frames, 64);
fprintf(stderr, "Backtrace (%d frames):\n", count);
backtrace_symbols_fd(frames, count, STDERR_FILENO);
fprintf(stderr, "=== END CRASH ===\n");
fflush(stderr);
// Re-raise to get default behavior (core dump / exit)
signal(sig, SIG_DFL);
raise(sig);
}
int main(int argc, char *argv[]) { int main(int argc, char *argv[]) {
signal(SIGSEGV, crash_handler);
signal(SIGABRT, crash_handler);
setpriority(PRIO_PROCESS, 0, -20); setpriority(PRIO_PROCESS, 0, -20);
qInstallMessageHandler(swagLogMessageHandler); qInstallMessageHandler(swagLogMessageHandler);
+327 -141
View File
@@ -1,14 +1,20 @@
#include "selfdrive/ui/qt/home.h" #include "selfdrive/ui/qt/home.h"
#include <cstdlib>
#include <QHBoxLayout> #include <QHBoxLayout>
#include <QMouseEvent> #include <QMouseEvent>
#include <QStackedWidget> #include <QStackedWidget>
#include <QVBoxLayout> #include <QVBoxLayout>
#include "selfdrive/ui/qt/offroad/experimental_mode.h" #include "common/swaglog.h"
#include "selfdrive/ui/qt/util.h" #include "common/params.h"
#include "selfdrive/ui/qt/widgets/drive_stats.h"
#include "system/hardware/hw.h" #include "system/hardware/hw.h"
#include "selfdrive/ui/qt/util.h"
#include "selfdrive/ui/qt/widgets/controls.h"
#include "selfdrive/ui/qt/widgets/input.h"
#include "selfdrive/ui/qt/widgets/scrollview.h"
#include "selfdrive/ui/qt/network/networking.h"
#include "cereal/messaging/messaging.h"
// HomeWindow: the container for the offroad and onroad UIs // HomeWindow: the container for the offroad and onroad UIs
@@ -21,6 +27,7 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) {
main_layout->setSpacing(0); main_layout->setSpacing(0);
sidebar = new Sidebar(this); sidebar = new Sidebar(this);
sidebar->setVisible(false);
main_layout->addWidget(sidebar); main_layout->addWidget(sidebar);
QObject::connect(sidebar, &Sidebar::openSettings, this, &HomeWindow::openSettings); QObject::connect(sidebar, &Sidebar::openSettings, this, &HomeWindow::openSettings);
QObject::connect(sidebar, &Sidebar::openOnroad, this, &HomeWindow::showOnroad); QObject::connect(sidebar, &Sidebar::openOnroad, this, &HomeWindow::showOnroad);
@@ -28,8 +35,17 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) {
slayout = new QStackedLayout(); slayout = new QStackedLayout();
main_layout->addLayout(slayout); main_layout->addLayout(slayout);
home = new OffroadHome(this); home = new ClearPilotPanel(this);
QObject::connect(home, &OffroadHome::openSettings, this, &HomeWindow::openSettings); QObject::connect(home, &ClearPilotPanel::openSettings, this, &HomeWindow::openSettings);
QObject::connect(home, &ClearPilotPanel::openStatus, this, &HomeWindow::openStatus);
QObject::connect(home, &ClearPilotPanel::closePanel, [=]() {
// Return to splash or onroad depending on state
if (uiState()->scene.started) {
slayout->setCurrentWidget(onroad);
} else {
slayout->setCurrentWidget(ready);
}
});
slayout->addWidget(home); slayout->addWidget(home);
onroad = new OnroadWindow(this); onroad = new OnroadWindow(this);
@@ -38,6 +54,7 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) {
// CLEARPILOT // CLEARPILOT
ready = new ReadyWindow(this); ready = new ReadyWindow(this);
slayout->addWidget(ready); slayout->addWidget(ready);
slayout->setCurrentWidget(ready); // show splash immediately, not ClearPilotPanel
driver_view = new DriverViewWindow(this); driver_view = new DriverViewWindow(this);
connect(driver_view, &DriverViewWindow::done, [=] { connect(driver_view, &DriverViewWindow::done, [=] {
@@ -64,52 +81,79 @@ void HomeWindow::showSidebar(bool show) {
} }
void HomeWindow::updateState(const UIState &s) { void HomeWindow::updateState(const UIState &s) {
// const SubMaster &sm = *(s.sm);
if (s.scene.started) { if (s.scene.started) {
showDriverView(s.scene.driver_camera_timer >= 10, true); showDriverView(s.scene.driver_camera_timer >= 10, true);
// CLEARPILOT: show splash screen when onroad but in park
bool parked = s.scene.parked;
int screenMode = paramsMemory.getInt("ScreenDisplayMode");
bool nightrider = (screenMode == 1 || screenMode == 4);
if (parked && !was_parked_onroad) {
LOGW("CLP UI: park transition -> showing splash");
slayout->setCurrentWidget(ready);
// If we were in nightrider mode, switch to screen off
if (nightrider) {
paramsMemory.putInt("ScreenDisplayMode", 3);
}
} else if (!parked && was_parked_onroad) {
LOGW("CLP UI: drive transition -> showing onroad");
slayout->setCurrentWidget(onroad);
ready->has_driven = true;
}
was_parked_onroad = parked;
// CLEARPILOT: honor display on/off while showing splash in park (normal mode only)
if (parked && ready->isVisible()) {
if (screenMode == 3) {
Hardware::set_display_power(false);
} else {
Hardware::set_display_power(true);
}
}
} }
} }
void HomeWindow::offroadTransition(bool offroad) { void HomeWindow::offroadTransition(bool offroad) {
sidebar->setVisible(false);
if (offroad) { if (offroad) {
sidebar->setVisible(false); LOGW("CLP UI: offroad transition -> showing splash");
was_parked_onroad = false;
slayout->setCurrentWidget(ready); slayout->setCurrentWidget(ready);
} else { } else {
sidebar->setVisible(false); // CLEARPILOT: start onroad in splash — updateState will switch to
slayout->setCurrentWidget(onroad); // camera view once the car shifts out of park. Reset has_driven so
// fresh ignition shows the READY text (not the post-drive textless splash).
LOGW("CLP UI: onroad transition -> showing splash (parked)");
was_parked_onroad = true;
ready->has_driven = false;
slayout->setCurrentWidget(ready);
} }
} }
void HomeWindow::showDriverView(bool show, bool started) { void HomeWindow::showDriverView(bool show, bool started) {
if (show) { if (show) {
LOGW("CLP UI: showDriverView(true) -> driver_view");
emit closeSettings(); emit closeSettings();
slayout->setCurrentWidget(driver_view); slayout->setCurrentWidget(driver_view);
sidebar->setVisible(show == false); sidebar->setVisible(false);
} else { } else if (!started) {
if (started) { // Offroad, not started — show home menu
slayout->setCurrentWidget(onroad); slayout->setCurrentWidget(home);
sidebar->setVisible(params.getBool("Sidebar")); sidebar->setVisible(false);
} else {
slayout->setCurrentWidget(home);
sidebar->setVisible(show == false);
}
} }
// CLEARPILOT: when started, don't touch slayout here —
// updateState handles park->splash and drive->onroad transitions
} }
void HomeWindow::mousePressEvent(QMouseEvent* e) { void HomeWindow::mousePressEvent(QMouseEvent* e) {
// CLEARPILOT todo - tap on main goes straight to settings // CLEARPILOT: tap from any view goes to ClearPilotPanel
// Unless we click a debug widget. if (ready->isVisible() || onroad->isVisible()) {
LOGW("CLP UI: tap -> showing ClearPilotPanel");
// CLEARPILOT - click ready shows home sidebar->setVisible(false);
if (!onroad->isVisible() && ready->isVisible()) { home->resetToGeneral();
sidebar->setVisible(true);
slayout->setCurrentWidget(home); slayout->setCurrentWidget(home);
} }
// Todo: widgets
if (onroad->isVisible()) {
emit openSettings();
}
} }
void HomeWindow::mouseDoubleClickEvent(QMouseEvent* e) { void HomeWindow::mouseDoubleClickEvent(QMouseEvent* e) {
@@ -117,132 +161,274 @@ void HomeWindow::mouseDoubleClickEvent(QMouseEvent* e) {
// const SubMaster &sm = *(uiState()->sm); // const SubMaster &sm = *(uiState()->sm);
} }
// OffroadHome: the offroad home page // CLEARPILOT: ClearPilotPanel — settings-style sidebar menu
OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) { static const char *clpSidebarBtnStyle = R"(
QVBoxLayout* main_layout = new QVBoxLayout(this); QPushButton {
main_layout->setContentsMargins(40, 40, 40, 40); color: grey;
border: none;
// top header background: none;
QHBoxLayout* header_layout = new QHBoxLayout(); font-size: 65px;
header_layout->setContentsMargins(0, 0, 0, 0); font-weight: 500;
header_layout->setSpacing(16);
update_notif = new QPushButton(tr("UPDATE"));
update_notif->setVisible(false);
update_notif->setStyleSheet("background-color: #364DEF;");
QObject::connect(update_notif, &QPushButton::clicked, [=]() { center_layout->setCurrentIndex(1); });
header_layout->addWidget(update_notif, 0, Qt::AlignHCenter | Qt::AlignLeft);
alert_notif = new QPushButton();
alert_notif->setVisible(false);
alert_notif->setStyleSheet("background-color: #E22C2C;");
QObject::connect(alert_notif, &QPushButton::clicked, [=] { center_layout->setCurrentIndex(2); });
header_layout->addWidget(alert_notif, 0, Qt::AlignHCenter | Qt::AlignLeft);
date = new ElidedLabel();
header_layout->addWidget(date, 0, Qt::AlignHCenter | Qt::AlignLeft);
version = new ElidedLabel();
header_layout->addWidget(version, 0, Qt::AlignHCenter | Qt::AlignRight);
main_layout->addLayout(header_layout);
// main content
main_layout->addSpacing(25);
center_layout = new QStackedLayout();
QWidget *home_widget = new QWidget(this);
{
QHBoxLayout *home_layout = new QHBoxLayout(home_widget);
home_layout->setContentsMargins(0, 0, 0, 0);
home_layout->setSpacing(30);
// // // Create a QWebEngineView
// QWebEngineView *web_view = new QWebEngineView();
// web_view->load(QUrl("http://fark.com"));
// // Add the QWebEngineView to the layout
// home_layout->addWidget(web_view);
} }
center_layout->addWidget(home_widget); QPushButton:checked {
color: white;
}
QPushButton:pressed {
color: #ADADAD;
}
)";
// add update & alerts widgets // clpActionBtnStyle removed — no longer used
update_widget = new UpdateAlert();
QObject::connect(update_widget, &UpdateAlert::dismiss, [=]() { center_layout->setCurrentIndex(0); });
center_layout->addWidget(update_widget);
alerts_widget = new OffroadAlert();
QObject::connect(alerts_widget, &OffroadAlert::dismiss, [=]() { center_layout->setCurrentIndex(0); });
center_layout->addWidget(alerts_widget);
main_layout->addLayout(center_layout, 1);
// set up refresh timer ClearPilotPanel::ClearPilotPanel(QWidget* parent) : QFrame(parent) {
timer = new QTimer(this); // Sidebar
timer->callOnTimeout(this, &OffroadHome::refresh); QWidget *sidebar_widget = new QWidget;
QVBoxLayout *sidebar_layout = new QVBoxLayout(sidebar_widget);
sidebar_layout->setContentsMargins(50, 50, 100, 50);
// Close button
QPushButton *close_btn = new QPushButton("← Back");
close_btn->setStyleSheet(R"(
QPushButton {
color: white;
border-radius: 25px;
background: #292929;
font-size: 50px;
font-weight: 500;
}
QPushButton:pressed {
color: #ADADAD;
}
)");
close_btn->setFixedSize(300, 125);
sidebar_layout->addSpacing(10);
sidebar_layout->addWidget(close_btn, 0, Qt::AlignRight);
QObject::connect(close_btn, &QPushButton::clicked, [=]() { emit closePanel(); });
// Panel content area
panel_widget = new QStackedWidget();
// ── General panel ──
ListWidget *general_panel = new ListWidget(this);
general_panel->setContentsMargins(50, 25, 50, 25);
// Status button
auto *status_btn = new ButtonControl("System Status", "VIEW", "");
connect(status_btn, &ButtonControl::clicked, [=]() { emit openStatus(); });
general_panel->addItem(status_btn);
// Reset Calibration
auto resetCalibBtn = new ButtonControl("Reset Calibration", "RESET", "");
connect(resetCalibBtn, &ButtonControl::showDescriptionEvent, [=]() {
QString desc = "openpilot requires the device to be mounted within 4° left or right and "
"within 5° up or 9° down. openpilot is continuously calibrating, resetting is rarely required.";
std::string calib_bytes = Params().get("CalibrationParams");
if (!calib_bytes.empty()) {
try {
AlignedBuffer aligned_buf;
capnp::FlatArrayMessageReader cmsg(aligned_buf.align(calib_bytes.data(), calib_bytes.size()));
auto calib = cmsg.getRoot<cereal::Event>().getLiveCalibration();
if (calib.getCalStatus() != cereal::LiveCalibrationData::Status::UNCALIBRATED) {
double pitch = calib.getRpyCalib()[1] * (180 / M_PI);
double yaw = calib.getRpyCalib()[2] * (180 / M_PI);
desc += QString(" Your device is pointed %1° %2 and %3° %4.")
.arg(QString::number(std::abs(pitch), 'g', 1), pitch > 0 ? "down" : "up",
QString::number(std::abs(yaw), 'g', 1), yaw > 0 ? "left" : "right");
}
} catch (...) {
qInfo() << "invalid CalibrationParams";
}
}
qobject_cast<ButtonControl *>(sender())->setDescription(desc);
});
connect(resetCalibBtn, &ButtonControl::clicked, [=]() {
if (ConfirmationDialog::confirm("Are you sure you want to reset calibration?", "Reset", this)) {
Params().remove("CalibrationParams");
Params().remove("LiveTorqueParameters");
}
});
general_panel->addItem(resetCalibBtn);
// Power buttons
QHBoxLayout *power_layout = new QHBoxLayout();
power_layout->setSpacing(30);
QPushButton *reboot_btn = new QPushButton("Reboot");
reboot_btn->setObjectName("reboot_btn");
power_layout->addWidget(reboot_btn);
QPushButton *softreboot_btn = new QPushButton("Soft Reboot");
softreboot_btn->setObjectName("softreboot_btn");
power_layout->addWidget(softreboot_btn);
QPushButton *poweroff_btn = new QPushButton("Power Off");
poweroff_btn->setObjectName("poweroff_btn");
power_layout->addWidget(poweroff_btn);
QObject::connect(reboot_btn, &QPushButton::clicked, [=]() {
if (!uiState()->engaged()) {
if (ConfirmationDialog::confirm("Are you sure you want to reboot?", "Reboot", this)) {
if (!uiState()->engaged()) {
Params().putBool("DoReboot", true);
}
}
} else {
ConfirmationDialog::alert("Disengage to Reboot", this);
}
});
QObject::connect(softreboot_btn, &QPushButton::clicked, [=]() {
if (!uiState()->engaged()) {
if (ConfirmationDialog::confirm("Are you sure you want to soft reboot?", "Soft Reboot", this)) {
if (!uiState()->engaged()) {
Params().putBool("DoSoftReboot", true);
}
}
} else {
ConfirmationDialog::alert("Disengage to Soft Reboot", this);
}
});
QObject::connect(poweroff_btn, &QPushButton::clicked, [=]() {
if (!uiState()->engaged()) {
if (ConfirmationDialog::confirm("Are you sure you want to power off?", "Power Off", this)) {
if (!uiState()->engaged()) {
Params().putBool("DoShutdown", true);
}
}
} else {
ConfirmationDialog::alert("Disengage to Power Off", this);
}
});
general_panel->addItem(power_layout);
// ── Network panel ──
Networking *network_panel = new Networking(this);
// Hide APN button — find by searching QPushButton labels inside AdvancedNetworking
for (auto *btn : network_panel->findChildren<QPushButton *>()) {
if (btn->text().contains("APN", Qt::CaseInsensitive)) {
// Hide the parent AbstractControl frame, not just the button
if (auto *frame = qobject_cast<QFrame *>(btn->parentWidget())) {
frame->setVisible(false);
}
}
}
// ── Dashcam panel ──
QWidget *dashcam_panel = new QWidget(this);
QVBoxLayout *dash_layout = new QVBoxLayout(dashcam_panel);
dash_layout->setContentsMargins(50, 25, 50, 25);
QLabel *dash_label = new QLabel("Dashcam viewer coming soon");
dash_label->setStyleSheet("color: grey; font-size: 40px;");
dash_label->setAlignment(Qt::AlignCenter);
dash_layout->addWidget(dash_label);
dash_layout->addStretch();
// ── Debug panel ──
ListWidget *debug_panel = new ListWidget(this);
debug_panel->setContentsMargins(50, 25, 50, 25);
auto *telemetry_toggle = new ToggleControl("Telemetry Logging",
"Record telemetry data to CSV in the session log directory. "
"Captures only changed values for efficiency.", "",
Params("/dev/shm/params").getBool("TelemetryEnabled"), this);
QObject::connect(telemetry_toggle, &ToggleControl::toggleFlipped, [](bool on) {
Params("/dev/shm/params").putBool("TelemetryEnabled", on);
});
debug_panel->addItem(telemetry_toggle);
auto *health_metrics_toggle = new ToggleControl("System Health Overlay",
"Show controls lag, model frame drops, temperature, CPU, and memory usage "
"in the lower-right of the onroad UI. For diagnosing slowdown issues.", "",
Params().getBool("ClearpilotShowHealthMetrics"), this);
QObject::connect(health_metrics_toggle, &ToggleControl::toggleFlipped, [](bool on) {
Params().putBool("ClearpilotShowHealthMetrics", on);
});
debug_panel->addItem(health_metrics_toggle);
auto *vpn_toggle = new ToggleControl("VPN",
"Connect to vpn.hanson.xyz for remote SSH access. "
"Disabling kills the active tunnel and stops reconnection attempts.", "",
Params("/dev/shm/params").getBool("VpnEnabled"), this);
QObject::connect(vpn_toggle, &ToggleControl::toggleFlipped, [](bool on) {
Params("/dev/shm/params").putBool("VpnEnabled", on);
if (on) {
std::system("sudo bash -c 'nohup /data/openpilot/system/clearpilot/vpn-monitor.sh >> /tmp/vpn-monitor.log 2>&1 &'");
} else {
std::system("sudo pkill -TERM -f vpn-monitor.sh; sudo killall openvpn");
}
});
debug_panel->addItem(vpn_toggle);
// ── Register panels with sidebar buttons ──
QList<QPair<QString, QWidget *>> panels = {
{"General", general_panel},
{"Network", network_panel},
{"Dashcam", dashcam_panel},
{"Debug", debug_panel},
};
nav_group = new QButtonGroup(this);
nav_group->setExclusive(true);
for (auto &[name, panel] : panels) {
QPushButton *btn = new QPushButton(name);
btn->setCheckable(true);
btn->setStyleSheet(clpSidebarBtnStyle);
btn->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding);
sidebar_layout->addWidget(btn, 0, Qt::AlignRight);
nav_group->addButton(btn);
// Network panel handles its own scrolling/margins
if (name == "Network") {
panel_widget->addWidget(panel);
QObject::connect(btn, &QPushButton::clicked, [=, w = panel]() {
panel_widget->setCurrentWidget(w);
});
} else {
ScrollView *panel_frame = new ScrollView(panel, this);
panel_widget->addWidget(panel_frame);
QObject::connect(btn, &QPushButton::clicked, [=, w = panel_frame]() {
panel_widget->setCurrentWidget(w);
});
}
}
// Select General by default
nav_group->buttons().first()->setChecked(true);
panel_widget->setCurrentIndex(0);
// Main layout: sidebar + panels
QHBoxLayout *main_layout = new QHBoxLayout(this);
sidebar_widget->setFixedWidth(500);
main_layout->addWidget(sidebar_widget);
main_layout->addWidget(panel_widget);
setStyleSheet(R"( setStyleSheet(R"(
* { * {
color: white; color: white;
font-size: 50px;
} }
OffroadHome { ClearPilotPanel {
background-color: black; background-color: black;
} }
OffroadHome > QPushButton { QStackedWidget, ScrollView, Networking {
padding: 15px 30px; background-color: #292929;
border-radius: 5px; border-radius: 30px;
font-size: 40px;
font-weight: 500;
}
OffroadHome > QLabel {
font-size: 55px;
} }
#softreboot_btn { height: 120px; border-radius: 15px; background-color: #e2e22c; }
#softreboot_btn:pressed { background-color: #ffe224; }
#reboot_btn { height: 120px; border-radius: 15px; background-color: #393939; }
#reboot_btn:pressed { background-color: #4a4a4a; }
#poweroff_btn { height: 120px; border-radius: 15px; background-color: #E22C2C; }
#poweroff_btn:pressed { background-color: #FF2424; }
)"); )");
} }
/* Refresh data on screen every 5 seconds. */ void ClearPilotPanel::resetToGeneral() {
void OffroadHome::showEvent(QShowEvent *event) { panel_widget->setCurrentIndex(0);
refresh(); nav_group->buttons().first()->setChecked(true);
timer->start(5 * 1000);
}
void OffroadHome::hideEvent(QHideEvent *event) {
timer->stop();
}
void OffroadHome::refresh() {
QString model = QString::fromStdString(params.get("ModelName"));
date->setText(QLocale(uiState()->language.mid(5)).toString(QDateTime::currentDateTime(), "dddd, MMMM d"));
version->setText(getBrand() + " v" + getVersion().left(14).trimmed() + " - " + model);
// bool updateAvailable = update_widget->refresh();
int alerts = alerts_widget->refresh();
if (alerts > 0 && !alerts_widget->isVisible()) {
alerts_widget->setVisible(true);
} else if (alerts == 0 && alerts_widget->isVisible()) {
alerts_widget->setVisible(false);
}
// pop-up new notification
// CLEARPILOT temp disabled update notifications
// int idx = center_layout->currentIndex();
// if (!updateAvailable && !alerts && false) {
// idx = 0;
// } else if (updateAvailable && (!update_notif->isVisible() || (!alerts && idx == 2))) {
// idx = 1;
// } else if (alerts && (!alert_notif->isVisible() || (!updateAvailable && idx == 1))) {
// idx = 2;
// }
// center_layout->setCurrentIndex(idx);
// CLEARPILOT temp disabled update notifications
// update_notif->setVisible(updateAvailable);
// alert_notif->setVisible(alerts);
alert_notif->setVisible(false);
if (alerts) {
alert_notif->setText(QString::number(alerts) + (alerts > 1 ? tr(" ALERTS") : tr(" ALERT")));
}
} }
+15 -20
View File
@@ -1,9 +1,11 @@
#pragma once #pragma once
#include <QButtonGroup>
#include <QFrame> #include <QFrame>
#include <QLabel> #include <QLabel>
#include <QPushButton> #include <QPushButton>
#include <QStackedLayout> #include <QStackedLayout>
#include <QStackedWidget>
#include <QTimer> #include <QTimer>
#include <QWidget> #include <QWidget>
@@ -16,32 +18,23 @@
#include "selfdrive/ui/qt/widgets/offroad_alerts.h" #include "selfdrive/ui/qt/widgets/offroad_alerts.h"
#include "selfdrive/ui/ui.h" #include "selfdrive/ui/ui.h"
class OffroadHome : public QFrame { class ClearPilotPanel : public QFrame {
Q_OBJECT Q_OBJECT
public: public:
explicit OffroadHome(QWidget* parent = 0); explicit ClearPilotPanel(QWidget* parent = 0);
signals: signals:
void openSettings(int index = 0, const QString &param = ""); void openSettings(int index = 0, const QString &param = "");
void openStatus();
void closePanel();
public:
void resetToGeneral();
private: private:
void showEvent(QShowEvent *event) override; QStackedWidget *panel_widget;
void hideEvent(QHideEvent *event) override; QButtonGroup *nav_group;
void refresh();
Params params;
QTimer* timer;
ElidedLabel* version;
QStackedLayout* center_layout;
UpdateAlert *update_widget;
OffroadAlert* alerts_widget;
QPushButton* alert_notif;
QPushButton* update_notif;
// FrogPilot variables
ElidedLabel* date;
}; };
class HomeWindow : public QWidget { class HomeWindow : public QWidget {
@@ -53,6 +46,7 @@ public:
signals: signals:
void openSettings(int index = 0, const QString &param = ""); void openSettings(int index = 0, const QString &param = "");
void openStatus();
void closeSettings(); void closeSettings();
public slots: public slots:
@@ -67,17 +61,18 @@ protected:
private: private:
Sidebar *sidebar; Sidebar *sidebar;
OffroadHome *home; ClearPilotPanel *home;
OnroadWindow *onroad; OnroadWindow *onroad;
DriverViewWindow *driver_view; DriverViewWindow *driver_view;
QStackedLayout *slayout; QStackedLayout *slayout;
// FrogPilot variables // FrogPilot variables
Params params; Params params;
Params paramsMemory{"/dev/shm/params"};
// CLEARPILOT // CLEARPILOT
// bool show_ready;
ReadyWindow *ready; ReadyWindow *ready;
bool was_parked_onroad = false;
private slots: private slots:
void updateState(const UIState &s); void updateState(const UIState &s);
+415 -69
View File
@@ -7,6 +7,7 @@
#include <sstream> #include <sstream>
#include <QApplication> #include <QApplication>
#include <QDateTime>
#include <QDebug> #include <QDebug>
#include <QMouseEvent> #include <QMouseEvent>
@@ -75,10 +76,11 @@ void OnroadWindow::updateState(const UIState &s) {
alerts->updateAlert(alert); alerts->updateAlert(alert);
nvg->updateState(s); nvg->updateState(s);
nvg->update(); // CLEARPILOT: force repaint every frame for HUD elements
QColor bgColor = bg_colors[s.status]; QColor bgColor = bg_colors[s.status];
// CLEARPILOT: read from frogpilotCarControl cereal message (was paramsMemory)
if (paramsMemory.getBool("no_lat_lane_change") == 1 || nvg->screenDisplayMode == 2) { if ((*s.sm)["frogpilotCarControl"].getFrogpilotCarControl().getNoLatLaneChange()) {
bgColor = bg_colors[STATUS_DISENGAGED]; bgColor = bg_colors[STATUS_DISENGAGED];
} }
@@ -176,7 +178,14 @@ void OnroadWindow::offroadTransition(bool offroad) {
void OnroadWindow::paintEvent(QPaintEvent *event) { void OnroadWindow::paintEvent(QPaintEvent *event) {
QPainter p(this); QPainter p(this);
p.fillRect(rect(), QColor(bg.red(), bg.green(), bg.blue(), 255)); // CLEARPILOT: hide engagement border in nightrider mode
int dm = paramsMemory.getInt("ScreenDisplayMode");
bool nightrider = (dm == 1 || dm == 4);
if (nightrider) {
p.fillRect(rect(), Qt::black);
} else {
p.fillRect(rect(), QColor(bg.red(), bg.green(), bg.blue(), 255));
}
QString logicsDisplayString = QString(); QString logicsDisplayString = QString();
if (scene.show_jerk) { if (scene.show_jerk) {
@@ -216,6 +225,13 @@ void OnroadWindow::paintEvent(QPaintEvent *event) {
} }
} }
// void OnroadWindow::update_screen_on_off() {
// int screenDisaplayMode = paramsMemory.getInt("ScreenDisaplayMode");
// if (screenDisaplayMode == 1) {
// // Conditionally off
// }
// }
// ***** onroad widgets ***** // ***** onroad widgets *****
@@ -308,10 +324,7 @@ AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget* par
QHBoxLayout *buttons_layout = new QHBoxLayout(); QHBoxLayout *buttons_layout = new QHBoxLayout();
buttons_layout->setSpacing(0); buttons_layout->setSpacing(0);
// Neokii screen recorder // Neokii screen recorder — DISABLED: using dashcamd instead
recorder_btn = new ScreenRecorder(this);
recorder_btn->setVisible(false);
// buttons_layout->addWidget(recorder_btn);
QVBoxLayout *top_right_layout = new QVBoxLayout(); QVBoxLayout *top_right_layout = new QVBoxLayout();
top_right_layout->setSpacing(0); top_right_layout->setSpacing(0);
@@ -327,24 +340,13 @@ AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget* par
} }
void AnnotatedCameraWidget::updateState(const UIState &s) { void AnnotatedCameraWidget::updateState(const UIState &s) {
screenDisplayMode = paramsMemory.getInt("ScreenDisplayMode");
if (screenDisplayMode == 2 && !alert_is_visible) {
// Draw black, filled, full-size rectangle to blank the screen
// p.fillRect(0, 0, width(), height(), Qt::black);
// p.restore();
Hardware::set_display_power(false);
return;
} else {
Hardware::set_display_power(true);
}
const int SET_SPEED_NA = 255; const int SET_SPEED_NA = 255;
const SubMaster &sm = *(s.sm); const SubMaster &sm = *(s.sm);
const bool cs_alive = sm.alive("controlsState"); const bool cs_alive = sm.alive("controlsState");
const auto cs = sm["controlsState"].getControlsState(); const auto cs = sm["controlsState"].getControlsState();
const auto car_state = sm["carState"].getCarState(); const auto car_state = sm["carState"].getCarState();
(void)car_state; // CLEARPILOT: suppress unused warning, will use later
// Handle older routes where vCruiseCluster is not set // Handle older routes where vCruiseCluster is not set
float v_cruise = cs.getVCruiseCluster() == 0.0 ? cs.getVCruise() : cs.getVCruiseCluster(); float v_cruise = cs.getVCruiseCluster() == 0.0 ? cs.getVCruise() : cs.getVCruiseCluster();
@@ -354,11 +356,16 @@ void AnnotatedCameraWidget::updateState(const UIState &s) {
setSpeed *= KM_TO_MILE; setSpeed *= KM_TO_MILE;
} }
// Handle older routes where vEgoCluster is not set // CLEARPILOT: read speed and speed limit from params (written by speed_logic.py ~2Hz)
v_ego_cluster_seen = v_ego_cluster_seen || car_state.getVEgoCluster() != 0.0; clpParamFrame++;
float v_ego = v_ego_cluster_seen && !scene.wheel_speed ? car_state.getVEgoCluster() : car_state.getVEgo(); if (clpParamFrame % 10 == 0) { // ~2Hz at 20Hz UI update rate
speed = cs_alive ? std::max<float>(0.0, v_ego) : 0.0; clpHasSpeed = paramsMemory.get("ClearpilotHasSpeed") == "1";
speed *= s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH; clpSpeedDisplay = QString::fromStdString(paramsMemory.get("ClearpilotSpeedDisplay"));
clpSpeedLimitDisplay = QString::fromStdString(paramsMemory.get("ClearpilotSpeedLimitDisplay"));
clpSpeedUnit = QString::fromStdString(paramsMemory.get("ClearpilotSpeedUnit"));
clpCruiseWarning = QString::fromStdString(paramsMemory.get("ClearpilotCruiseWarning"));
clpCruiseWarningSpeed = QString::fromStdString(paramsMemory.get("ClearpilotCruiseWarningSpeed"));
}
// auto speed_limit_sign = nav_instruction.getSpeedLimitSign(); // auto speed_limit_sign = nav_instruction.getSpeedLimitSign();
// speedLimit = slcOverridden ? scene.speed_limit_overridden_speed : speedLimitController ? scene.speed_limit : nav_alive ? nav_instruction.getSpeedLimit() : 0.0; // speedLimit = slcOverridden ? scene.speed_limit_overridden_speed : speedLimitController ? scene.speed_limit : nav_alive ? nav_instruction.getSpeedLimit() : 0.0;
@@ -394,9 +401,28 @@ if (edgeColor != bgColor) {
} }
void AnnotatedCameraWidget::drawHud(QPainter &p) { void AnnotatedCameraWidget::drawHud(QPainter &p) {
// Blank when screenDisplayMode=1 // CLEARPILOT: display power control based on ScreenDisplayMode
p.save(); p.save();
if (displayMode == 3 && !alert_is_visible) {
Hardware::set_display_power(false);
p.restore();
return;
} else {
Hardware::set_display_power(true);
}
// CLEARPILOT: blinking blue circle when telemetry is recording
if (paramsMemory.getBool("TelemetryEnabled")) {
// Blink: visible for 500ms, hidden for 500ms
int phase = (QDateTime::currentMSecsSinceEpoch() / 500) % 2;
if (phase == 0) {
p.setPen(Qt::NoPen);
p.setBrush(QColor(30, 100, 220));
p.drawEllipse(width() - 150, 50, 100, 100);
}
}
// Header gradient // Header gradient
QLinearGradient bg(0, UI_HEADER_HEIGHT - (UI_HEADER_HEIGHT / 2.5), 0, UI_HEADER_HEIGHT); QLinearGradient bg(0, UI_HEADER_HEIGHT - (UI_HEADER_HEIGHT / 2.5), 0, UI_HEADER_HEIGHT);
bg.setColorAt(0, QColor::fromRgbF(0, 0, 0, 0.45)); bg.setColorAt(0, QColor::fromRgbF(0, 0, 0, 0.45));
@@ -407,7 +433,7 @@ void AnnotatedCameraWidget::drawHud(QPainter &p) {
// QString speedLimitStr = (speedLimit > 1) ? QString::number(std::nearbyint(speedLimit)) : ""; // QString speedLimitStr = (speedLimit > 1) ? QString::number(std::nearbyint(speedLimit)) : "";
// QString speedLimitOffsetStr = slcSpeedLimitOffset == 0 ? "" : QString::number(slcSpeedLimitOffset, 'f', 0).prepend(slcSpeedLimitOffset > 0 ? "+" : ""); // QString speedLimitOffsetStr = slcSpeedLimitOffset == 0 ? "" : QString::number(slcSpeedLimitOffset, 'f', 0).prepend(slcSpeedLimitOffset > 0 ? "+" : "");
QString speedStr = QString::number(std::nearbyint(speed)); // QString speedStr = QString::number(std::nearbyint(speed));
QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed - cruiseAdjustment)) : ""; QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed - cruiseAdjustment)) : "";
p.restore(); p.restore();
@@ -431,17 +457,21 @@ void AnnotatedCameraWidget::drawHud(QPainter &p) {
// Todo: lead speed // Todo: lead speed
// Todo: Experimental speed // Todo: Experimental speed
// // current speed // CLEARPILOT: show speed from speed_logic params, hide when no speed or speed=0
if (!(scene.hide_speed)) { if (clpHasSpeed && !clpSpeedDisplay.isEmpty() && !scene.hide_speed) {
// CLEARPILOT changes to 120 from ~176
// Maybe we want to hide this?
p.setFont(InterFont(140, QFont::Bold)); p.setFont(InterFont(140, QFont::Bold));
drawText(p, rect().center().x(), 210, speedStr); drawText(p, rect().center().x(), 210, clpSpeedDisplay);
// CLEARPILOT changes to 40 from 66
p.setFont(InterFont(50)); p.setFont(InterFont(50));
drawText(p, rect().center().x(), 290, speedUnit, 200); drawText(p, rect().center().x(), 290, clpSpeedUnit, 200);
} }
// CLEARPILOT: speed limit sign in lower-left, cruise warning above it
drawSpeedLimitSign(p);
drawCruiseWarningSign(p);
// CLEARPILOT: system health metrics in lower-right (debug overlay)
drawHealthMetrics(p);
// Draw FrogPilot widgets // Draw FrogPilot widgets
paintFrogPilotWidgets(p); paintFrogPilotWidgets(p);
} }
@@ -535,6 +565,164 @@ void AnnotatedCameraWidget::drawSpeedWidget(QPainter &p, int x, int y, const QSt
} }
void AnnotatedCameraWidget::drawSpeedLimitSign(QPainter &p) {
// Hide when no speed limit or speed limit is 0
if (clpSpeedLimitDisplay.isEmpty() || clpSpeedLimitDisplay == "0") return;
p.save();
const int signW = 189;
const int signH = 239;
const int margin = 20;
const int borderW = 6;
const int innerBorderW = 4;
const int innerMargin = 10;
const int cornerR = 15;
// Position: 20px from lower-left corner
QRect signRect(margin, height() - signH - margin, signW, signH);
if (nightriderMode) {
// Nightrider: black background, light gray-blue border and text
QColor borderColor(160, 180, 210);
QColor textColor(160, 180, 210);
// Outer border
p.setPen(QPen(borderColor, borderW));
p.setBrush(QColor(0, 0, 0, 220));
p.drawRoundedRect(signRect, cornerR, cornerR);
// Inner border
QRect innerRect = signRect.adjusted(innerMargin, innerMargin, -innerMargin, -innerMargin);
p.setPen(QPen(borderColor, innerBorderW));
p.setBrush(Qt::NoBrush);
p.drawRoundedRect(innerRect, cornerR - 4, cornerR - 4);
// "SPEED" text
p.setPen(textColor);
p.setFont(InterFont(30, QFont::Bold));
p.drawText(innerRect.adjusted(0, 15, 0, 0), Qt::AlignTop | Qt::AlignHCenter, "SPEED");
// "LIMIT" text
p.setFont(InterFont(30, QFont::Bold));
p.drawText(innerRect.adjusted(0, 48, 0, 0), Qt::AlignTop | Qt::AlignHCenter, "LIMIT");
// Speed limit number — shifted down ~10% of innerRect height via extra top inset
p.setFont(InterFont(90, QFont::Bold));
p.drawText(innerRect.adjusted(0, 86, 0, 0), Qt::AlignCenter, clpSpeedLimitDisplay);
} else {
// Normal: white background, black border and text
QColor borderColor(0, 0, 0);
QColor textColor(0, 0, 0);
// Outer border
p.setPen(QPen(borderColor, borderW));
p.setBrush(QColor(255, 255, 255, 240));
p.drawRoundedRect(signRect, cornerR, cornerR);
// Inner border
QRect innerRect = signRect.adjusted(innerMargin, innerMargin, -innerMargin, -innerMargin);
p.setPen(QPen(borderColor, innerBorderW));
p.setBrush(Qt::NoBrush);
p.drawRoundedRect(innerRect, cornerR - 4, cornerR - 4);
// "SPEED" text
p.setPen(textColor);
p.setFont(InterFont(30, QFont::Bold));
p.drawText(innerRect.adjusted(0, 15, 0, 0), Qt::AlignTop | Qt::AlignHCenter, "SPEED");
// "LIMIT" text
p.setFont(InterFont(30, QFont::Bold));
p.drawText(innerRect.adjusted(0, 48, 0, 0), Qt::AlignTop | Qt::AlignHCenter, "LIMIT");
// Speed limit number — shifted down ~10% of innerRect height via extra top inset
p.setFont(InterFont(90, QFont::Bold));
p.drawText(innerRect.adjusted(0, 86, 0, 0), Qt::AlignCenter, clpSpeedLimitDisplay);
}
p.restore();
}
void AnnotatedCameraWidget::drawCruiseWarningSign(QPainter &p) {
// Only show when there's an active warning and the speed limit sign is visible
if (clpCruiseWarning.isEmpty() || clpCruiseWarningSpeed.isEmpty()) return;
if (clpSpeedLimitDisplay.isEmpty() || clpSpeedLimitDisplay == "0") return;
bool isOver = (clpCruiseWarning == "over");
if (!isOver && clpCruiseWarning != "under") return;
p.save();
// Same dimensions as speed limit sign
const int signW = 189;
const int signH = 239;
const int margin = 20;
const int borderW = 6;
const int innerBorderW = 4;
const int innerMargin = 10;
const int cornerR = 15;
const int gap = 20;
// Position: directly above the speed limit sign
int speedLimitY = height() - signH - margin;
QRect signRect(margin, speedLimitY - signH - gap, signW, signH);
if (nightriderMode) {
// Nightrider: black background with colored border/text
QColor accentColor = isOver ? QColor(220, 50, 50) : QColor(50, 180, 80);
p.setPen(QPen(accentColor, borderW));
p.setBrush(QColor(0, 0, 0, 220));
p.drawRoundedRect(signRect, cornerR, cornerR);
QRect innerRect = signRect.adjusted(innerMargin, innerMargin, -innerMargin, -innerMargin);
p.setPen(QPen(accentColor, innerBorderW));
p.setBrush(Qt::NoBrush);
p.drawRoundedRect(innerRect, cornerR - 4, cornerR - 4);
// "CRUISE" text
p.setPen(accentColor);
p.setFont(InterFont(26, QFont::Bold));
p.drawText(innerRect.adjusted(0, 15, 0, 0), Qt::AlignTop | Qt::AlignHCenter, "CRUISE");
// "SET" text
p.setFont(InterFont(26, QFont::Bold));
p.drawText(innerRect.adjusted(0, 45, 0, 0), Qt::AlignTop | Qt::AlignHCenter, "SET");
// Cruise speed number
p.setFont(InterFont(90, QFont::Bold));
p.drawText(innerRect.adjusted(0, 86, 0, 0), Qt::AlignCenter, clpCruiseWarningSpeed);
} else {
// Normal: colored background with white border/text
QColor bgColor = isOver ? QColor(200, 30, 30, 240) : QColor(40, 160, 60, 240);
QColor fgColor(255, 255, 255);
p.setPen(QPen(fgColor, borderW));
p.setBrush(bgColor);
p.drawRoundedRect(signRect, cornerR, cornerR);
QRect innerRect = signRect.adjusted(innerMargin, innerMargin, -innerMargin, -innerMargin);
p.setPen(QPen(fgColor, innerBorderW));
p.setBrush(Qt::NoBrush);
p.drawRoundedRect(innerRect, cornerR - 4, cornerR - 4);
// "CRUISE" text
p.setPen(fgColor);
p.setFont(InterFont(26, QFont::Bold));
p.drawText(innerRect.adjusted(0, 15, 0, 0), Qt::AlignTop | Qt::AlignHCenter, "CRUISE");
// "SET" text
p.setFont(InterFont(26, QFont::Bold));
p.drawText(innerRect.adjusted(0, 45, 0, 0), Qt::AlignTop | Qt::AlignHCenter, "SET");
// Cruise speed number
p.setFont(InterFont(90, QFont::Bold));
p.drawText(innerRect.adjusted(0, 86, 0, 0), Qt::AlignCenter, clpCruiseWarningSpeed);
}
p.restore();
}
void AnnotatedCameraWidget::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { void AnnotatedCameraWidget::drawText(QPainter &p, int x, int y, const QString &text, int alpha) {
QRect real_rect = p.fontMetrics().boundingRect(text); QRect real_rect = p.fontMetrics().boundingRect(text);
real_rect.moveCenter({x, y - real_rect.height() / 2}); real_rect.moveCenter({x, y - real_rect.height() / 2});
@@ -543,6 +731,87 @@ void AnnotatedCameraWidget::drawText(QPainter &p, int x, int y, const QString &t
p.drawText(real_rect.x(), real_rect.bottom(), text); p.drawText(real_rect.x(), real_rect.bottom(), text);
} }
// CLEARPILOT: System health overlay — shows metrics that indicate the system
// is overburdened or behind. Toggled via ClearpilotShowHealthMetrics param.
// Metrics (top→bottom): FPS, DROP, TEMP, CPU, MEM, FAN
// FPS: modeld framerate — 20 normally, 0 in park. Read from ModelFps memory
// param which modeld writes only on transition.
// DROP (%): modelV2 frameDropPerc — modeld losing frames; controlsd errors >20%
// TEMP (°C): deviceState.maxTempC — thermal throttling starts ~75, serious >88
// CPU (%): max core from deviceState.cpuUsagePercent
// MEM (%): deviceState.memoryUsagePercent
// FAN (%): actual fan duty from peripheralState RPM (scaled to 6500 RPM = 100%)
// Each value color-codes green/yellow/red by severity.
void AnnotatedCameraWidget::drawHealthMetrics(QPainter &p) {
static bool enabled = Params().getBool("ClearpilotShowHealthMetrics");
static int check_counter = 0;
// re-check the param every ~2s without a toggle signal path
if (++check_counter >= 40) {
check_counter = 0;
enabled = Params().getBool("ClearpilotShowHealthMetrics");
}
if (!enabled) return;
SubMaster &sm = *(uiState()->sm);
auto ds = sm["deviceState"].getDeviceState();
auto mv = sm["modelV2"].getModelV2();
auto ps = sm["peripheralState"].getPeripheralState();
int model_fps = paramsMemory.getInt("ModelFps");
float drop_pct = mv.getFrameDropPerc();
float temp_c = ds.getMaxTempC();
int mem_pct = ds.getMemoryUsagePercent();
int cpu_pct = 0;
for (auto v : ds.getCpuUsagePercent()) cpu_pct = std::max(cpu_pct, (int)v);
// Actual fan (not commanded): scale RPM to 0-100 using 6500 RPM as full scale
int fan_pct = std::min(100, (int)(ps.getFanSpeedRpm() * 100 / 6500));
auto color_for = [](float v, float warn, float crit) {
if (v >= crit) return QColor(0xff, 0x50, 0x50); // red
if (v >= warn) return QColor(0xff, 0xd0, 0x40); // yellow
return QColor(0xff, 0xff, 0xff); // white (ok)
};
struct Row { QString label; QString value; QColor color; };
Row rows[] = {
{"FPS", QString::number(model_fps), QColor(0xff, 0xff, 0xff)},
{"DROP", QString::number((int)drop_pct),color_for(drop_pct, 5.f, 15.f)},
{"TEMP", QString::number((int)temp_c), color_for(temp_c, 75.f, 88.f)},
{"CPU", QString::number(cpu_pct), color_for((float)cpu_pct, 75.f, 90.f)},
{"MEM", QString::number(mem_pct), color_for((float)mem_pct, 70.f, 85.f)},
{"FAN", QString::number(fan_pct), QColor(0xff, 0xff, 0xff)},
};
p.save();
p.setFont(InterFont(90, QFont::Bold));
QFontMetrics fm = p.fontMetrics();
int row_h = fm.height(); // natural line height at 90pt bold
int gap = 40; // requested 40px between values
int margin = 30; // requested 30px margin
int panel_w = 360; // fixed width — fits "TEMP 99"
int n = sizeof(rows) / sizeof(rows[0]);
int panel_h = n * row_h + (n - 1) * gap + 2 * margin;
int x = width() - panel_w - margin;
int y = height() - panel_h - margin;
// black background
p.setPen(Qt::NoPen);
p.setBrush(QColor(0, 0, 0, 200));
p.drawRoundedRect(QRect(x, y, panel_w, panel_h), 20, 20);
// rows
int text_y = y + margin + fm.ascent();
for (int i = 0; i < n; i++) {
p.setPen(rows[i].color);
// label left (shifted -50px per user request), value right
p.drawText(x + margin - 50, text_y, rows[i].label);
QRect vrect = fm.boundingRect(rows[i].value);
p.drawText(x + panel_w - margin - vrect.width(), text_y, rows[i].value);
text_y += row_h + gap;
}
p.restore();
}
void AnnotatedCameraWidget::initializeGL() { void AnnotatedCameraWidget::initializeGL() {
CameraWidget::initializeGL(); CameraWidget::initializeGL();
qInfo() << "OpenGL version:" << QString((const char*)glGetString(GL_VERSION)); qInfo() << "OpenGL version:" << QString((const char*)glGetString(GL_VERSION));
@@ -562,13 +831,6 @@ void AnnotatedCameraWidget::updateFrameMat() {
s->fb_w = w; s->fb_w = w;
s->fb_h = h; s->fb_h = h;
if (screenDisplayMode == 1 || screenDisplayMode == 2) {
// Render a black box instead of the video feed
QPainter painter(this);
painter.fillRect(0, 0, w, h, Qt::black);
return;
}
// Apply transformation such that video pixel coordinates match video // Apply transformation such that video pixel coordinates match video
// 1) Put (0, 0) in the middle of the video // 1) Put (0, 0) in the middle of the video
// 2) Apply same scaling as video // 2) Apply same scaling as video
@@ -580,32 +842,59 @@ void AnnotatedCameraWidget::updateFrameMat() {
} }
void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) { void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) {
if (screenDisplayMode == 2) {
return;
}
painter.save(); painter.save();
// CLEARPILOT: color channel code rewriten to allow custom colors // CLEARPILOT: color channel code rewriten to allow custom colors
SubMaster &sm = *(s->sm); SubMaster &sm = *(s->sm);
// CLEARPILOT: nightrider mode — outline only, no fill
bool outlineOnly = nightriderMode;
// CLEARPILOT: in nightrider mode, hide all lines when not engaged
if (outlineOnly && edgeColor == bg_colors[STATUS_DISENGAGED]) {
painter.restore();
return;
}
// CLEARPILOT: nightrider lines are 1px wider (3 instead of 2)
int outlineWidth = outlineOnly ? 3 : 2;
// CLEARPILOT: lane lines 5% thinner than the generic outline (QPen accepts float width)
float laneLineWidth = outlineOnly ? (float)outlineWidth * 0.95f : (float)outlineWidth;
// lanelines // lanelines
for (int i = 0; i < std::size(scene.lane_line_vertices); ++i) { for (int i = 0; i < std::size(scene.lane_line_vertices); ++i) {
painter.setBrush(QColor::fromRgbF(1.0, 1.0, 1.0, std::clamp<float>(scene.lane_line_probs[i], 0.0, 0.7))); QColor lineColor = QColor::fromRgbF(1.0, 1.0, 1.0, std::clamp<float>(scene.lane_line_probs[i], 0.0, 0.7));
if (outlineOnly) {
painter.setPen(QPen(lineColor, laneLineWidth));
painter.setBrush(Qt::NoBrush);
} else {
painter.setPen(Qt::NoPen);
painter.setBrush(lineColor);
}
painter.drawPolygon(scene.lane_line_vertices[i]); painter.drawPolygon(scene.lane_line_vertices[i]);
} }
if (outlineOnly) painter.setPen(Qt::NoPen);
// road edges // road edges
for (int i = 0; i < std::size(scene.road_edge_vertices); ++i) { for (int i = 0; i < std::size(scene.road_edge_vertices); ++i) {
painter.setBrush(QColor::fromRgbF(1.0, 0, 0, std::clamp<float>(1.0 - scene.road_edge_stds[i], 0.0, 1.0))); QColor edgeCol = QColor::fromRgbF(1.0, 0, 0, std::clamp<float>(1.0 - scene.road_edge_stds[i], 0.0, 1.0));
if (outlineOnly) {
painter.setPen(QPen(edgeCol, outlineWidth));
painter.setBrush(Qt::NoBrush);
} else {
painter.setPen(Qt::NoPen);
painter.setBrush(edgeCol);
}
painter.drawPolygon(scene.road_edge_vertices[i]); painter.drawPolygon(scene.road_edge_vertices[i]);
} }
if (outlineOnly) painter.setPen(Qt::NoPen);
// paint center lane path // paint center lane path
// QColor bg_colors[CHANGE_LANE_PATH_COLOR]; // QColor bg_colors[CHANGE_LANE_PATH_COLOR];
bool is_no_lat_lane_change = paramsMemory.getBool("no_lat_lane_change"); // CLEARPILOT: read from frogpilotCarControl cereal message (was paramsMemory)
bool is_no_lat_lane_change = sm["frogpilotCarControl"].getFrogpilotCarControl().getNoLatLaneChange();
QColor center_lane_color; QColor center_lane_color;
@@ -665,12 +954,23 @@ void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) {
path_gradient.setColorAt(1.0, QColor(center_lane_color.red(), center_lane_color.green(), center_lane_color.blue(), static_cast<int>(CENTER_LANE_ALPHA * 255 * 0.0))); path_gradient.setColorAt(1.0, QColor(center_lane_color.red(), center_lane_color.green(), center_lane_color.blue(), static_cast<int>(CENTER_LANE_ALPHA * 255 * 0.0)));
} }
painter.setBrush(path_gradient); if (outlineOnly) {
// CLEARPILOT: in nightrider, the tire path outline is light blue at 3px.
// Uses a fixed light-blue instead of center_lane_color (which is status-tinted) so
// the path reads as a neutral guide, not as engagement/status feedback.
QColor lightBlue(153, 204, 255, 220); // #99CCFF light blue, mostly opaque
painter.setPen(QPen(lightBlue, 3));
painter.setBrush(Qt::NoBrush);
} else {
painter.setPen(Qt::NoPen);
painter.setBrush(path_gradient);
}
painter.drawPolygon(scene.track_vertices); painter.drawPolygon(scene.track_vertices);
if (outlineOnly) painter.setPen(Qt::NoPen);
} }
// Paint path edges ,Use current background color // Paint path edges ,Use current background color
if (edgeColor != bg_colors[STATUS_DISENGAGED]) { if (edgeColor != bg_colors[STATUS_DISENGAGED] && !outlineOnly) {
QLinearGradient edge_gradient; QLinearGradient edge_gradient;
edge_gradient.setColorAt(0.0, QColor(edgeColor.red(), edgeColor.green(), edgeColor.blue(), static_cast<int>(255))); edge_gradient.setColorAt(0.0, QColor(edgeColor.red(), edgeColor.green(), edgeColor.blue(), static_cast<int>(255)));
edge_gradient.setColorAt(0.5, QColor(edgeColor.red(), edgeColor.green(), edgeColor.blue(), static_cast<int>(255 * 0.8) )); edge_gradient.setColorAt(0.5, QColor(edgeColor.red(), edgeColor.green(), edgeColor.blue(), static_cast<int>(255 * 0.8) ));
@@ -686,18 +986,24 @@ void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) {
// Paint blindspot path // Paint blindspot path
if (scene.blind_spot_path) { if (scene.blind_spot_path) {
QLinearGradient bs(0, height(), 0, 0); QColor bsColor = QColor::fromHslF(0 / 360., 0.75, 0.50, 0.6);
bs.setColorAt(0.0, QColor::fromHslF(0 / 360., 0.75, 0.50, 0.6)); if (outlineOnly) {
bs.setColorAt(0.5, QColor::fromHslF(0 / 360., 0.75, 0.50, 0.4)); painter.setPen(QPen(bsColor, outlineWidth));
bs.setColorAt(1.0, QColor::fromHslF(0 / 360., 0.75, 0.50, 0.2)); painter.setBrush(Qt::NoBrush);
} else {
painter.setBrush(bs); QLinearGradient bs(0, height(), 0, 0);
bs.setColorAt(0.0, QColor::fromHslF(0 / 360., 0.75, 0.50, 0.6));
bs.setColorAt(0.5, QColor::fromHslF(0 / 360., 0.75, 0.50, 0.4));
bs.setColorAt(1.0, QColor::fromHslF(0 / 360., 0.75, 0.50, 0.2));
painter.setBrush(bs);
}
if (blindSpotLeft) { if (blindSpotLeft) {
painter.drawPolygon(scene.track_adjacent_vertices[4]); painter.drawPolygon(scene.track_adjacent_vertices[4]);
} }
if (blindSpotRight) { if (blindSpotRight) {
painter.drawPolygon(scene.track_adjacent_vertices[5]); painter.drawPolygon(scene.track_adjacent_vertices[5]);
} }
if (outlineOnly) painter.setPen(Qt::NoPen);
} }
// Paint adjacent lane paths // Paint adjacent lane paths
@@ -708,16 +1014,19 @@ void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) {
float maxLaneWidth = laneDetectionWidth * 1.5; float maxLaneWidth = laneDetectionWidth * 1.5;
auto paintLane = [=](QPainter &painter, const QPolygonF &lane, float laneWidth, bool blindspot) { auto paintLane = [=](QPainter &painter, const QPolygonF &lane, float laneWidth, bool blindspot) {
QLinearGradient al(0, height(), 0, 0);
bool redPath = laneWidth < minLaneWidth || laneWidth > maxLaneWidth || blindspot; bool redPath = laneWidth < minLaneWidth || laneWidth > maxLaneWidth || blindspot;
float hue = redPath ? 0.0 : 120.0 * (laneWidth - minLaneWidth) / (maxLaneWidth - minLaneWidth); float hue = redPath ? 0.0 : 120.0 * (laneWidth - minLaneWidth) / (maxLaneWidth - minLaneWidth);
al.setColorAt(0.0, QColor::fromHslF(hue / 360.0, 0.75, 0.50, 0.6)); if (outlineOnly) {
al.setColorAt(0.5, QColor::fromHslF(hue / 360.0, 0.75, 0.50, 0.4)); painter.setPen(QPen(QColor::fromHslF(hue / 360.0, 0.75, 0.50, 0.6), 2));
al.setColorAt(1.0, QColor::fromHslF(hue / 360.0, 0.75, 0.50, 0.2)); painter.setBrush(Qt::NoBrush);
} else {
painter.setBrush(al); QLinearGradient al(0, height(), 0, 0);
al.setColorAt(0.0, QColor::fromHslF(hue / 360.0, 0.75, 0.50, 0.6));
al.setColorAt(0.5, QColor::fromHslF(hue / 360.0, 0.75, 0.50, 0.4));
al.setColorAt(1.0, QColor::fromHslF(hue / 360.0, 0.75, 0.50, 0.2));
painter.setBrush(al);
}
painter.drawPolygon(lane); painter.drawPolygon(lane);
painter.setFont(InterFont(30, QFont::DemiBold)); painter.setFont(InterFont(30, QFont::DemiBold));
@@ -805,6 +1114,10 @@ void AnnotatedCameraWidget::paintEvent(QPaintEvent *event) {
const cereal::ModelDataV2::Reader &model = sm["modelV2"].getModelV2(); const cereal::ModelDataV2::Reader &model = sm["modelV2"].getModelV2();
const float v_ego = sm["carState"].getCarState().getVEgo(); const float v_ego = sm["carState"].getCarState().getVEgo();
// CLEARPILOT: read display mode early — needed for camera suppression
displayMode = paramsMemory.getInt("ScreenDisplayMode");
nightriderMode = (displayMode == 1 || displayMode == 4);
// draw camera frame // draw camera frame
{ {
std::lock_guard lk(frame_lock); std::lock_guard lk(frame_lock);
@@ -845,9 +1158,19 @@ void AnnotatedCameraWidget::paintEvent(QPaintEvent *event) {
} else { } else {
CameraWidget::updateCalibration(DEFAULT_CALIBRATION); CameraWidget::updateCalibration(DEFAULT_CALIBRATION);
} }
// CLEARPILOT: force CameraWidget bg to black in nightrider to prevent color bleed
if (nightriderMode) {
CameraWidget::setBackgroundColor(Qt::black);
}
painter.beginNativePainting(); painter.beginNativePainting();
CameraWidget::setFrameId(model.getFrameId()); if (nightriderMode) {
CameraWidget::paintGL(); // CLEARPILOT: black background, no camera feed
glClearColor(0.0f, 0.0f, 0.0f, 1.0f);
glClear(GL_COLOR_BUFFER_BIT | GL_STENCIL_BUFFER_BIT);
} else {
CameraWidget::setFrameId(model.getFrameId());
CameraWidget::paintGL();
}
painter.endNativePainting(); painter.endNativePainting();
} }
@@ -925,7 +1248,7 @@ void AnnotatedCameraWidget::initializeFrogPilotWidgets() {
animationFrameIndex = (animationFrameIndex + 1) % totalFrames; animationFrameIndex = (animationFrameIndex + 1) % totalFrames;
}); });
// Initialize the timer for the screen recorder // CLEARPILOT: screen recorder disabled — replaced by dedicated dashcamd process
// QTimer *record_timer = new QTimer(this); // QTimer *record_timer = new QTimer(this);
// connect(record_timer, &QTimer::timeout, this, [this]() { // connect(record_timer, &QTimer::timeout, this, [this]() {
// if (recorder_btn) { // if (recorder_btn) {
@@ -1010,7 +1333,8 @@ void AnnotatedCameraWidget::updateFrogPilotWidgets() {
} }
void AnnotatedCameraWidget::paintFrogPilotWidgets(QPainter &p) { void AnnotatedCameraWidget::paintFrogPilotWidgets(QPainter &p) {
if ((showAlwaysOnLateralStatusBar || showConditionalExperimentalStatusBar || roadNameUI)) { // CLEARPILOT: only show status bar when telemetry is enabled
if (paramsMemory.getBool("TelemetryEnabled")) {
drawStatusBar(p); drawStatusBar(p);
} }
@@ -1022,8 +1346,7 @@ void AnnotatedCameraWidget::paintFrogPilotWidgets(QPainter &p) {
drawSLCConfirmation(p); drawSLCConfirmation(p);
} }
// recorder_btn->setVisible(scene.screen_recorder && !mapOpen); // CLEARPILOT: screen recorder disabled, using dashcamd instead
recorder_btn->setVisible(false);
} }
void AnnotatedCameraWidget::drawLeadInfo(QPainter &p) { void AnnotatedCameraWidget::drawLeadInfo(QPainter &p) {
@@ -1212,7 +1535,30 @@ void AnnotatedCameraWidget::drawStatusBar(QPainter &p) {
QString roadName = roadNameUI ? QString::fromStdString(paramsMemory.get("RoadName")) : QString(); QString roadName = roadNameUI ? QString::fromStdString(paramsMemory.get("RoadName")) : QString();
if (alwaysOnLateralActive && showAlwaysOnLateralStatusBar) { // CLEARPILOT: telemetry status bar — show live stats when telemetry enabled
if (paramsMemory.getBool("TelemetryEnabled")) {
SubMaster &sm = *(uiState()->sm);
auto deviceState = sm["deviceState"].getDeviceState();
int maxTempC = deviceState.getMaxTempC();
int fanPct = deviceState.getFanSpeedPercentDesired();
bool standstill = sm["carState"].getCarState().getStandstill();
static double last_model_status_t = 0;
static float model_status_fps = 0;
if (sm.updated("modelV2")) {
double now = millis_since_boot();
if (last_model_status_t > 0) {
double dt = now - last_model_status_t;
if (dt > 0) model_status_fps = model_status_fps * 0.8 + (1000.0 / dt) * 0.2;
}
last_model_status_t = now;
}
newStatus = QString("%1\u00B0C FAN %2% MDL %3")
.arg(maxTempC).arg(fanPct).arg(model_status_fps, 0, 'f', 0);
if (standstill) newStatus += " STANDSTILL";
// CLEARPILOT: suppress "Always On Lateral active" status bar message
} else if (false && alwaysOnLateralActive && showAlwaysOnLateralStatusBar) {
newStatus = tr("Always On Lateral active") + (tr(". Press the \"Cruise Control\" button to disable")); newStatus = tr("Always On Lateral active") + (tr(". Press the \"Cruise Control\" button to disable"));
} else if (showConditionalExperimentalStatusBar) { } else if (showConditionalExperimentalStatusBar) {
newStatus = conditionalStatusMap[status != STATUS_DISENGAGED ? conditionalStatus : 0]; newStatus = conditionalStatusMap[status != STATUS_DISENGAGED ? conditionalStatus : 0];
+17 -4
View File
@@ -12,7 +12,7 @@
#include "selfdrive/ui/ui.h" #include "selfdrive/ui/ui.h"
#include "selfdrive/ui/qt/widgets/cameraview.h" #include "selfdrive/ui/qt/widgets/cameraview.h"
#include "selfdrive/frogpilot/screenrecorder/screenrecorder.h" // #include "selfdrive/frogpilot/screenrecorder/screenrecorder.h" // DISABLED: using dashcamd instead
const int btn_size = 192; const int btn_size = 192;
const int img_size = (btn_size / 4) * 3; const int img_size = (btn_size / 4) * 3;
@@ -47,16 +47,31 @@ public:
explicit AnnotatedCameraWidget(VisionStreamType type, QWidget* parent = 0); explicit AnnotatedCameraWidget(VisionStreamType type, QWidget* parent = 0);
void updateState(const UIState &s); void updateState(const UIState &s);
void updateLaneEdgeColor(QColor &bgColor); void updateLaneEdgeColor(QColor &bgColor);
int screenDisplayMode = 0;
private: private:
void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255); void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255);
void drawSpeedWidget(QPainter &p, int x, int y, const QString &title, const QString &speedLimitStr, QColor colorSpeed, int width = 176); void drawSpeedWidget(QPainter &p, int x, int y, const QString &title, const QString &speedLimitStr, QColor colorSpeed, int width = 176);
void drawSpeedLimitSign(QPainter &p);
void drawCruiseWarningSign(QPainter &p);
void drawHealthMetrics(QPainter &p);
QVBoxLayout *main_layout; QVBoxLayout *main_layout;
QPixmap dm_img; QPixmap dm_img;
float speed; float speed;
bool has_gps_speed = false;
bool nightriderMode = false;
int displayMode = 0;
QString speedUnit; QString speedUnit;
// ClearPilot speed state (from params_memory, updated ~2Hz)
bool clpHasSpeed = false;
QString clpSpeedDisplay;
QString clpSpeedLimitDisplay;
QString clpSpeedUnit;
QString clpCruiseWarning;
QString clpCruiseWarningSpeed;
int clpParamFrame = 0;
float setSpeed; float setSpeed;
float speedLimit; float speedLimit;
bool is_cruise_set = false; bool is_cruise_set = false;
@@ -89,8 +104,6 @@ private:
Params paramsMemory{"/dev/shm/params"}; Params paramsMemory{"/dev/shm/params"};
UIScene &scene; UIScene &scene;
ScreenRecorder *recorder_btn;
QHBoxLayout *bottom_layout; QHBoxLayout *bottom_layout;
bool alwaysOnLateralActive; bool alwaysOnLateralActive;
+74 -13
View File
@@ -30,11 +30,12 @@ ReadyWindow::ReadyWindow(QWidget *parent) : QWidget(parent) {
timer = new QTimer(this); timer = new QTimer(this);
timer->callOnTimeout(this, &ReadyWindow::refresh); timer->callOnTimeout(this, &ReadyWindow::refresh);
uptime.start();
} }
void ReadyWindow::showEvent(QShowEvent *event) { void ReadyWindow::showEvent(QShowEvent *event) {
refresh(); refresh();
timer->start(5 * 1000); timer->start(2 * 1000);
} }
void ReadyWindow::hideEvent(QHideEvent *event) { void ReadyWindow::hideEvent(QHideEvent *event) {
@@ -43,34 +44,94 @@ void ReadyWindow::hideEvent(QHideEvent *event) {
void ReadyWindow::paintEvent(QPaintEvent *event) { void ReadyWindow::paintEvent(QPaintEvent *event) {
QPainter painter(this); QPainter painter(this);
QPixmap *img_shown = nullptr; painter.fillRect(rect(), Qt::black);
if (is_hot) { if (is_hot) {
if (img_hot.isNull()) { if (img_hot.isNull()) {
img_hot.load("/data/openpilot/selfdrive/clearpilot/theme/clearpilot/images/hot.png"); img_hot.load("/data/openpilot/selfdrive/clearpilot/theme/clearpilot/images/hot.png");
} }
img_shown = &img_hot; int x = (width() - img_hot.width()) / 2;
int y = (height() - img_hot.height()) / 2;
painter.drawPixmap(x, y, img_hot);
} else { } else {
if (img_ready.isNull()) { // Boot logo — same rotation as spinner (bg.jpg is pre-rotated 90° CW for framebuffer)
img_ready.load("/data/openpilot/selfdrive/clearpilot/theme/clearpilot/images/ready.png"); if (img_bg.isNull()) {
QPixmap raw("/usr/comma/bg.jpg");
if (!raw.isNull()) {
QTransform rot;
rot.rotate(-90);
img_bg = raw.transformed(rot);
}
}
if (!img_bg.isNull()) {
QPixmap scaled = img_bg.scaled(size(), Qt::KeepAspectRatio, Qt::SmoothTransformation);
int x = (width() - scaled.width()) / 2;
int y = (height() - scaled.height()) / 2;
painter.drawPixmap(x, y, scaled);
} }
img_shown = &img_ready;
}
int x = (width() - img_shown->width()) / 2; if (error_msg.isEmpty() && !has_driven) {
int y = (height() - img_shown->height()) / 2; // "READY!" 8-bit text sprite, 15% below center — only before first drive
painter.drawPixmap(x, y, *img_shown); static QPixmap ready_text("/data/openpilot/selfdrive/clearpilot/theme/clearpilot/images/ready_text.png");
if (!ready_text.isNull()) {
int tx = (width() - ready_text.width()) / 2;
int ty = height() / 2 + height() * 15 / 100;
painter.drawPixmap(tx, ty, ready_text);
}
} else {
// Error state: red text at 25% below center
QFont font("Inter", 50, QFont::Bold);
painter.setFont(font);
painter.setPen(QColor(0xFF, 0x44, 0x44));
int ty = height() / 2 + height() * 25 / 100;
QRect text_rect(0, ty, width(), 100);
painter.drawText(text_rect, Qt::AlignHCenter | Qt::AlignTop, error_msg);
}
}
} }
void ReadyWindow::refresh() { void ReadyWindow::refresh() {
bool changed = false;
// Temperature check
std::string bytes = params.get("Offroad_TemperatureTooHigh"); std::string bytes = params.get("Offroad_TemperatureTooHigh");
bool was_hot = is_hot;
if (!bytes.empty()) { if (!bytes.empty()) {
auto doc = QJsonDocument::fromJson(bytes.data()); auto doc = QJsonDocument::fromJson(bytes.data());
is_hot = true; is_hot = true;
cur_temp = doc["extra"].toString(); cur_temp = doc["extra"].toString();
update(); } else {
} else if (is_hot) {
is_hot = false; is_hot = false;
update();
} }
if (is_hot != was_hot) changed = true;
// Error state checks (only when not hot — hot has its own display)
if (!is_hot) {
QString prev_error = error_msg;
// Panda check — same logic as sidebar, with 10s grace period on startup
if (uptime.elapsed() > 10000 &&
uiState()->scene.pandaType == cereal::PandaState::PandaType::UNKNOWN) {
error_msg = "PANDA NOT CONNECTED";
}
// Car unrecognized check
else if (!params.get("Offroad_CarUnrecognized").empty()) {
error_msg = "CAR NOT RECOGNIZED";
}
else {
error_msg = "";
}
if (error_msg != prev_error) changed = true;
}
// Reset has_driven on ignition off→on (power cycle)
bool started = uiState()->scene.started;
if (!last_started && started) {
has_driven = false;
changed = true;
}
last_started = started;
if (changed) update();
} }
+6 -1
View File
@@ -8,6 +8,7 @@
#include <QSocketNotifier> #include <QSocketNotifier>
#include <QVariantAnimation> #include <QVariantAnimation>
#include <QWidget> #include <QWidget>
#include <QElapsedTimer>
#include <QTimer> #include <QTimer>
#include "common/util.h" #include "common/util.h"
@@ -17,6 +18,7 @@ class ReadyWindow : public QWidget {
Q_OBJECT Q_OBJECT
public: public:
ReadyWindow(QWidget* parent = nullptr); ReadyWindow(QWidget* parent = nullptr);
bool has_driven = false;
private: private:
void showEvent(QShowEvent *event) override; void showEvent(QShowEvent *event) override;
void hideEvent(QHideEvent *event) override; void hideEvent(QHideEvent *event) override;
@@ -26,6 +28,9 @@ private:
QTimer* timer; QTimer* timer;
bool is_hot = false; bool is_hot = false;
QString cur_temp; QString cur_temp;
QPixmap img_ready; QString error_msg; // non-empty = show red error instead of READY!
QElapsedTimer uptime;
bool last_started = false;
QPixmap img_bg;
QPixmap img_hot; QPixmap img_hot;
}; };
Binary file not shown.
+310 -3
View File
@@ -1,6 +1,9 @@
#include "selfdrive/ui/qt/window.h" #include "selfdrive/ui/qt/window.h"
#include <QFontDatabase> #include <QFontDatabase>
#include <QMouseEvent>
#include <zmq.h>
#include "system/hardware/hw.h" #include "system/hardware/hw.h"
@@ -11,6 +14,7 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) {
homeWindow = new HomeWindow(this); homeWindow = new HomeWindow(this);
main_layout->addWidget(homeWindow); main_layout->addWidget(homeWindow);
QObject::connect(homeWindow, &HomeWindow::openSettings, this, &MainWindow::openSettings); QObject::connect(homeWindow, &HomeWindow::openSettings, this, &MainWindow::openSettings);
QObject::connect(homeWindow, &HomeWindow::openStatus, this, &MainWindow::openStatus);
QObject::connect(homeWindow, &HomeWindow::closeSettings, this, &MainWindow::closeSettings); QObject::connect(homeWindow, &HomeWindow::closeSettings, this, &MainWindow::closeSettings);
settingsWindow = new SettingsWindow(this); settingsWindow = new SettingsWindow(this);
@@ -24,6 +28,11 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) {
homeWindow->showDriverView(true); homeWindow->showDriverView(true);
}); });
// CLEARPILOT: Status window
statusWindow = new StatusWindow(this);
main_layout->addWidget(statusWindow);
QObject::connect(statusWindow, &StatusWindow::closeStatus, this, &MainWindow::closeSettings);
onboardingWindow = new OnboardingWindow(this); onboardingWindow = new OnboardingWindow(this);
main_layout->addWidget(onboardingWindow); main_layout->addWidget(onboardingWindow);
QObject::connect(onboardingWindow, &OnboardingWindow::onboardingDone, [=]() { QObject::connect(onboardingWindow, &OnboardingWindow::onboardingDone, [=]() {
@@ -35,13 +44,17 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) {
QObject::connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { QObject::connect(uiState(), &UIState::offroadTransition, [=](bool offroad) {
if (!offroad) { if (!offroad) {
closeSettings(); // CLEARPILOT: just switch to homeWindow, don't show sidebar
// HomeWindow::offroadTransition handles the internal view
main_layout->setCurrentWidget(homeWindow);
} }
}); });
QObject::connect(device(), &Device::interactiveTimeout, [=]() { QObject::connect(device(), &Device::interactiveTimeout, [=]() {
if (main_layout->currentWidget() == settingsWindow) { // CLEARPILOT: on timeout, return to splash/onroad (not ClearPilotPanel)
closeSettings(); if (main_layout->currentWidget() != homeWindow) {
main_layout->setCurrentWidget(homeWindow);
} }
homeWindow->offroadTransition(!uiState()->scene.started);
}); });
// load fonts // load fonts
@@ -63,6 +76,74 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) {
} }
)"); )");
setAttribute(Qt::WA_NoSystemBackground); setAttribute(Qt::WA_NoSystemBackground);
// CLEARPILOT: UI introspection RPC server
zmq_ctx = zmq_ctx_new();
zmq_sock = zmq_socket(zmq_ctx, ZMQ_REP);
zmq_bind(zmq_sock, "ipc:///tmp/clearpilot_ui_rpc");
int fd;
size_t fd_sz = sizeof(fd);
zmq_getsockopt(zmq_sock, ZMQ_FD, &fd, &fd_sz);
rpc_notifier = new QSocketNotifier(fd, QSocketNotifier::Read, this);
connect(rpc_notifier, &QSocketNotifier::activated, this, &MainWindow::handleRpcRequest);
}
void MainWindow::handleRpcRequest() {
int events = 0;
size_t events_sz = sizeof(events);
zmq_getsockopt(zmq_sock, ZMQ_EVENTS, &events, &events_sz);
if (!(events & ZMQ_POLLIN)) return;
char buf[256];
int rc = zmq_recv(zmq_sock, buf, sizeof(buf) - 1, ZMQ_DONTWAIT);
if (rc < 0) return;
buf[rc] = 0;
QString response;
if (strcmp(buf, "dump") == 0) {
response = dumpWidgetTree(this);
} else {
response = "unknown command";
}
QByteArray resp = response.toUtf8();
zmq_send(zmq_sock, resp.data(), resp.size(), 0);
}
QString MainWindow::dumpWidgetTree(QWidget *w, int depth) {
QString result;
QString indent(depth * 2, ' ');
QString className = w->metaObject()->className();
QString name = w->objectName().isEmpty() ? "(no name)" : w->objectName();
bool visible = w->isVisible();
QRect geo = w->geometry();
result += QString("%1%2 [%3] vis=%4 geo=%5,%6 %7x%8")
.arg(indent, className, name)
.arg(visible ? "Y" : "N")
.arg(geo.x()).arg(geo.y()).arg(geo.width()).arg(geo.height());
// Show stacked layout/widget current index
if (auto *sl = w->findChild<QStackedLayout *>(QString(), Qt::FindDirectChildrenOnly)) {
QWidget *cur = sl->currentWidget();
QString curClass = cur ? cur->metaObject()->className() : "null";
result += QString(" stack_cur=%1/%2(%3)").arg(sl->currentIndex()).arg(sl->count()).arg(curClass);
}
if (auto *sw = qobject_cast<QStackedWidget *>(w)) {
QWidget *cur = sw->currentWidget();
QString curClass = cur ? cur->metaObject()->className() : "null";
result += QString(" stack_cur=%1/%2(%3)").arg(sw->currentIndex()).arg(sw->count()).arg(curClass);
}
result += "\n";
for (QObject *child : w->children()) {
QWidget *cw = qobject_cast<QWidget *>(child);
if (cw && depth < 4) {
result += dumpWidgetTree(cw, depth + 1);
}
}
return result;
} }
void MainWindow::openSettings(int index, const QString &param) { void MainWindow::openSettings(int index, const QString &param) {
@@ -70,6 +151,10 @@ void MainWindow::openSettings(int index, const QString &param) {
settingsWindow->setCurrentPanel(index, param); settingsWindow->setCurrentPanel(index, param);
} }
void MainWindow::openStatus() {
main_layout->setCurrentWidget(statusWindow);
}
void MainWindow::closeSettings() { void MainWindow::closeSettings() {
main_layout->setCurrentWidget(homeWindow); main_layout->setCurrentWidget(homeWindow);
@@ -86,6 +171,16 @@ bool MainWindow::eventFilter(QObject *obj, QEvent *event) {
case QEvent::TouchEnd: case QEvent::TouchEnd:
case QEvent::MouseButtonPress: case QEvent::MouseButtonPress:
case QEvent::MouseMove: { case QEvent::MouseMove: {
// CLEARPILOT: tap while screen-off (mode 3) -> wake to auto-normal (mode 0)
Params pmem{"/dev/shm/params"};
if (!device()->isAwake()) {
if (pmem.getInt("ScreenDisplayMode") == 3) {
pmem.putInt("ScreenDisplayMode", 0);
}
}
// CLEARPILOT: reset shutdown timer on any screen touch
static int touch_counter = 0;
pmem.put("ShutdownTouchReset", std::to_string(++touch_counter));
// ignore events when device is awakened by resetInteractiveTimeout // ignore events when device is awakened by resetInteractiveTimeout
ignore = !device()->isAwake(); ignore = !device()->isAwake();
device()->resetInteractiveTimeout(uiState()->scene.screen_timeout, uiState()->scene.screen_timeout_onroad); device()->resetInteractiveTimeout(uiState()->scene.screen_timeout, uiState()->scene.screen_timeout_onroad);
@@ -96,3 +191,215 @@ bool MainWindow::eventFilter(QObject *obj, QEvent *event) {
} }
return ignore; return ignore;
} }
// CLEARPILOT: Status window — live system stats, collected on background thread
#include <QFile>
#include <QProcess>
#include <QDateTime>
#include <QtConcurrent>
static QString readFile(const QString &path) {
QFile f(path);
if (f.open(QIODevice::ReadOnly)) return QString(f.readAll()).trimmed();
return "";
}
static QString shellCmd(const QString &cmd) {
QProcess p;
p.start("bash", QStringList() << "-c" << cmd);
p.waitForFinished(1000);
return QString(p.readAllStandardOutput()).trimmed();
}
static StatusWindow::StatusData collectStatus() {
StatusWindow::StatusData d;
d.time = QDateTime::currentDateTime().toString("yyyy-MM-dd hh:mm:ss");
d.storage = shellCmd("df -h /data | tail -1 | awk '{print $3 \" / \" $2 \" (\" $5 \" used)\"}'");
// RAM from /proc/meminfo (no subprocess needed)
QString meminfo = readFile("/proc/meminfo");
long total = 0, avail = 0;
for (const QString &line : meminfo.split('\n')) {
if (line.startsWith("MemTotal:")) total = line.split(QRegExp("\\s+"))[1].toLong();
if (line.startsWith("MemAvailable:")) avail = line.split(QRegExp("\\s+"))[1].toLong();
}
if (total > 0) {
long used = total - avail;
d.ram = QString("%1 / %2 MB").arg(used / 1024).arg(total / 1024);
}
// Load from /proc/loadavg
QString loadavg = readFile("/proc/loadavg");
QStringList parts = loadavg.split(' ');
if (parts.size() >= 3) {
d.load = QString("%1 %2 %3").arg(parts[0], parts[1], parts[2]);
}
// Temperature
QString temps = shellCmd("cat /sys/class/thermal/thermal_zone*/temp 2>/dev/null | sort -rn | head -1");
if (!temps.isEmpty()) {
d.temp_c = temps.toLong() / 1000.0f;
d.temp = QString("%1\u00B0C").arg(d.temp_c, 0, 'f', 1);
}
// Fan
QString fan = shellCmd("cat /sys/class/hwmon/hwmon*/fan1_input 2>/dev/null | head -1");
if (fan.isEmpty()) fan = readFile("/dev/shm/params/d/LastFanSpeed");
d.fan = fan.isEmpty() ? QString::fromUtf8("\u2014") : fan + " RPM";
// Network
d.ip = shellCmd("ip route get 1.1.1.1 2>/dev/null | head -1 | awk '{print $7}'");
d.wifi = shellCmd("iwconfig wlan0 2>/dev/null | grep -oP 'ESSID:\"\\K[^\"]*'");
// VPN
QString tun = shellCmd("ip link show tun0 2>/dev/null | head -1");
if (tun.contains("UP")) {
d.vpn_status = "up";
d.vpn_ip = shellCmd("ip addr show tun0 2>/dev/null | grep 'inet ' | awk '{print $2}'");
}
// GPS
d.gps = readFile("/data/params/d/LastGPSPosition");
// Telemetry
d.telemetry = readFile("/data/params/d/TelemetryEnabled");
// Dashcam
d.dashcam_state = readFile("/dev/shm/params/d/DashcamState");
if (d.dashcam_state.isEmpty()) d.dashcam_state = "stopped";
d.dashcam_frames = readFile("/dev/shm/params/d/DashcamFrames");
// Panda: checked on UI thread in applyResults() via scene.pandaType
return d;
}
StatusWindow::StatusWindow(QWidget *parent) : QFrame(parent) {
QVBoxLayout *layout = new QVBoxLayout(this);
layout->setContentsMargins(50, 60, 50, 40);
layout->setSpacing(0);
// Status rows
auto makeRow = [&](const QString &label) -> QLabel* {
QHBoxLayout *row = new QHBoxLayout();
row->setContentsMargins(20, 0, 20, 0);
QLabel *name = new QLabel(label);
name->setStyleSheet("color: grey; font-size: 38px;");
name->setFixedWidth(350);
row->addWidget(name);
QLabel *value = new QLabel("");
value->setStyleSheet("color: white; font-size: 38px;");
row->addWidget(value);
row->addStretch();
layout->addLayout(row);
layout->addSpacing(12);
return value;
};
time_label = makeRow("Time");
storage_label = makeRow("Storage");
ram_label = makeRow("Memory");
load_label = makeRow("Load");
temp_label = makeRow("Temperature");
fan_label = makeRow("Fan Speed");
panda_label = makeRow("Panda");
ip_label = makeRow("IP Address");
wifi_label = makeRow("WiFi");
vpn_label = makeRow("VPN");
gps_label = makeRow("GPS");
telemetry_label = makeRow("Telemetry");
dashcam_label = makeRow("Dashcam");
layout->addStretch();
setStyleSheet("StatusWindow { background-color: black; }");
connect(&watcher, &QFutureWatcher<StatusData>::finished, this, &StatusWindow::applyResults);
QTimer *timer = new QTimer(this);
connect(timer, &QTimer::timeout, this, &StatusWindow::kickRefresh);
timer->start(1000);
}
void StatusWindow::kickRefresh() {
if (!isVisible() || collecting) return;
collecting = true;
watcher.setFuture(QtConcurrent::run(collectStatus));
}
void StatusWindow::applyResults() {
collecting = false;
StatusData d = watcher.result();
time_label->setText(d.time);
storage_label->setText(d.storage);
if (!d.ram.isEmpty()) ram_label->setText(d.ram);
if (!d.load.isEmpty()) load_label->setText(d.load);
if (!d.temp.isEmpty()) {
temp_label->setText(d.temp);
temp_label->setStyleSheet(d.temp_c > 70 ? "color: #ff4444; font-size: 38px;" :
d.temp_c > 55 ? "color: #ffaa00; font-size: 38px;" :
"color: white; font-size: 38px;");
}
fan_label->setText(d.fan);
// Panda: same check as sidebar — read scene.pandaType on UI thread
if (uiState()->scene.pandaType != cereal::PandaState::PandaType::UNKNOWN) {
panda_label->setText("Connected");
panda_label->setStyleSheet("color: #17c44d; font-size: 38px;");
} else {
panda_label->setText("Not connected");
panda_label->setStyleSheet("color: #ff4444; font-size: 38px;");
}
ip_label->setText(d.ip.isEmpty() ? "No connection" : d.ip);
wifi_label->setText(d.wifi.isEmpty() ? "Not connected" : d.wifi);
if (d.vpn_status == "up") {
vpn_label->setText("Connected (" + d.vpn_ip + ")");
vpn_label->setStyleSheet("color: #17c44d; font-size: 38px;");
} else {
vpn_label->setText("Not connected");
vpn_label->setStyleSheet("color: #ff4444; font-size: 38px;");
}
if (d.gps.isEmpty()) {
gps_label->setText("No fix");
gps_label->setStyleSheet("color: #ff4444; font-size: 38px;");
} else {
gps_label->setText(d.gps);
gps_label->setStyleSheet("color: white; font-size: 38px;");
}
if (d.telemetry == "1") {
telemetry_label->setText("Enabled");
telemetry_label->setStyleSheet("color: #17c44d; font-size: 38px;");
} else {
telemetry_label->setText("Disabled");
telemetry_label->setStyleSheet("color: grey; font-size: 38px;");
}
if (d.dashcam_state == "recording") {
QString text = "Recording";
if (!d.dashcam_frames.isEmpty() && d.dashcam_frames != "0") text += " (" + d.dashcam_frames + " frames)";
dashcam_label->setText(text);
dashcam_label->setStyleSheet("color: #17c44d; font-size: 38px;");
} else if (d.dashcam_state == "waiting") {
dashcam_label->setText("Waiting");
dashcam_label->setStyleSheet("color: #ffaa00; font-size: 38px;");
} else {
dashcam_label->setText("Stopped");
dashcam_label->setStyleSheet("color: #ff4444; font-size: 38px;");
}
}
void StatusWindow::mousePressEvent(QMouseEvent *e) {
emit closeStatus();
}
+58
View File
@@ -1,12 +1,59 @@
#pragma once #pragma once
#include <QFutureWatcher>
#include <QStackedLayout> #include <QStackedLayout>
#include <QLabel>
#include <QSocketNotifier>
#include <QTimer>
#include <QWidget> #include <QWidget>
#include "selfdrive/ui/qt/home.h" #include "selfdrive/ui/qt/home.h"
#include "selfdrive/ui/qt/offroad/onboarding.h" #include "selfdrive/ui/qt/offroad/onboarding.h"
#include "selfdrive/ui/qt/offroad/settings.h" #include "selfdrive/ui/qt/offroad/settings.h"
class StatusWindow : public QFrame {
Q_OBJECT
public:
explicit StatusWindow(QWidget *parent = 0);
struct StatusData {
QString time, storage, ram, load, temp, fan, ip, wifi;
QString vpn_status, vpn_ip, gps, telemetry;
QString dashcam_state, dashcam_frames;
float temp_c = 0;
};
protected:
void mousePressEvent(QMouseEvent *e) override;
signals:
void closeStatus();
private slots:
void kickRefresh();
void applyResults();
private:
QFutureWatcher<StatusData> watcher;
bool collecting = false;
QLabel *storage_label;
QLabel *ram_label;
QLabel *load_label;
QLabel *temp_label;
QLabel *fan_label;
QLabel *ip_label;
QLabel *wifi_label;
QLabel *vpn_label;
QLabel *gps_label;
QLabel *time_label;
QLabel *telemetry_label;
QLabel *dashcam_label;
QLabel *panda_label;
};
class MainWindow : public QWidget { class MainWindow : public QWidget {
Q_OBJECT Q_OBJECT
@@ -16,13 +63,24 @@ public:
private: private:
bool eventFilter(QObject *obj, QEvent *event) override; bool eventFilter(QObject *obj, QEvent *event) override;
void openSettings(int index = 0, const QString &param = ""); void openSettings(int index = 0, const QString &param = "");
void openStatus();
void closeSettings(); void closeSettings();
QString dumpWidgetTree(QWidget *w, int depth = 0);
QStackedLayout *main_layout; QStackedLayout *main_layout;
HomeWindow *homeWindow; HomeWindow *homeWindow;
SettingsWindow *settingsWindow; SettingsWindow *settingsWindow;
StatusWindow *statusWindow;
OnboardingWindow *onboardingWindow; OnboardingWindow *onboardingWindow;
// CLEARPILOT: UI introspection RPC
void *zmq_ctx = nullptr;
void *zmq_sock = nullptr;
QSocketNotifier *rpc_notifier = nullptr;
// FrogPilot variables // FrogPilot variables
Params params; Params params;
private slots:
void handleRpcRequest();
}; };
+43 -1
View File
@@ -93,6 +93,27 @@ class Soundd:
self.spl_filter_weighted = FirstOrderFilter(0, 2.5, FILTER_DT, initialized=False) self.spl_filter_weighted = FirstOrderFilter(0, 2.5, FILTER_DT, initialized=False)
# ClearPilot ding (plays independently of alerts)
self.ding_sound = None
self.ding_frame = 0
self.ding_playing = False
self.ding_check_counter = 0
self._load_ding()
def _load_ding(self):
ding_path = BASEDIR + "/selfdrive/clearpilot/sounds/ding.wav"
try:
wavefile = wave.open(ding_path, 'r')
assert wavefile.getnchannels() == 1
assert wavefile.getsampwidth() == 2
assert wavefile.getframerate() == SAMPLE_RATE
length = wavefile.getnframes()
self.ding_sound = np.frombuffer(wavefile.readframes(length), dtype=np.int16).astype(np.float32) / (2**16/2)
cloudlog.info(f"ClearPilot ding loaded: {length} frames")
except Exception as e:
cloudlog.error(f"Failed to load ding sound: {e}")
self.ding_sound = None
def load_sounds(self): def load_sounds(self):
self.loaded_sounds: dict[int, np.ndarray] = {} self.loaded_sounds: dict[int, np.ndarray] = {}
@@ -137,7 +158,20 @@ class Soundd:
written_frames += frames_to_write written_frames += frames_to_write
self.current_sound_frame += frames_to_write self.current_sound_frame += frames_to_write
return ret * self.current_volume ret = ret * self.current_volume
# Mix in ClearPilot ding (independent of alerts, always max volume)
if self.ding_playing and self.ding_sound is not None:
ding_remaining = len(self.ding_sound) - self.ding_frame
if ding_remaining > 0:
frames_to_write = min(ding_remaining, frames)
ret[:frames_to_write] += self.ding_sound[self.ding_frame:self.ding_frame + frames_to_write] * MAX_VOLUME
self.ding_frame += frames_to_write
else:
self.ding_playing = False
self.ding_frame = 0
return ret
def callback(self, data_out: np.ndarray, frames: int, time, status) -> None: def callback(self, data_out: np.ndarray, frames: int, time, status) -> None:
if status: if status:
@@ -197,6 +231,14 @@ class Soundd:
self.get_audible_alert(sm) self.get_audible_alert(sm)
# ClearPilot: check for ding trigger at ~2Hz
self.ding_check_counter += 1
if self.ding_check_counter % 10 == 0 and self.ding_sound is not None:
if self.params_memory.get("ClearpilotPlayDing") == b"1":
self.params_memory.put("ClearpilotPlayDing", "0")
self.ding_playing = True
self.ding_frame = 0
rk.keep_time() rk.keep_time()
assert stream.active assert stream.active
+5
View File
@@ -1,5 +1,10 @@
#!/bin/sh #!/bin/sh
# CLEARPILOT: prefer freshly built _spinner over prebuilt qt/spinner
if [ -f ./_spinner ]; then
exec ./_spinner "$1"
fi
if [ -f /TICI ] && [ ! -f qt/spinner ]; then if [ -f /TICI ] && [ ! -f qt/spinner ]; then
cp qt/spinner_larch64 qt/spinner cp qt/spinner_larch64 qt/spinner
fi fi
+3 -3
View File
@@ -818,15 +818,15 @@
<name>OffroadHome</name> <name>OffroadHome</name>
<message> <message>
<source>UPDATE</source> <source>UPDATE</source>
<translation>تحديث</translation> <translation type="vanished">تحديث</translation>
</message> </message>
<message> <message>
<source> ALERTS</source> <source> ALERTS</source>
<translation> التنبهات</translation> <translation type="vanished"> التنبهات</translation>
</message> </message>
<message> <message>
<source> ALERT</source> <source> ALERT</source>
<translation> تنبيه</translation> <translation type="vanished"> تنبيه</translation>
</message> </message>
</context> </context>
<context> <context>
+3 -3
View File
@@ -771,15 +771,15 @@
<name>OffroadHome</name> <name>OffroadHome</name>
<message> <message>
<source>UPDATE</source> <source>UPDATE</source>
<translation>Aktualisieren</translation> <translation type="vanished">Aktualisieren</translation>
</message> </message>
<message> <message>
<source> ALERTS</source> <source> ALERTS</source>
<translation> HINWEISE</translation> <translation type="vanished"> HINWEISE</translation>
</message> </message>
<message> <message>
<source> ALERT</source> <source> ALERT</source>
<translation> HINWEIS</translation> <translation type="vanished"> HINWEIS</translation>
</message> </message>
</context> </context>
<context> <context>
+3 -3
View File
@@ -814,15 +814,15 @@
<name>OffroadHome</name> <name>OffroadHome</name>
<message> <message>
<source>UPDATE</source> <source>UPDATE</source>
<translation>MISE À JOUR</translation> <translation type="vanished">MISE À JOUR</translation>
</message> </message>
<message> <message>
<source> ALERTS</source> <source> ALERTS</source>
<translation> ALERTES</translation> <translation type="vanished"> ALERTES</translation>
</message> </message>
<message> <message>
<source> ALERT</source> <source> ALERT</source>
<translation> ALERTE</translation> <translation type="vanished"> ALERTE</translation>
</message> </message>
</context> </context>
<context> <context>
+3 -3
View File
@@ -770,15 +770,15 @@
<name>OffroadHome</name> <name>OffroadHome</name>
<message> <message>
<source>UPDATE</source> <source>UPDATE</source>
<translation></translation> <translation type="vanished"></translation>
</message> </message>
<message> <message>
<source> ALERTS</source> <source> ALERTS</source>
<translation> </translation> <translation type="vanished"> </translation>
</message> </message>
<message> <message>
<source> ALERT</source> <source> ALERT</source>
<translation> </translation> <translation type="vanished"> </translation>
</message> </message>
</context> </context>
<context> <context>
+3 -3
View File
@@ -813,15 +813,15 @@
<name>OffroadHome</name> <name>OffroadHome</name>
<message> <message>
<source>UPDATE</source> <source>UPDATE</source>
<translation></translation> <translation type="vanished"></translation>
</message> </message>
<message> <message>
<source> ALERTS</source> <source> ALERTS</source>
<translation> </translation> <translation type="vanished"> </translation>
</message> </message>
<message> <message>
<source> ALERT</source> <source> ALERT</source>
<translation> </translation> <translation type="vanished"> </translation>
</message> </message>
</context> </context>
<context> <context>
+3 -3
View File
@@ -814,15 +814,15 @@
<name>OffroadHome</name> <name>OffroadHome</name>
<message> <message>
<source>UPDATE</source> <source>UPDATE</source>
<translation>ATUALIZAÇÃO</translation> <translation type="vanished">ATUALIZAÇÃO</translation>
</message> </message>
<message> <message>
<source> ALERTS</source> <source> ALERTS</source>
<translation> ALERTAS</translation> <translation type="vanished"> ALERTAS</translation>
</message> </message>
<message> <message>
<source> ALERT</source> <source> ALERT</source>
<translation> ALERTA</translation> <translation type="vanished"> ALERTA</translation>
</message> </message>
</context> </context>
<context> <context>
+3 -3
View File
@@ -813,15 +813,15 @@
<name>OffroadHome</name> <name>OffroadHome</name>
<message> <message>
<source>UPDATE</source> <source>UPDATE</source>
<translation></translation> <translation type="vanished"></translation>
</message> </message>
<message> <message>
<source> ALERTS</source> <source> ALERTS</source>
<translation> </translation> <translation type="vanished"> </translation>
</message> </message>
<message> <message>
<source> ALERT</source> <source> ALERT</source>
<translation> </translation> <translation type="vanished"> </translation>
</message> </message>
</context> </context>
<context> <context>
+3 -3
View File
@@ -770,15 +770,15 @@
<name>OffroadHome</name> <name>OffroadHome</name>
<message> <message>
<source>UPDATE</source> <source>UPDATE</source>
<translation>GÜNCELLE</translation> <translation type="vanished">GÜNCELLE</translation>
</message> </message>
<message> <message>
<source> ALERTS</source> <source> ALERTS</source>
<translation> UYARILAR</translation> <translation type="vanished"> UYARILAR</translation>
</message> </message>
<message> <message>
<source> ALERT</source> <source> ALERT</source>
<translation> UYARI</translation> <translation type="vanished"> UYARI</translation>
</message> </message>
</context> </context>
<context> <context>
+3 -3
View File
@@ -813,15 +813,15 @@
<name>OffroadHome</name> <name>OffroadHome</name>
<message> <message>
<source>UPDATE</source> <source>UPDATE</source>
<translation></translation> <translation type="vanished"></translation>
</message> </message>
<message> <message>
<source> ALERTS</source> <source> ALERTS</source>
<translation> </translation> <translation type="vanished"> </translation>
</message> </message>
<message> <message>
<source> ALERT</source> <source> ALERT</source>
<translation> </translation> <translation type="vanished"> </translation>
</message> </message>
</context> </context>
<context> <context>
+3 -3
View File
@@ -813,15 +813,15 @@
<name>OffroadHome</name> <name>OffroadHome</name>
<message> <message>
<source>UPDATE</source> <source>UPDATE</source>
<translation></translation> <translation type="vanished"></translation>
</message> </message>
<message> <message>
<source> ALERTS</source> <source> ALERTS</source>
<translation> </translation> <translation type="vanished"> </translation>
</message> </message>
<message> <message>
<source> ALERT</source> <source> ALERT</source>
<translation> </translation> <translation type="vanished"> </translation>
</message> </message>
</context> </context>
<context> <context>
+17 -4
View File
@@ -93,6 +93,9 @@ void update_model(UIState *s,
if (plan_position.getX().size() < model.getPosition().getX().size()) { if (plan_position.getX().size() < model.getPosition().getX().size()) {
plan_position = model.getPosition(); plan_position = model.getPosition();
} }
// CLEARPILOT: guard against empty model data (bench mode, no modeld running)
if (plan_position.getX().size() == 0) return;
float max_distance = scene.unlimited_road_ui_length ? *(plan_position.getX().end() - 1) : float max_distance = scene.unlimited_road_ui_length ? *(plan_position.getX().end() - 1) :
std::clamp(*(plan_position.getX().end() - 1), std::clamp(*(plan_position.getX().end() - 1),
MIN_DRAW_DISTANCE, MAX_DRAW_DISTANCE); MIN_DRAW_DISTANCE, MAX_DRAW_DISTANCE);
@@ -115,8 +118,10 @@ void update_model(UIState *s,
} }
// update path // update path
// CLEARPILOT: read from frogpilotCarControl cereal message (was paramsMemory)
bool no_lat_lane_change = (*s->sm)["frogpilotCarControl"].getFrogpilotCarControl().getNoLatLaneChange();
float path; float path;
if (paramsMemory.getBool("no_lat_lane_change")) { if (no_lat_lane_change) {
path = (float)LANE_CHANGE_NO_LAT_PATH_WIDTH / 20; // Release: better calc for EU users path = (float)LANE_CHANGE_NO_LAT_PATH_WIDTH / 20; // Release: better calc for EU users
} else { } else {
path = (float)CENTER_LANE_WIDTH / 20; // Release: better calc for EU users path = (float)CENTER_LANE_WIDTH / 20; // Release: better calc for EU users
@@ -391,6 +396,7 @@ void ui_update_frogpilot_params(UIState *s) {
scene.screen_brightness = screen_management ? params.getInt("ScreenBrightness") : 101; scene.screen_brightness = screen_management ? params.getInt("ScreenBrightness") : 101;
scene.screen_brightness_onroad = screen_management ? params.getInt("ScreenBrightnessOnroad") : 101; scene.screen_brightness_onroad = screen_management ? params.getInt("ScreenBrightnessOnroad") : 101;
scene.screen_recorder = screen_management && params.getBool("ScreenRecorder"); scene.screen_recorder = screen_management && params.getBool("ScreenRecorder");
scene.screen_recorder_debug = params.getBool("ScreenRecorderDebug");
scene.screen_timeout = screen_management ? params.getInt("ScreenTimeout") : 120; scene.screen_timeout = screen_management ? params.getInt("ScreenTimeout") : 120;
scene.screen_timeout_onroad = screen_management ? params.getInt("ScreenTimeoutOnroad") : 10; scene.screen_timeout_onroad = screen_management ? params.getInt("ScreenTimeoutOnroad") : 10;
scene.standby_mode = screen_management && params.getBool("StandbyMode"); scene.standby_mode = screen_management && params.getBool("StandbyMode");
@@ -435,9 +441,10 @@ void UIState::updateStatus() {
UIState::UIState(QObject *parent) : QObject(parent) { UIState::UIState(QObject *parent) : QObject(parent) {
sm = std::make_unique<SubMaster, const std::initializer_list<const char *>>({ sm = std::make_unique<SubMaster, const std::initializer_list<const char *>>({
"modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState",
"pandaStates", "carParams", "driverMonitoringState", "carState", "liveLocationKalman", "driverStateV2", "pandaStates", "peripheralState", "carParams", "driverMonitoringState", "carState", "liveLocationKalman", "driverStateV2",
"wideRoadCameraState", "managerState", "uiPlan", "liveTorqueParameters", "wideRoadCameraState", "managerState", "uiPlan", "liveTorqueParameters",
"frogpilotCarControl", "frogpilotDeviceState", "frogpilotPlan", "frogpilotCarControl", "frogpilotDeviceState", "frogpilotPlan",
"gpsLocation",
}); });
Params params; Params params;
@@ -551,7 +558,10 @@ void Device::updateWakefulness(const UIState &s) {
} }
if (ignition_state_changed) { if (ignition_state_changed) {
if (ignition_on && s.scene.screen_brightness_onroad == 0 && !s.scene.standby_mode) { if (!ignition_on) {
// CLEARPILOT: ignition on→off blanks the screen immediately (tap still wakes).
resetInteractiveTimeout(0, 0);
} else if (s.scene.screen_brightness_onroad == 0 && !s.scene.standby_mode) {
resetInteractiveTimeout(0, 0); resetInteractiveTimeout(0, 0);
} else { } else {
resetInteractiveTimeout(s.scene.screen_timeout, s.scene.screen_timeout_onroad); resetInteractiveTimeout(s.scene.screen_timeout, s.scene.screen_timeout_onroad);
@@ -560,7 +570,10 @@ void Device::updateWakefulness(const UIState &s) {
emit interactiveTimeout(); emit interactiveTimeout();
} }
if (s.scene.screen_brightness_onroad != 0) { // CLEARPILOT: ScreenDisplayMode 3 = screen off — override awake state
if (paramsMemory.getInt("ScreenDisplayMode") == 3) {
setAwake(false);
} else if (s.scene.screen_brightness_onroad != 0) {
setAwake(s.scene.ignition || interactive_timeout > 0); setAwake(s.scene.ignition || interactive_timeout > 0);
} else { } else {
setAwake(interactive_timeout > 0); setAwake(interactive_timeout > 0);
+1
View File
@@ -231,6 +231,7 @@ typedef struct UIScene {
bool road_name_ui; bool road_name_ui;
bool rotating_wheel; bool rotating_wheel;
bool screen_recorder; bool screen_recorder;
bool screen_recorder_debug;
bool show_aol_status_bar; bool show_aol_status_bar;
bool show_cem_status_bar; bool show_cem_status_bar;
bool show_jerk; bool show_jerk;
+13 -3
View File
@@ -7,17 +7,27 @@
#include "system/hardware/hw.h" #include "system/hardware/hw.h"
int main(int argc, char *argv[]) { int main(int argc, char *argv[]) {
fprintf(stderr, "camerad: starting\n");
if (Hardware::PC()) { if (Hardware::PC()) {
printf("exiting, camerad is not meant to run on PC\n"); fprintf(stderr, "camerad: exiting, not meant to run on PC\n");
return 0; return 0;
} }
int ret; int ret;
fprintf(stderr, "camerad: setting realtime priority 53\n");
ret = util::set_realtime_priority(53); ret = util::set_realtime_priority(53);
fprintf(stderr, "camerad: set_realtime_priority ret=%d\n", ret);
assert(ret == 0); assert(ret == 0);
ret = util::set_core_affinity({6});
assert(ret == 0 || Params().getBool("IsOffroad")); // failure ok while offroad due to offlining cores
fprintf(stderr, "camerad: setting core affinity to cpu6\n");
ret = util::set_core_affinity({6});
bool isOffroad = Params().getBool("IsOffroad");
fprintf(stderr, "camerad: set_core_affinity ret=%d, IsOffroad=%d\n", ret, isOffroad);
assert(ret == 0 || isOffroad); // failure ok while offroad due to offlining cores
fprintf(stderr, "camerad: starting camerad_thread\n");
camerad_thread(); camerad_thread();
fprintf(stderr, "camerad: camerad_thread returned\n");
return 0; return 0;
} }
View File
+258
View File
@@ -0,0 +1,258 @@
#!/usr/bin/env python3
"""
ClearPilot GPS daemon reads GPS from Quectel EC25 modem via AT commands
and publishes gpsLocation messages for locationd/timed.
Replaces qcomgpsd which uses the diag interface (broken on this device).
"""
import math
import os
import subprocess
import time
import datetime
from cereal import log
import cereal.messaging as messaging
from openpilot.common.gpio import gpio_init, gpio_set
from openpilot.common.params import Params
from openpilot.common.swaglog import cloudlog
from openpilot.common.time import system_time_valid
from openpilot.system.hardware.tici.pins import GPIO
def _sunrise_sunset_min(lat: float, lon: float, utc_dt: datetime.datetime):
"""Compute (sunrise_min, sunset_min) in UTC minutes since midnight of utc_dt's day.
Values can be negative or >1440 for western/eastern longitudes. Returns
(None, None) for polar night, ('always', 'always') for midnight sun."""
n = utc_dt.timetuple().tm_yday
gamma = 2 * math.pi / 365 * (n - 1 + (utc_dt.hour - 12) / 24)
eqtime = 229.18 * (0.000075 + 0.001868 * math.cos(gamma)
- 0.032077 * math.sin(gamma)
- 0.014615 * math.cos(2 * gamma)
- 0.040849 * math.sin(2 * gamma))
decl = (0.006918 - 0.399912 * math.cos(gamma)
+ 0.070257 * math.sin(gamma)
- 0.006758 * math.cos(2 * gamma)
+ 0.000907 * math.sin(2 * gamma)
- 0.002697 * math.cos(3 * gamma)
+ 0.00148 * math.sin(3 * gamma))
lat_rad = math.radians(lat)
zenith = math.radians(90.833)
cos_ha = (math.cos(zenith) / (math.cos(lat_rad) * math.cos(decl))
- math.tan(lat_rad) * math.tan(decl))
if cos_ha < -1:
return ('always', 'always') # midnight sun
if cos_ha > 1:
return (None, None) # polar night
ha = math.degrees(math.acos(cos_ha))
sunrise_min = 720 - 4 * (lon + ha) - eqtime
sunset_min = 720 - 4 * (lon - ha) - eqtime
return (sunrise_min, sunset_min)
def is_daylight(lat: float, lon: float, utc_dt: datetime.datetime) -> bool:
"""Return True if the sun is currently above the horizon at (lat, lon).
Handles west-of-Greenwich correctly: at UTC midnight it may still be
evening local time, and the relevant sunset is the PREVIOUS UTC day's
value (which is >1440 min if we re-ref to that day, i.e. it's past
midnight UTC). Symmetric case for east-of-Greenwich at the other end.
Strategy: compute sunrise/sunset for yesterday, today, and tomorrow (each
relative to its own UTC midnight), shift them all onto today's clock
(yesterday = -1440, tomorrow = +1440), and check if now_min falls inside
any of the three [sunrise, sunset] intervals.
"""
now_min = utc_dt.hour * 60 + utc_dt.minute + utc_dt.second / 60
for day_offset in (-1, 0, 1):
d = utc_dt + datetime.timedelta(days=day_offset)
sr, ss = _sunrise_sunset_min(lat, lon, d)
if sr == 'always':
return True
if sr is None:
continue # polar night this day
sr += day_offset * 1440
ss += day_offset * 1440
if sr <= now_min <= ss:
return True
return False
def at_cmd(cmd: str) -> str:
try:
result = subprocess.check_output(
f"mmcli -m any --timeout 10 --command='{cmd}'",
shell=True, encoding='utf8', stderr=subprocess.DEVNULL
).strip()
# mmcli wraps AT responses: response: '+QGPSLOC: ...'
# Strip the wrapper to get just the AT response
if result.startswith("response: '") and result.endswith("'"):
result = result[len("response: '"):-1]
return result
except subprocess.CalledProcessError:
return ""
def wait_for_modem():
cloudlog.warning("gpsd: waiting for modem")
while True:
ret = subprocess.call(
"mmcli -m any --timeout 10 --command='AT+QGPS?'",
stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL, shell=True
)
if ret == 0:
return
time.sleep(0.5)
def parse_qgpsloc(response: str):
"""Parse AT+QGPSLOC=2 response into a dict.
Format: +QGPSLOC: UTC,lat,lon,hdop,alt,fix,cog,spkm,spkn,date,nsat
"""
if "+QGPSLOC:" not in response:
return None
try:
data = response.split("+QGPSLOC:")[1].strip()
fields = data.split(",")
if len(fields) < 11:
return None
utc = fields[0] # HHMMSS.S
lat = float(fields[1])
lon = float(fields[2])
hdop = float(fields[3])
alt = float(fields[4])
fix = int(fields[5]) # 2=2D, 3=3D
cog = float(fields[6]) # course over ground
spkm = float(fields[7]) # speed km/h
spkn = float(fields[8]) # speed knots
date = fields[9] # DDMMYY
nsat = int(fields[10])
# Build unix timestamp from UTC + date
# utc: "HHMMSS.S", date: "DDMMYY"
hh, mm = int(utc[0:2]), int(utc[2:4])
ss = float(utc[4:])
dd, mo, yy = int(date[0:2]), int(date[2:4]), 2000 + int(date[4:6])
dt = datetime.datetime(yy, mo, dd, hh, mm, int(ss),
int((ss % 1) * 1e6), datetime.timezone.utc)
return {
"latitude": lat,
"longitude": lon,
"altitude": alt,
"speed": spkm / 3.6, # convert km/h to m/s
"bearing": cog,
"accuracy": hdop * 5, # rough conversion from HDOP to meters
"timestamp_ms": dt.timestamp() * 1e3,
"satellites": nsat,
"fix": fix,
}
except (ValueError, IndexError) as e:
cloudlog.error(f"gpsd: parse error: {e}")
return None
def main():
import sys
print("gpsd: starting", file=sys.stderr, flush=True)
# Kill system gpsd which may respawn and interfere with modem access
subprocess.run("pkill -f /usr/sbin/gpsd", shell=True,
stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL)
wait_for_modem()
print("gpsd: modem ready", file=sys.stderr, flush=True)
# Enable GPS antenna power
gpio_init(GPIO.GNSS_PWR_EN, True)
gpio_set(GPIO.GNSS_PWR_EN, True)
print("gpsd: GPIO power enabled", file=sys.stderr, flush=True)
# Don't restart GPS if already running (preserve existing fix)
resp = at_cmd("AT+QGPS?")
print(f"gpsd: QGPS status: {resp}", file=sys.stderr, flush=True)
if "QGPS: 1" not in resp:
at_cmd('AT+QGPSCFG="dpoenable",0')
at_cmd('AT+QGPSCFG="outport","none"')
at_cmd("AT+QGPS=1")
print("gpsd: GPS started fresh", file=sys.stderr, flush=True)
else:
print("gpsd: GPS already running, keeping fix", file=sys.stderr, flush=True)
pm = messaging.PubMaster(["gpsLocation"])
clock_set = system_time_valid()
params_memory = Params("/dev/shm/params")
last_daylight_check = 0.0
daylight_computed = False
prev_daylight = None # CLEARPILOT: gate IsDaylight write on change
print("gpsd: entering main loop", file=sys.stderr, flush=True)
while True:
resp = at_cmd("AT+QGPSLOC=2")
fix = parse_qgpsloc(resp)
if fix:
# Set system clock from GPS on first valid fix if clock is invalid
if not clock_set:
gps_dt = datetime.datetime.utcfromtimestamp(fix["timestamp_ms"] / 1000)
ret = subprocess.run(["date", "-s", gps_dt.strftime("%Y-%m-%d %H:%M:%S")],
env={**os.environ, "TZ": "UTC"},
capture_output=True)
if ret.returncode == 0:
clock_set = True
cloudlog.warning("gpsd: system clock set from GPS: %s", gps_dt)
print(f"gpsd: system clock set from GPS: {gps_dt}", file=sys.stderr, flush=True)
else:
cloudlog.error("gpsd: failed to set clock: %s", ret.stderr.decode().strip())
msg = messaging.new_message("gpsLocation", valid=True)
gps = msg.gpsLocation
gps.latitude = fix["latitude"]
gps.longitude = fix["longitude"]
gps.altitude = fix["altitude"]
gps.speed = fix["speed"]
gps.bearingDeg = fix["bearing"]
gps.horizontalAccuracy = fix["accuracy"]
gps.unixTimestampMillis = int(fix["timestamp_ms"])
gps.source = log.GpsLocationData.SensorSource.qcomdiag
gps.hasFix = fix["fix"] >= 2
gps.flags = 1
gps.vNED = [0.0, 0.0, 0.0]
gps.verticalAccuracy = fix["accuracy"]
gps.bearingAccuracyDeg = 10.0
gps.speedAccuracy = 1.0
pm.send("gpsLocation", msg)
# CLEARPILOT: daylight calculation for auto display mode switching
if clock_set:
now_mono = time.monotonic()
interval = 1.0 if not daylight_computed else 30.0
if (now_mono - last_daylight_check) >= interval:
last_daylight_check = now_mono
utc_now = datetime.datetime.utcfromtimestamp(fix["timestamp_ms"] / 1000)
daylight = is_daylight(fix["latitude"], fix["longitude"], utc_now)
# CLEARPILOT: gate on change — daylight flips twice a day, don't rewrite every 30s
if daylight != prev_daylight:
params_memory.put_bool("IsDaylight", daylight)
prev_daylight = daylight
if not daylight_computed:
daylight_computed = True
cloudlog.warning("gpsd: initial daylight calc: %s", "day" if daylight else "night")
print(f"gpsd: initial daylight calc: {'day' if daylight else 'night'}", file=sys.stderr, flush=True)
# Auto-transition: only touch states 0 and 1
current_mode = params_memory.get_int("ScreenDisplayMode")
if current_mode == 0 and not daylight:
params_memory.put_int("ScreenDisplayMode", 1)
cloudlog.warning("gpsd: auto-switch to nightrider (sunset)")
elif current_mode == 1 and daylight:
params_memory.put_int("ScreenDisplayMode", 0)
cloudlog.warning("gpsd: auto-switch to normal (sunrise)")
time.sleep(0.5) # 2 Hz polling
if __name__ == "__main__":
main()
-4
View File
@@ -50,7 +50,6 @@ public:
} }
static void reboot() { std::system("sudo reboot"); } static void reboot() { std::system("sudo reboot"); }
static void soft_reboot() { static void soft_reboot() {
const std::vector<std::string> commands = { const std::vector<std::string> commands = {
"rm -f /tmp/safe_staging_overlay.lock", "rm -f /tmp/safe_staging_overlay.lock",
@@ -68,9 +67,7 @@ public:
} }
} }
} }
static void poweroff() { std::system("sudo poweroff"); } static void poweroff() { std::system("sudo poweroff"); }
static void set_brightness(int percent) { static void set_brightness(int percent) {
std::string max = util::read_file("/sys/class/backlight/panel0-backlight/max_brightness"); std::string max = util::read_file("/sys/class/backlight/panel0-backlight/max_brightness");
@@ -80,7 +77,6 @@ public:
brightness_control.close(); brightness_control.close();
} }
} }
static void set_display_power(bool on) { static void set_display_power(bool on) {
std::ofstream bl_power_control("/sys/class/backlight/panel0-backlight/bl_power"); std::ofstream bl_power_control("/sys/class/backlight/panel0-backlight/bl_power");
if (bl_power_control.is_open()) { if (bl_power_control.is_open()) {
+98 -1
View File
@@ -8,11 +8,15 @@ from openpilot.system.loggerd.config import get_available_bytes, get_available_p
from openpilot.system.loggerd.uploader import listdir_by_creation from openpilot.system.loggerd.uploader import listdir_by_creation
from openpilot.system.loggerd.xattr_cache import getxattr from openpilot.system.loggerd.xattr_cache import getxattr
MIN_BYTES = 5 * 1024 * 1024 * 1024 # CLEARPILOT: increased from 5 GB to 9 GB to reserve space for screen recordings
MIN_BYTES = 9 * 1024 * 1024 * 1024
MIN_PERCENT = 10 MIN_PERCENT = 10
DELETE_LAST = ['boot', 'crash'] DELETE_LAST = ['boot', 'crash']
# CLEARPILOT: screen recorder video directory
VIDEOS_DIR = '/data/media/0/videos'
PRESERVE_ATTR_NAME = 'user.preserve' PRESERVE_ATTR_NAME = 'user.preserve'
PRESERVE_ATTR_VALUE = b'1' PRESERVE_ATTR_VALUE = b'1'
PRESERVE_COUNT = 5 PRESERVE_COUNT = 5
@@ -44,12 +48,103 @@ def get_preserved_segments(dirs_by_creation: list[str]) -> list[str]:
return preserved return preserved
def delete_oldest_video():
"""CLEARPILOT: delete oldest dashcam footage when disk space is low.
Trip directories are /data/media/0/videos/YYYYMMDD-HHMMSS/ containing .mp4 segments.
Deletes entire oldest trip directory first. If only one trip remains (active),
deletes individual segments oldest-first within it. Also cleans up legacy flat .mp4 files."""
try:
if not os.path.isdir(VIDEOS_DIR):
return False
# Collect legacy flat mp4 files and trip directories
legacy_files = []
trip_dirs = []
for entry in os.listdir(VIDEOS_DIR):
path = os.path.join(VIDEOS_DIR, entry)
if os.path.isfile(path) and entry.endswith('.mp4'):
legacy_files.append(entry)
elif os.path.isdir(path):
trip_dirs.append(entry)
# Delete legacy flat files first (oldest by name)
if legacy_files:
legacy_files.sort()
delete_path = os.path.join(VIDEOS_DIR, legacy_files[0])
cloudlog.info(f"deleting legacy video {delete_path}")
os.remove(delete_path)
return True
if not trip_dirs:
return False
trip_dirs.sort() # sorted by timestamp name = chronological order
# If more than one trip, delete the oldest entire trip directory
if len(trip_dirs) > 1:
delete_path = os.path.join(VIDEOS_DIR, trip_dirs[0])
cloudlog.info(f"deleting trip {delete_path}")
shutil.rmtree(delete_path)
return True
# Only one trip left (likely active) — delete oldest segment within it
trip_path = os.path.join(VIDEOS_DIR, trip_dirs[0])
segments = sorted(f for f in os.listdir(trip_path) if f.endswith('.mp4'))
if not segments:
return False
delete_path = os.path.join(trip_path, segments[0])
cloudlog.info(f"deleting segment {delete_path}")
os.remove(delete_path)
return True
except OSError:
cloudlog.exception(f"issue deleting video from {VIDEOS_DIR}")
return False
# CLEARPILOT: max total size for /data/log2 session logs
LOG2_MAX_BYTES = 4 * 1024 * 1024 * 1024
def cleanup_log2():
"""Delete oldest session log directories until /data/log2 is under LOG2_MAX_BYTES."""
log_base = "/data/log2"
if not os.path.isdir(log_base):
return
# Get all session dirs sorted oldest first (by name = timestamp)
dirs = []
for entry in sorted(os.listdir(log_base)):
if entry == "current":
continue
path = os.path.join(log_base, entry)
if os.path.isdir(path) and not os.path.islink(path):
size = sum(f.stat().st_size for f in os.scandir(path) if f.is_file())
dirs.append((entry, path, size))
total = sum(s for _, _, s in dirs)
# Also count current session
current = os.path.join(log_base, "current")
if os.path.isdir(current):
total += sum(f.stat().st_size for f in os.scandir(current) if f.is_file())
# Delete oldest until under quota
while total > LOG2_MAX_BYTES and dirs:
entry, path, size = dirs.pop(0)
try:
cloudlog.info(f"deleting log session {path} ({size // 1024 // 1024} MB)")
shutil.rmtree(path)
total -= size
except OSError:
cloudlog.exception(f"issue deleting log {path}")
def deleter_thread(exit_event): def deleter_thread(exit_event):
while not exit_event.is_set(): while not exit_event.is_set():
out_of_bytes = get_available_bytes(default=MIN_BYTES + 1) < MIN_BYTES out_of_bytes = get_available_bytes(default=MIN_BYTES + 1) < MIN_BYTES
out_of_percent = get_available_percent(default=MIN_PERCENT + 1) < MIN_PERCENT out_of_percent = get_available_percent(default=MIN_PERCENT + 1) < MIN_PERCENT
if out_of_percent or out_of_bytes: if out_of_percent or out_of_bytes:
# CLEARPILOT: try deleting oldest video first, then fall back to log segments
if delete_oldest_video():
exit_event.wait(.1)
continue
dirs = listdir_by_creation(Paths.log_root()) dirs = listdir_by_creation(Paths.log_root())
# skip deleting most recent N preserved segments (and their prior segment) # skip deleting most recent N preserved segments (and their prior segment)
@@ -73,6 +168,8 @@ def deleter_thread(exit_event):
cloudlog.exception(f"issue deleting {delete_path}") cloudlog.exception(f"issue deleting {delete_path}")
exit_event.wait(.1) exit_event.wait(.1)
else: else:
# CLEARPILOT: enforce log2 size quota even when disk space is fine
cleanup_log2()
exit_event.wait(30) exit_event.wait(30)
-1
View File
@@ -1 +0,0 @@
libqpOASES_e.so.3.1
BIN
View File
Binary file not shown.
-1
View File
@@ -1 +0,0 @@
libqpOASES_e.so.3.1
Binary file not shown.
-1
View File
@@ -1 +0,0 @@
../include
+32
View File
@@ -0,0 +1,32 @@
/*
* Copyright 2011 The LibYuv Project Authors. All rights reserved.
*
* Use of this source code is governed by a BSD-style license
* that can be found in the LICENSE file in the root of the source
* tree. An additional intellectual property rights grant can be found
* in the file PATENTS. All contributing project authors may
* be found in the AUTHORS file in the root of the source tree.
*/
#ifndef INCLUDE_LIBYUV_H_
#define INCLUDE_LIBYUV_H_
#include "libyuv/basic_types.h"
#include "libyuv/compare.h"
#include "libyuv/convert.h"
#include "libyuv/convert_argb.h"
#include "libyuv/convert_from.h"
#include "libyuv/convert_from_argb.h"
#include "libyuv/cpu_id.h"
#include "libyuv/mjpeg_decoder.h"
#include "libyuv/planar_functions.h"
#include "libyuv/rotate.h"
#include "libyuv/rotate_argb.h"
#include "libyuv/row.h"
#include "libyuv/scale.h"
#include "libyuv/scale_argb.h"
#include "libyuv/scale_row.h"
#include "libyuv/version.h"
#include "libyuv/video_common.h"
#endif // INCLUDE_LIBYUV_H_
+118
View File
@@ -0,0 +1,118 @@
/*
* Copyright 2011 The LibYuv Project Authors. All rights reserved.
*
* Use of this source code is governed by a BSD-style license
* that can be found in the LICENSE file in the root of the source
* tree. An additional intellectual property rights grant can be found
* in the file PATENTS. All contributing project authors may
* be found in the AUTHORS file in the root of the source tree.
*/
#ifndef INCLUDE_LIBYUV_BASIC_TYPES_H_
#define INCLUDE_LIBYUV_BASIC_TYPES_H_
#include <stddef.h> // for NULL, size_t
#if defined(_MSC_VER) && (_MSC_VER < 1600)
#include <sys/types.h> // for uintptr_t on x86
#else
#include <stdint.h> // for uintptr_t
#endif
#ifndef GG_LONGLONG
#ifndef INT_TYPES_DEFINED
#define INT_TYPES_DEFINED
#ifdef COMPILER_MSVC
typedef unsigned __int64 uint64;
typedef __int64 int64;
#ifndef INT64_C
#define INT64_C(x) x ## I64
#endif
#ifndef UINT64_C
#define UINT64_C(x) x ## UI64
#endif
#define INT64_F "I64"
#else // COMPILER_MSVC
#if defined(__LP64__) && !defined(__OpenBSD__) && !defined(__APPLE__)
typedef unsigned long uint64; // NOLINT
typedef long int64; // NOLINT
#ifndef INT64_C
#define INT64_C(x) x ## L
#endif
#ifndef UINT64_C
#define UINT64_C(x) x ## UL
#endif
#define INT64_F "l"
#else // defined(__LP64__) && !defined(__OpenBSD__) && !defined(__APPLE__)
typedef unsigned long long uint64; // NOLINT
typedef long long int64; // NOLINT
#ifndef INT64_C
#define INT64_C(x) x ## LL
#endif
#ifndef UINT64_C
#define UINT64_C(x) x ## ULL
#endif
#define INT64_F "ll"
#endif // __LP64__
#endif // COMPILER_MSVC
typedef unsigned int uint32;
typedef int int32;
typedef unsigned short uint16; // NOLINT
typedef short int16; // NOLINT
typedef unsigned char uint8;
typedef signed char int8;
#endif // INT_TYPES_DEFINED
#endif // GG_LONGLONG
// Detect compiler is for x86 or x64.
#if defined(__x86_64__) || defined(_M_X64) || \
defined(__i386__) || defined(_M_IX86)
#define CPU_X86 1
#endif
// Detect compiler is for ARM.
#if defined(__arm__) || defined(_M_ARM)
#define CPU_ARM 1
#endif
#ifndef ALIGNP
#ifdef __cplusplus
#define ALIGNP(p, t) \
(reinterpret_cast<uint8*>(((reinterpret_cast<uintptr_t>(p) + \
((t) - 1)) & ~((t) - 1))))
#else
#define ALIGNP(p, t) \
((uint8*)((((uintptr_t)(p) + ((t) - 1)) & ~((t) - 1)))) /* NOLINT */
#endif
#endif
#if !defined(LIBYUV_API)
#if defined(_WIN32) || defined(__CYGWIN__)
#if defined(LIBYUV_BUILDING_SHARED_LIBRARY)
#define LIBYUV_API __declspec(dllexport)
#elif defined(LIBYUV_USING_SHARED_LIBRARY)
#define LIBYUV_API __declspec(dllimport)
#else
#define LIBYUV_API
#endif // LIBYUV_BUILDING_SHARED_LIBRARY
#elif defined(__GNUC__) && (__GNUC__ >= 4) && !defined(__APPLE__) && \
(defined(LIBYUV_BUILDING_SHARED_LIBRARY) || \
defined(LIBYUV_USING_SHARED_LIBRARY))
#define LIBYUV_API __attribute__ ((visibility ("default")))
#else
#define LIBYUV_API
#endif // __GNUC__
#endif // LIBYUV_API
#define LIBYUV_BOOL int
#define LIBYUV_FALSE 0
#define LIBYUV_TRUE 1
// Visual C x86 or GCC little endian.
#if defined(__x86_64__) || defined(_M_X64) || \
defined(__i386__) || defined(_M_IX86) || \
defined(__arm__) || defined(_M_ARM) || \
(defined(__BYTE_ORDER__) && __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__)
#define LIBYUV_LITTLE_ENDIAN
#endif
#endif // INCLUDE_LIBYUV_BASIC_TYPES_H_
+78
View File
@@ -0,0 +1,78 @@
/*
* Copyright 2011 The LibYuv Project Authors. All rights reserved.
*
* Use of this source code is governed by a BSD-style license
* that can be found in the LICENSE file in the root of the source
* tree. An additional intellectual property rights grant can be found
* in the file PATENTS. All contributing project authors may
* be found in the AUTHORS file in the root of the source tree.
*/
#ifndef INCLUDE_LIBYUV_COMPARE_H_
#define INCLUDE_LIBYUV_COMPARE_H_
#include "libyuv/basic_types.h"
#ifdef __cplusplus
namespace libyuv {
extern "C" {
#endif
// Compute a hash for specified memory. Seed of 5381 recommended.
LIBYUV_API
uint32 HashDjb2(const uint8* src, uint64 count, uint32 seed);
// Scan an opaque argb image and return fourcc based on alpha offset.
// Returns FOURCC_ARGB, FOURCC_BGRA, or 0 if unknown.
LIBYUV_API
uint32 ARGBDetect(const uint8* argb, int stride_argb, int width, int height);
// Sum Square Error - used to compute Mean Square Error or PSNR.
LIBYUV_API
uint64 ComputeSumSquareError(const uint8* src_a,
const uint8* src_b, int count);
LIBYUV_API
uint64 ComputeSumSquareErrorPlane(const uint8* src_a, int stride_a,
const uint8* src_b, int stride_b,
int width, int height);
static const int kMaxPsnr = 128;
LIBYUV_API
double SumSquareErrorToPsnr(uint64 sse, uint64 count);
LIBYUV_API
double CalcFramePsnr(const uint8* src_a, int stride_a,
const uint8* src_b, int stride_b,
int width, int height);
LIBYUV_API
double I420Psnr(const uint8* src_y_a, int stride_y_a,
const uint8* src_u_a, int stride_u_a,
const uint8* src_v_a, int stride_v_a,
const uint8* src_y_b, int stride_y_b,
const uint8* src_u_b, int stride_u_b,
const uint8* src_v_b, int stride_v_b,
int width, int height);
LIBYUV_API
double CalcFrameSsim(const uint8* src_a, int stride_a,
const uint8* src_b, int stride_b,
int width, int height);
LIBYUV_API
double I420Ssim(const uint8* src_y_a, int stride_y_a,
const uint8* src_u_a, int stride_u_a,
const uint8* src_v_a, int stride_v_a,
const uint8* src_y_b, int stride_y_b,
const uint8* src_u_b, int stride_u_b,
const uint8* src_v_b, int stride_v_b,
int width, int height);
#ifdef __cplusplus
} // extern "C"
} // namespace libyuv
#endif
#endif // INCLUDE_LIBYUV_COMPARE_H_
+84
View File
@@ -0,0 +1,84 @@
/*
* Copyright 2013 The LibYuv Project Authors. All rights reserved.
*
* Use of this source code is governed by a BSD-style license
* that can be found in the LICENSE file in the root of the source
* tree. An additional intellectual property rights grant can be found
* in the file PATENTS. All contributing project authors may
* be found in the AUTHORS file in the root of the source tree.
*/
#ifndef INCLUDE_LIBYUV_COMPARE_ROW_H_
#define INCLUDE_LIBYUV_COMPARE_ROW_H_
#include "libyuv/basic_types.h"
#ifdef __cplusplus
namespace libyuv {
extern "C" {
#endif
#if defined(__pnacl__) || defined(__CLR_VER) || \
(defined(__i386__) && !defined(__SSE2__))
#define LIBYUV_DISABLE_X86
#endif
// MemorySanitizer does not support assembly code yet. http://crbug.com/344505
#if defined(__has_feature)
#if __has_feature(memory_sanitizer)
#define LIBYUV_DISABLE_X86
#endif
#endif
// Visual C 2012 required for AVX2.
#if defined(_M_IX86) && !defined(__clang__) && \
defined(_MSC_VER) && _MSC_VER >= 1700
#define VISUALC_HAS_AVX2 1
#endif // VisualStudio >= 2012
// clang >= 3.4.0 required for AVX2.
#if defined(__clang__) && (defined(__x86_64__) || defined(__i386__))
#if (__clang_major__ > 3) || (__clang_major__ == 3 && (__clang_minor__ >= 4))
#define CLANG_HAS_AVX2 1
#endif // clang >= 3.4
#endif // __clang__
#if !defined(LIBYUV_DISABLE_X86) && \
defined(_M_IX86) && (defined(VISUALC_HAS_AVX2) || defined(CLANG_HAS_AVX2))
#define HAS_HASHDJB2_AVX2
#endif
// The following are available for Visual C and GCC:
#if !defined(LIBYUV_DISABLE_X86) && \
(defined(__x86_64__) || (defined(__i386__) || defined(_M_IX86)))
#define HAS_HASHDJB2_SSE41
#define HAS_SUMSQUAREERROR_SSE2
#endif
// The following are available for Visual C and clangcl 32 bit:
#if !defined(LIBYUV_DISABLE_X86) && defined(_M_IX86) && \
(defined(VISUALC_HAS_AVX2) || defined(CLANG_HAS_AVX2))
#define HAS_HASHDJB2_AVX2
#define HAS_SUMSQUAREERROR_AVX2
#endif
// The following are available for Neon:
#if !defined(LIBYUV_DISABLE_NEON) && \
(defined(__ARM_NEON__) || defined(LIBYUV_NEON) || defined(__aarch64__))
#define HAS_SUMSQUAREERROR_NEON
#endif
uint32 SumSquareError_C(const uint8* src_a, const uint8* src_b, int count);
uint32 SumSquareError_SSE2(const uint8* src_a, const uint8* src_b, int count);
uint32 SumSquareError_AVX2(const uint8* src_a, const uint8* src_b, int count);
uint32 SumSquareError_NEON(const uint8* src_a, const uint8* src_b, int count);
uint32 HashDjb2_C(const uint8* src, int count, uint32 seed);
uint32 HashDjb2_SSE41(const uint8* src, int count, uint32 seed);
uint32 HashDjb2_AVX2(const uint8* src, int count, uint32 seed);
#ifdef __cplusplus
} // extern "C"
} // namespace libyuv
#endif
#endif // INCLUDE_LIBYUV_COMPARE_ROW_H_
+259
View File
@@ -0,0 +1,259 @@
/*
* Copyright 2011 The LibYuv Project Authors. All rights reserved.
*
* Use of this source code is governed by a BSD-style license
* that can be found in the LICENSE file in the root of the source
* tree. An additional intellectual property rights grant can be found
* in the file PATENTS. All contributing project authors may
* be found in the AUTHORS file in the root of the source tree.
*/
#ifndef INCLUDE_LIBYUV_CONVERT_H_
#define INCLUDE_LIBYUV_CONVERT_H_
#include "libyuv/basic_types.h"
#include "libyuv/rotate.h" // For enum RotationMode.
// TODO(fbarchard): fix WebRTC source to include following libyuv headers:
#include "libyuv/convert_argb.h" // For WebRTC I420ToARGB. b/620
#include "libyuv/convert_from.h" // For WebRTC ConvertFromI420. b/620
#include "libyuv/planar_functions.h" // For WebRTC I420Rect, CopyPlane. b/618
#ifdef __cplusplus
namespace libyuv {
extern "C" {
#endif
// Convert I444 to I420.
LIBYUV_API
int I444ToI420(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// Convert I422 to I420.
LIBYUV_API
int I422ToI420(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// Convert I411 to I420.
LIBYUV_API
int I411ToI420(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// Copy I420 to I420.
#define I420ToI420 I420Copy
LIBYUV_API
int I420Copy(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// Convert I400 (grey) to I420.
LIBYUV_API
int I400ToI420(const uint8* src_y, int src_stride_y,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
#define J400ToJ420 I400ToI420
// Convert NV12 to I420.
LIBYUV_API
int NV12ToI420(const uint8* src_y, int src_stride_y,
const uint8* src_uv, int src_stride_uv,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// Convert NV21 to I420.
LIBYUV_API
int NV21ToI420(const uint8* src_y, int src_stride_y,
const uint8* src_vu, int src_stride_vu,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// Convert YUY2 to I420.
LIBYUV_API
int YUY2ToI420(const uint8* src_yuy2, int src_stride_yuy2,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// Convert UYVY to I420.
LIBYUV_API
int UYVYToI420(const uint8* src_uyvy, int src_stride_uyvy,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// Convert M420 to I420.
LIBYUV_API
int M420ToI420(const uint8* src_m420, int src_stride_m420,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// Convert Android420 to I420.
LIBYUV_API
int Android420ToI420(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
int pixel_stride_uv,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// ARGB little endian (bgra in memory) to I420.
LIBYUV_API
int ARGBToI420(const uint8* src_frame, int src_stride_frame,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// BGRA little endian (argb in memory) to I420.
LIBYUV_API
int BGRAToI420(const uint8* src_frame, int src_stride_frame,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// ABGR little endian (rgba in memory) to I420.
LIBYUV_API
int ABGRToI420(const uint8* src_frame, int src_stride_frame,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// RGBA little endian (abgr in memory) to I420.
LIBYUV_API
int RGBAToI420(const uint8* src_frame, int src_stride_frame,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// RGB little endian (bgr in memory) to I420.
LIBYUV_API
int RGB24ToI420(const uint8* src_frame, int src_stride_frame,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// RGB big endian (rgb in memory) to I420.
LIBYUV_API
int RAWToI420(const uint8* src_frame, int src_stride_frame,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// RGB16 (RGBP fourcc) little endian to I420.
LIBYUV_API
int RGB565ToI420(const uint8* src_frame, int src_stride_frame,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// RGB15 (RGBO fourcc) little endian to I420.
LIBYUV_API
int ARGB1555ToI420(const uint8* src_frame, int src_stride_frame,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
// RGB12 (R444 fourcc) little endian to I420.
LIBYUV_API
int ARGB4444ToI420(const uint8* src_frame, int src_stride_frame,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int width, int height);
#ifdef HAVE_JPEG
// src_width/height provided by capture.
// dst_width/height for clipping determine final size.
LIBYUV_API
int MJPGToI420(const uint8* sample, size_t sample_size,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int src_width, int src_height,
int dst_width, int dst_height);
// Query size of MJPG in pixels.
LIBYUV_API
int MJPGSize(const uint8* sample, size_t sample_size,
int* width, int* height);
#endif
// Convert camera sample to I420 with cropping, rotation and vertical flip.
// "src_size" is needed to parse MJPG.
// "dst_stride_y" number of bytes in a row of the dst_y plane.
// Normally this would be the same as dst_width, with recommended alignment
// to 16 bytes for better efficiency.
// If rotation of 90 or 270 is used, stride is affected. The caller should
// allocate the I420 buffer according to rotation.
// "dst_stride_u" number of bytes in a row of the dst_u plane.
// Normally this would be the same as (dst_width + 1) / 2, with
// recommended alignment to 16 bytes for better efficiency.
// If rotation of 90 or 270 is used, stride is affected.
// "crop_x" and "crop_y" are starting position for cropping.
// To center, crop_x = (src_width - dst_width) / 2
// crop_y = (src_height - dst_height) / 2
// "src_width" / "src_height" is size of src_frame in pixels.
// "src_height" can be negative indicating a vertically flipped image source.
// "crop_width" / "crop_height" is the size to crop the src to.
// Must be less than or equal to src_width/src_height
// Cropping parameters are pre-rotation.
// "rotation" can be 0, 90, 180 or 270.
// "format" is a fourcc. ie 'I420', 'YUY2'
// Returns 0 for successful; -1 for invalid parameter. Non-zero for failure.
LIBYUV_API
int ConvertToI420(const uint8* src_frame, size_t src_size,
uint8* dst_y, int dst_stride_y,
uint8* dst_u, int dst_stride_u,
uint8* dst_v, int dst_stride_v,
int crop_x, int crop_y,
int src_width, int src_height,
int crop_width, int crop_height,
enum RotationMode rotation,
uint32 format);
#ifdef __cplusplus
} // extern "C"
} // namespace libyuv
#endif
#endif // INCLUDE_LIBYUV_CONVERT_H_
+319
View File
@@ -0,0 +1,319 @@
/*
* Copyright 2012 The LibYuv Project Authors. All rights reserved.
*
* Use of this source code is governed by a BSD-style license
* that can be found in the LICENSE file in the root of the source
* tree. An additional intellectual property rights grant can be found
* in the file PATENTS. All contributing project authors may
* be found in the AUTHORS file in the root of the source tree.
*/
#ifndef INCLUDE_LIBYUV_CONVERT_ARGB_H_
#define INCLUDE_LIBYUV_CONVERT_ARGB_H_
#include "libyuv/basic_types.h"
#include "libyuv/rotate.h" // For enum RotationMode.
// TODO(fbarchard): This set of functions should exactly match convert.h
// TODO(fbarchard): Add tests. Create random content of right size and convert
// with C vs Opt and or to I420 and compare.
// TODO(fbarchard): Some of these functions lack parameter setting.
#ifdef __cplusplus
namespace libyuv {
extern "C" {
#endif
// Alias.
#define ARGBToARGB ARGBCopy
// Copy ARGB to ARGB.
LIBYUV_API
int ARGBCopy(const uint8* src_argb, int src_stride_argb,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert I420 to ARGB.
LIBYUV_API
int I420ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Duplicate prototype for function in convert_from.h for remoting.
LIBYUV_API
int I420ToABGR(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert I422 to ARGB.
LIBYUV_API
int I422ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert I444 to ARGB.
LIBYUV_API
int I444ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert J444 to ARGB.
LIBYUV_API
int J444ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert I444 to ABGR.
LIBYUV_API
int I444ToABGR(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_abgr, int dst_stride_abgr,
int width, int height);
// Convert I411 to ARGB.
LIBYUV_API
int I411ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert I420 with Alpha to preattenuated ARGB.
LIBYUV_API
int I420AlphaToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
const uint8* src_a, int src_stride_a,
uint8* dst_argb, int dst_stride_argb,
int width, int height, int attenuate);
// Convert I420 with Alpha to preattenuated ABGR.
LIBYUV_API
int I420AlphaToABGR(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
const uint8* src_a, int src_stride_a,
uint8* dst_abgr, int dst_stride_abgr,
int width, int height, int attenuate);
// Convert I400 (grey) to ARGB. Reverse of ARGBToI400.
LIBYUV_API
int I400ToARGB(const uint8* src_y, int src_stride_y,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert J400 (jpeg grey) to ARGB.
LIBYUV_API
int J400ToARGB(const uint8* src_y, int src_stride_y,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Alias.
#define YToARGB I400ToARGB
// Convert NV12 to ARGB.
LIBYUV_API
int NV12ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_uv, int src_stride_uv,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert NV21 to ARGB.
LIBYUV_API
int NV21ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_vu, int src_stride_vu,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert M420 to ARGB.
LIBYUV_API
int M420ToARGB(const uint8* src_m420, int src_stride_m420,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert YUY2 to ARGB.
LIBYUV_API
int YUY2ToARGB(const uint8* src_yuy2, int src_stride_yuy2,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert UYVY to ARGB.
LIBYUV_API
int UYVYToARGB(const uint8* src_uyvy, int src_stride_uyvy,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert J420 to ARGB.
LIBYUV_API
int J420ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert J422 to ARGB.
LIBYUV_API
int J422ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert J420 to ABGR.
LIBYUV_API
int J420ToABGR(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_abgr, int dst_stride_abgr,
int width, int height);
// Convert J422 to ABGR.
LIBYUV_API
int J422ToABGR(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_abgr, int dst_stride_abgr,
int width, int height);
// Convert H420 to ARGB.
LIBYUV_API
int H420ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert H422 to ARGB.
LIBYUV_API
int H422ToARGB(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Convert H420 to ABGR.
LIBYUV_API
int H420ToABGR(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_abgr, int dst_stride_abgr,
int width, int height);
// Convert H422 to ABGR.
LIBYUV_API
int H422ToABGR(const uint8* src_y, int src_stride_y,
const uint8* src_u, int src_stride_u,
const uint8* src_v, int src_stride_v,
uint8* dst_abgr, int dst_stride_abgr,
int width, int height);
// BGRA little endian (argb in memory) to ARGB.
LIBYUV_API
int BGRAToARGB(const uint8* src_frame, int src_stride_frame,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// ABGR little endian (rgba in memory) to ARGB.
LIBYUV_API
int ABGRToARGB(const uint8* src_frame, int src_stride_frame,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// RGBA little endian (abgr in memory) to ARGB.
LIBYUV_API
int RGBAToARGB(const uint8* src_frame, int src_stride_frame,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// Deprecated function name.
#define BG24ToARGB RGB24ToARGB
// RGB little endian (bgr in memory) to ARGB.
LIBYUV_API
int RGB24ToARGB(const uint8* src_frame, int src_stride_frame,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// RGB big endian (rgb in memory) to ARGB.
LIBYUV_API
int RAWToARGB(const uint8* src_frame, int src_stride_frame,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// RGB16 (RGBP fourcc) little endian to ARGB.
LIBYUV_API
int RGB565ToARGB(const uint8* src_frame, int src_stride_frame,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// RGB15 (RGBO fourcc) little endian to ARGB.
LIBYUV_API
int ARGB1555ToARGB(const uint8* src_frame, int src_stride_frame,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
// RGB12 (R444 fourcc) little endian to ARGB.
LIBYUV_API
int ARGB4444ToARGB(const uint8* src_frame, int src_stride_frame,
uint8* dst_argb, int dst_stride_argb,
int width, int height);
#ifdef HAVE_JPEG
// src_width/height provided by capture
// dst_width/height for clipping determine final size.
LIBYUV_API
int MJPGToARGB(const uint8* sample, size_t sample_size,
uint8* dst_argb, int dst_stride_argb,
int src_width, int src_height,
int dst_width, int dst_height);
#endif
// Convert camera sample to ARGB with cropping, rotation and vertical flip.
// "src_size" is needed to parse MJPG.
// "dst_stride_argb" number of bytes in a row of the dst_argb plane.
// Normally this would be the same as dst_width, with recommended alignment
// to 16 bytes for better efficiency.
// If rotation of 90 or 270 is used, stride is affected. The caller should
// allocate the I420 buffer according to rotation.
// "dst_stride_u" number of bytes in a row of the dst_u plane.
// Normally this would be the same as (dst_width + 1) / 2, with
// recommended alignment to 16 bytes for better efficiency.
// If rotation of 90 or 270 is used, stride is affected.
// "crop_x" and "crop_y" are starting position for cropping.
// To center, crop_x = (src_width - dst_width) / 2
// crop_y = (src_height - dst_height) / 2
// "src_width" / "src_height" is size of src_frame in pixels.
// "src_height" can be negative indicating a vertically flipped image source.
// "crop_width" / "crop_height" is the size to crop the src to.
// Must be less than or equal to src_width/src_height
// Cropping parameters are pre-rotation.
// "rotation" can be 0, 90, 180 or 270.
// "format" is a fourcc. ie 'I420', 'YUY2'
// Returns 0 for successful; -1 for invalid parameter. Non-zero for failure.
LIBYUV_API
int ConvertToARGB(const uint8* src_frame, size_t src_size,
uint8* dst_argb, int dst_stride_argb,
int crop_x, int crop_y,
int src_width, int src_height,
int crop_width, int crop_height,
enum RotationMode rotation,
uint32 format);
#ifdef __cplusplus
} // extern "C"
} // namespace libyuv
#endif
#endif // INCLUDE_LIBYUV_CONVERT_ARGB_H_

Some files were not shown because too many files have changed in this diff Show More