feat: Squash all min-features into full

This commit is contained in:
Rick Lan
2025-09-05 11:07:32 +08:00
parent 028b6e5664
commit 5e0f34905d
75 changed files with 4041 additions and 83 deletions

View File

@@ -10,10 +10,13 @@ $Cxx.namespace("cereal");
# DO rename the structs
# DON'T change the identifier (e.g. @0x81c2f05a394cf4af)
struct CustomReserved0 @0x81c2f05a394cf4af {
struct DpControlsState @0x81c2f05a394cf4af {
alkaActive @0 :Bool;
}
struct CustomReserved1 @0xaedffd8f31e7b55d {
struct ModelExt @0xaedffd8f31e7b55d {
leftEdgeDetected @0 :Bool;
rightEdgeDetected @1 :Bool;
}
struct CustomReserved2 @0xf35cc4560bbf6ec2 {

View File

@@ -2622,8 +2622,8 @@ struct Event {
# DO change the name of the field and struct
# DON'T change the ID (e.g. @107)
# DON'T change which struct it points to
customReserved0 @107 :Custom.CustomReserved0;
customReserved1 @108 :Custom.CustomReserved1;
dpControlsState @107 :Custom.DpControlsState;
modelExt @108 :Custom.ModelExt;
customReserved2 @109 :Custom.CustomReserved2;
customReserved3 @110 :Custom.CustomReserved3;
customReserved4 @111 :Custom.CustomReserved4;

View File

@@ -95,6 +95,8 @@ _services: dict[str, tuple] = {
"customReservedRawData0": (True, 0.),
"customReservedRawData1": (True, 0.),
"customReservedRawData2": (True, 0.),
"dpControlsState": (False, 100., 10),
"modelExt": (True, 20.),
}
SERVICE_LIST = {name: Service(*vals) for
idx, (name, vals) in enumerate(_services.items())}

View File

@@ -131,4 +131,26 @@ inline static std::unordered_map<std::string, ParamKeyAttributes> keys = {
{"Version", {PERSISTENT, STRING}},
{"dp_device_last_log", {CLEAR_ON_ONROAD_TRANSITION, STRING}},
{"dp_device_reset_conf", {CLEAR_ON_MANAGER_START, BOOL}},
{"dp_device_is_rhd", {PERSISTENT, BOOL, "0"}},
{"dp_device_monitoring_disabled", {PERSISTENT, BOOL, "0"}},
{"dp_device_beep", {PERSISTENT, BOOL, "0"}},
{"dp_lat_alka", {PERSISTENT, BOOL, "0"}},
{"dp_ui_display_mode", {PERSISTENT, BOOL, "0"}},
{"dp_device_model_selected", {PERSISTENT, STRING}},
{"dp_device_model_list", {PERSISTENT, STRING}},
{"dp_lat_lca_speed", {PERSISTENT, INT, "20"}},
{"dp_lat_lca_auto_sec", {PERSISTENT, FLOAT, "0.0"}},
{"dp_device_go_off_road", {CLEAR_ON_MANAGER_START, BOOL}},
{"dp_ui_hide_hud_speed_kph", {PERSISTENT, INT, "0"}},
{"dp_lon_ext_radar", {PERSISTENT, BOOL, "0"}},
{"dp_lat_road_edge_detection", {PERSISTENT, BOOL, "0"}},
{"dp_ui_rainbow", {PERSISTENT, BOOL, "0"}},
{"dp_lon_acm", {PERSISTENT, BOOL, "0"}},
{"dp_lon_acm_downhill", {PERSISTENT, BOOL, "0"}},
{"dp_lon_aem", {PERSISTENT, BOOL, "0"}},
{"dp_device_audible_alert_mode", {PERSISTENT, INT, "0"}},
{"dp_device_auto_shutdown_in", {PERSISTENT, INT, "-5"}},
{"dp_ui_radar_tracks", {PERSISTENT, BOOL, "0"}},
{"dp_dev_dashy", {PERSISTENT, INT, "0"}},
{"dp_dev_delay_loggerd", {PERSISTENT, INT, "0"}},
};

View File

View File

@@ -0,0 +1,15 @@
Copyright (c) 2025, Rick Lan
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, and/or sublicense,
for non-commercial purposes only, subject to the following conditions:
- The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
- Commercial use (e.g. use in a product, service, or activity intended to
generate revenue) is prohibited without explicit written permission from
the copyright holder.
THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.

View File

@@ -0,0 +1,46 @@
# Dashy Release Branch
This is the production-ready release branch of Dashy - Dragonpilot's All-in-one System Hub for You.
## 🚀 Quick Installation
```bash
git clone -b release https://github.com/efinilan/dashy
cd dashy
python3 backend/server.py
```
## 📁 What's Included
- `backend/` - Python server with all dependencies included
- `web/` - Pre-built web interface (minified and optimized)
## 🌐 Access
After starting the server, open Chrome browser and navigate to:
```
http://<device-ip>:5088
```
## 🔧 Requirements
- Network connection
- Port 5088 available
## 📄 License
Copyright (c) 2025, Rick Lan
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, and/or sublicense,
for non-commercial purposes only, subject to the following conditions:
- The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
- Commercial use (e.g. use in a product, service, or activity intended to
generate revenue) is prohibited without explicit written permission from
the copyright holder.
THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.

1
dragonpilot/dashy/backend/.gitignore vendored Normal file
View File

@@ -0,0 +1 @@
__pycache__

View File

@@ -0,0 +1,194 @@
"""
Copyright (c) 2025, Rick Lan
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, and/or sublicense,
for non-commercial purposes only, subject to the following conditions:
- The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
- Commercial use (e.g. use in a product, service, or activity intended to
generate revenue) is prohibited without explicit written permission from
the copyright holder.
THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
"""
#!/usr/bin/env python3
import argparse
# import asyncio
# import json
import os
import logging
from datetime import datetime
from urllib.parse import quote
# import socket
# import sys
from aiohttp import web
from openpilot.common.params import Params
from openpilot.system.hardware import PC
# --- File Browser Settings ---
DEFAULT_DIR = os.path.realpath(os.path.join(os.path.dirname(__file__), '..') if PC else '/data/media/0/realdata')
WEB_DIST_PATH = os.path.join(os.path.dirname(__file__), "..", "web", "dist")
def get_safe_path(requested_path):
"""Ensures the requested path is within DEFAULT_DIR, preventing arbitrary file access"""
combined_path = os.path.join(DEFAULT_DIR, requested_path.lstrip('/'))
safe_path = os.path.realpath(combined_path)
if os.path.commonpath((safe_path, DEFAULT_DIR)) == DEFAULT_DIR:
return safe_path
return None
async def list_files_api(request):
"""API endpoint to list files and folders"""
try:
path_param = request.query.get('path', '/')
safe_path = get_safe_path(path_param)
if not safe_path or not os.path.isdir(safe_path):
return web.json_response({'error': 'Invalid or Not Found Path'}, status=404)
items = []
for entry in os.listdir(safe_path):
full_path = os.path.join(safe_path, entry)
try:
stat = os.stat(full_path)
is_dir = os.path.isdir(full_path)
items.append({
'name': entry,
'is_dir': is_dir,
'mtime': datetime.fromtimestamp(stat.st_mtime).strftime('%Y-%m-%d %H:%M'),
'size': stat.st_size if not is_dir else 0
})
except FileNotFoundError:
continue
directories = sorted([item for item in items if item['is_dir']], key=lambda x: x['mtime'], reverse=True)
files = sorted([item for item in items if not item['is_dir']], key=lambda x: x['mtime'], reverse=True)
items = directories + files
relative_path = os.path.relpath(safe_path, DEFAULT_DIR)
if relative_path == '.':
relative_path = ''
return web.json_response({'path': relative_path, 'files': items})
except Exception as e:
return web.json_response({'error': str(e)}, status=500)
async def serve_player_api(request):
"""API endpoint to serve the HLS player page"""
file_path = request.query.get('file')
if not file_path:
return web.Response(text="File parameter is required.", status=400)
player_html_path = os.path.join(WEB_DIST_PATH, 'pages', 'player.html')
try:
with open(player_html_path, 'r') as f:
html_template = f.read()
except FileNotFoundError:
return web.Response(text="Player HTML not found.", status=500)
encoded_path = quote(file_path)
html = html_template.replace('{{FILE_PATH}}', encoded_path)
return web.Response(text=html, content_type='text/html')
async def serve_manifest_api(request):
"""API endpoint to dynamically generate m3u8 playlist"""
file_path = request.query.get('file').lstrip('/')
if not file_path:
return web.Response(text="File parameter is required.", status=400)
encoded_path = quote(file_path)
manifest = f"""#EXTM3U\n#EXT-X-VERSION:3\n#EXT-X-TARGETDURATION:60\n#EXT-X-PLAYLIST-TYPE:VOD\n#EXTINF:60.0,\n/media/{encoded_path}\n#EXT-X-ENDLIST\n"""
return web.Response(text=manifest, content_type='application/vnd.apple.mpegurl')
async def save_settings_api(request):
"""API endpoint to receive and save settings"""
try:
data = await request.json()
logging.getLogger("web_ui").info(f"Received settings to save: {data}")
return web.json_response({'status': 'success', 'message': 'Settings saved successfully!'})
except Exception as e:
logging.getLogger("web_ui").error(f"Error saving settings: {e}")
return web.json_response({'status': 'error', 'message': str(e)}, status=500)
async def init_api(request):
"""API endpoint to provide initial data to the client."""
try:
params = Params()
return web.json_response({
'is_metric': params.get_bool("IsMetric"),
'dp_dev_dashy': int(params.get("dp_dev_dashy") or 0)
})
except Exception as e:
logging.getLogger("web_ui").error(f"Error fetching initial data: {e}")
return web.json_response({'error': f"Error fetching initial data: {e}"}, status=500)
async def on_startup(app):
logging.getLogger("web_ui").info("Web UI application starting up...")
async def on_cleanup(app):
logging.getLogger("web_ui").info("Web UI application shutting down...")
# --- CORS Middleware ---
@web.middleware
async def cors_middleware(request, handler):
response = await handler(request)
response.headers['Access-Control-Allow-Origin'] = '*'
response.headers['Access-Control-Allow-Methods'] = 'GET, POST, PUT, DELETE, OPTIONS'
response.headers['Access-Control-Allow-Headers'] = 'Content-Type, Authorization'
return response
async def handle_cors_preflight(request):
if request.method == 'OPTIONS':
headers = {
'Access-Control-Allow-Origin': '*',
'Access-Control-Allow-Methods': 'GET, POST, PUT, DELETE, OPTIONS',
'Access-Control-Allow-Headers': 'Content-Type, Authorization',
'Access-Control-Max-Age': '86400',
}
return web.Response(status=200, headers=headers)
return await request.app['handler'](request)
def setup_aiohttp_app(host: str, port: int, debug: bool):
logging.basicConfig(level=logging.INFO, format='%(asctime)s - %(name)s - %(levelname)s - %(message)s')
logging.getLogger("web_ui").setLevel(logging.DEBUG if debug else logging.INFO)
app = web.Application(middlewares=[cors_middleware])
app['port'] = port
# Register API endpoints
app.router.add_get("/api/init", init_api)
app.router.add_get("/api/files", list_files_api)
app.router.add_get("/api/play", serve_player_api)
app.router.add_get("/api/manifest.m3u8", serve_manifest_api)
# app.router.add_post("/api/settings", save_settings_api)
# Static files
app.router.add_static('/media', path=DEFAULT_DIR, name='media', show_index=False, follow_symlinks=False)
app.router.add_static('/download', path=DEFAULT_DIR, name='download', show_index=False, follow_symlinks=False)
app.router.add_get("/", lambda r: web.FileResponse(os.path.join(WEB_DIST_PATH, "index.html")))
app.router.add_static("/", path=WEB_DIST_PATH)
app.on_startup.append(on_startup)
app.on_cleanup.append(on_cleanup)
# Add CORS preflight handler
app.router.add_route('OPTIONS', '/{tail:.*}', handle_cors_preflight)
return app
def main():
# rick - may need "sudo ufw allow 5088" to allow port access
parser = argparse.ArgumentParser(description="Dashy Server")
parser.add_argument("--host", type=str, default="0.0.0.0", help="Host to listen on")
parser.add_argument("--port", type=int, default=5088, help="Port to listen on")
parser.add_argument("--debug", action="store_true", help="Enable debug mode")
args = parser.parse_args()
app = setup_aiohttp_app(args.host, args.port, args.debug)
web.run_app(app, host=args.host, port=args.port)
if __name__ == "__main__":
main()

58
dragonpilot/dashy/web/dist/README.md vendored Normal file
View File

@@ -0,0 +1,58 @@
# dashy - dragonpilot's All-in-one System Hub for You
A modern web-based dashboard for monitoring and controlling your dragonpilot/openpilot remotely.
## Usage
These files should be served by the Dashy backend server running on your comma device.
Access the interface by navigating to `http://<comma-device-ip>:5088` in Chrome browser.
## Files
- `index.html` - Main application
- `js/app.js` - Minified JavaScript bundle
- `css/styles.css` - Minified styles
- `icons/` - Favicon
- `pages/player.html` - HLS video player
## Features
- **Live Driving View** - Real-time WebRTC video with augmented reality overlay
- **File Browser** - Access and stream driving recordings
- **Settings Control** - Configure vehicle and display preferences
## 🎮 Usage
### Navigation
- **Driving View** - Live camera feed with lane lines and path visualization
- **Files** - Browse `/data/media/0/realdata` recordings
- **Local Settings** - Adjust display preferences
### Display Options
- Metric/Imperial units
- HUD mode for windshield projection
## Requirements
- dragonpilot/openpilot device (comma 3/3X)
- Chrome browser (recommended)
- Same network connection as vehicle
## 📄 License
Copyright (c) 2025, Rick Lan
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, and/or sublicense,
for non-commercial purposes only, subject to the following conditions:
- The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
- Commercial use (e.g. use in a product, service, or activity intended to
generate revenue) is prohibited without explicit written permission from
the copyright holder.
THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 145 KiB

1
dragonpilot/dashy/web/dist/index.html vendored Normal file
View File

@@ -0,0 +1 @@
<!doctypehtml><html lang="en"><meta charset="UTF-8"><meta name="viewport"content="width=device-width,initial-scale=1,user-scalable=no"><title>Dashy by dragonpilot</title><link rel="icon"href="/icons/icon-192x192.png"><link rel="stylesheet"href="/css/styles.css"><div id="app-container"><nav><button id="nav-files"class="active">Files</button> <button id="nav-driving"style="display:none"class="">Driving</button> <button id="nav-local-settings"style="display:none">Local Settings</button></nav><main id="page-content"style="flex-grow:1;min-height:0"><div id="files-page"class="page active"><div id="files-breadcrumbs"></div><table id="files-table"><thead><tr><th><th>Name<th>Last Modified<th style="text-align:right">Size<th><tbody></table></div><div id="driving-page"class="page"><div id="driving-page-content"><video id="videoPlayer"autoplay playsinline muted></video><canvas id="uiCanvas"></canvas></div></div><div id="local-settings-page"class="page"><div class="settings-page-wrapper"><h1>Local Settings</h1><div id="local-settings-content"></div></div></div></main></div><script src="/js/app.js"></script>

1
dragonpilot/dashy/web/dist/js/app.js vendored Normal file

File diff suppressed because one or more lines are too long

2
dragonpilot/dashy/web/dist/lib/hls.js vendored Normal file

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1 @@
<!doctypehtml><title>HLS Player</title><style>body,html{margin:0;padding:0;height:100%;background-color:#000}#video{width:100%;height:100%}</style><script src="/lib/hls.js"></script><video id="video"controls autoplay></video><script>var v=document.getElementById("video"),s="/api/manifest.m3u8?file={{FILE_PATH}}";if(Hls.isSupported()){var h=new Hls;h.loadSource(s),h.attachMedia(v)}else v.canPlayType("application/vnd.apple.mpegurl")&&(v.src=s)</script>

View File

@@ -0,0 +1,85 @@
"""
Copyright (c) 2025, Rick Lan
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, and/or sublicense,
for non-commercial purposes only, subject to the following conditions:
- The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
- Commercial use (e.g. use in a product, service, or activity intended to
generate revenue) is prohibited without explicit written permission from
the copyright holder.
THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
"""
import numpy as np
SLOPE = -0.04
RATIO = 0.9
TTC = 3.5
TTC_BP = [TTC, 2.5]
MIN_BRAKE_ALLOW_VALS = [0., -0.5]
class ACM:
def __init__(self):
self.enabled = False
self.downhill_only = False
self._is_downhill = False
self._is_speed_over_cruise = False
self._has_lead = False
self._active_prev = False
self.active = False
self.just_disabled = False
self.allowed_brake_val = 0.
def update_states(self, cs, rs, user_ctrl_lon, v_ego, v_cruise):
self.lead_ttc = float('inf') # Default if no lead
if not self.enabled:
self.active = False
return
if len(cs.orientationNED) != 3:
self.active = False
return
pitch_rad = cs.orientationNED[1]
self._is_downhill = np.sin(pitch_rad) < SLOPE
self._is_speed_over_cruise = v_ego > (v_cruise * RATIO)
lead = rs.leadOne
if lead and lead.status:
self.lead_ttc = lead.dRel / v_ego if v_ego > 0 else float('inf')
self._has_lead = self.lead_ttc < TTC
else:
self._has_lead = False
self.active = not user_ctrl_lon and not self._has_lead and self._is_speed_over_cruise and (self._is_downhill if self.downhill_only else True)
self.just_disabled = self._active_prev and not self.active
self._active_prev = self.active
def update_a_desired_trajectory(self, a_desired_trajectory):
if not self.active:
return a_desired_trajectory
# Suppress all braking to allow smooth coasting
for i in range(len(a_desired_trajectory)):
if a_desired_trajectory[i] < 0 and a_desired_trajectory[i] > self.allowed_brake_val:
a_desired_trajectory[i] = 0.0
return a_desired_trajectory
def update_output_a_target(self, output_a_target):
if not self.active:
return output_a_target
# Suppress braking
if output_a_target < 0 and output_a_target > self.allowed_brake_val:
output_a_target = 0.0
return output_a_target

View File

@@ -0,0 +1,389 @@
"""
Copyright (c) 2025, Rick Lan
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, and/or sublicense,
for non-commercial purposes only, subject to the following conditions:
- The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
- Commercial use (e.g. use in a product, service, or activity intended to
generate revenue) is prohibited without explicit written permission from
the copyright holder.
THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
"""
from openpilot.common.filter_simple import FirstOrderFilter
from openpilot.common.realtime import DT_MDL
import numpy as np
from cereal import log
class AEM:
# --- Configuration Constants ---
# Speed thresholds (m/s)
SPEED_THRESHOLD_HIGHWAY = 22.23 # m/s (approx. 80 kph)
SPEED_THRESHOLD_CITY = 15.27 # m/s (approx. 55 kph)
SPEED_THRESHOLD_LOW = 5.56 # m/s (approx. 20 kph)
SPEED_THRESHOLD_CREEP = 2.23 # m/s (approx. 8 kph)
# Lead related thresholds
LEAD_TTC_CRITICAL = 1.75 # seconds, time to collision
LEAD_TTC_CAUTION = 3.0
LEAD_DIST_VERY_CLOSE = 10.0 # meters
LEAD_DIST_FAR_HIGHWAY = 85.0 # meters, for considering lead far enough on highway
LEAD_DIST_DEFAULT_NO_LEAD = 150.0 # Default distance for EMA when no lead
LEAD_ACCEL_HARD_BRAKE = -3.0 # m/s^2
LEAD_ACCEL_MILD_BRAKE = -2.0 # m/s^2
LEAD_ACCEL_PULLING_AWAY = 0.5 # m/s^2
# Steering thresholds
STEERING_ANGLE_ABS_HIGH_CURVATURE = 45.0 # degrees (EMA value)
# Hysteresis & Timers
HYSTERESIS_FRAMES_TO_SWITCH = 10 # Approx 0.5s at 20Hz
LEAD_LOST_FRAMES_TO_FALLBACK_BASE = 40 # Approx 2s at 20Hz
# EMA filter time constants (seconds) - THESE ARE DESIGN PARAMETERS
EMA_TC_V_EGO = 1.0
EMA_TC_LEAD_DREL = 0.5
EMA_TC_LEAD_V_ABS = 0.5 # Filters absolute lead speed
EMA_TC_LEAD_ALEAD = 0.5
EMA_TC_STEERING_ANGLE_ABS = 0.8
EMA_TC_V_MODEL_ERROR = 1.0
# Model & Planner Related Thresholds
MODEL_VEL_ERROR_THRESHOLD = 2.0 # m/s (EMA value)
MIN_VISION_LEAD_PROB_ACTION = 0.5 # Min modelProb for acting on vision-only leads
# Other
REL_SPEED_SIGNIFICANT_DIFFERENCE = 2.5 # m/s
def __init__(self, debug=False):
self.enabled = False
self._current_mode = 'acc' # Default to ACC
self._target_mode_suggestion = None
self._mode_switch_counter = 0
self.debug = debug
self._lead_id_prev = -1
self._lead_absence_frames = 0
self.personality = log.LongitudinalPersonality.standard
# --- Calculate alpha values from time constants (tau) ---
def get_alpha(tau, dt):
"""Calculates EMA alpha from time constant and time step."""
# Ensure tau > 0 to avoid division by zero if dt=0 somehow
# Also handle potential case where dt is zero
return dt / (tau + dt) if tau > 1e-5 and dt > 1e-5 else 1.0 # Default to alpha=1 (no filtering) if tau or dt is invalid/zero
alpha_v_ego = get_alpha(AEM.EMA_TC_V_EGO, DT_MDL)
alpha_lead_drel = get_alpha(AEM.EMA_TC_LEAD_DREL, DT_MDL)
alpha_lead_v_abs = get_alpha(AEM.EMA_TC_LEAD_V_ABS, DT_MDL)
alpha_lead_alead = get_alpha(AEM.EMA_TC_LEAD_ALEAD, DT_MDL)
alpha_steering_angle_abs = get_alpha(AEM.EMA_TC_STEERING_ANGLE_ABS, DT_MDL)
alpha_v_model_error = get_alpha(AEM.EMA_TC_V_MODEL_ERROR, DT_MDL)
# --- Initialize EMA Filters using alpha ---
# Ensure FirstOrderFilter takes 'alpha' as keyword arg
try:
self._v_ego_ema = FirstOrderFilter(0.0, alpha=alpha_v_ego, dt=DT_MDL)
self._lead_drel_ema = FirstOrderFilter(AEM.LEAD_DIST_DEFAULT_NO_LEAD, alpha=alpha_lead_drel, dt=DT_MDL)
self._lead_v_ema = FirstOrderFilter(0.0, alpha=alpha_lead_v_abs, dt=DT_MDL) # Filters absolute V_lead
self._lead_alead_ema = FirstOrderFilter(0.0, alpha=alpha_lead_alead, dt=DT_MDL)
self._steering_angle_abs_ema = FirstOrderFilter(0.0, alpha=alpha_steering_angle_abs, dt=DT_MDL)
# self._v_model_error_ema = FirstOrderFilter(0.0, alpha=alpha_v_model_error, dt=DT_MDL)
except TypeError:
# Fallback if the specific FirstOrderFilter expects positional args differently
print("Warning: FirstOrderFilter init failed with keyword 'alpha', attempting positional.")
self._v_ego_ema = FirstOrderFilter(0.0, alpha_v_ego, DT_MDL)
self._lead_drel_ema = FirstOrderFilter(AEM.LEAD_DIST_DEFAULT_NO_LEAD, alpha_lead_drel, DT_MDL)
self._lead_v_ema = FirstOrderFilter(0.0, alpha_lead_v_abs, DT_MDL)
self._lead_alead_ema = FirstOrderFilter(0.0, alpha_lead_alead, DT_MDL)
self._steering_angle_abs_ema = FirstOrderFilter(0.0, alpha_steering_angle_abs, DT_MDL)
# self._v_model_error_ema = FirstOrderFilter(0.0, alpha_v_model_error, DT_MDL)
self._log(f"AEM Initialized. Alphas: v_ego={alpha_v_ego:.3f}, dRel={alpha_lead_drel:.3f}, vLead={alpha_lead_v_abs:.3f}, aLead={alpha_lead_alead:.3f}, steer={alpha_steering_angle_abs:.3f}, v_err={alpha_v_model_error:.3f}")
def _log(self, msg: str):
"""Logs debug messages if debug is enabled."""
if self.debug:
# Consider using cloudlog for persistent logs during testing
# from openpilot.common.swaglog import cloudlog
# cloudlog.debug(f"[AEM]: {msg}")
print(f"[AEM]: {msg}")
def _calculate_ttc(self, dist: float, ego_speed: float, lead_speed: float) -> float:
"""Calculates Time To Collision (TTC), returns infinity if collision is not imminent."""
relative_speed = ego_speed - lead_speed
if dist > 0.1 and relative_speed > 0.3: # Thresholds to avoid noise and division issues
# Avoid division by zero or very small numbers
return max(0.0, dist / relative_speed) # Return non-negative TTC
return float('inf') # Return infinity if no collision course or relative speed is too low
def _reset_lead_emas(self, d_lead_raw, v_lead_raw, a_lead_raw):
"""Helper to reset/initialize lead EMAs' state."""
# This assumes direct state access/setting via '.x' is the correct method
# for the FirstOrderFilter implementation being used.
try:
self._lead_drel_ema.x = float(d_lead_raw)
self._lead_v_ema.x = float(v_lead_raw)
self._lead_alead_ema.x = float(a_lead_raw)
# Ensure filter knows it's 'initialized' if it uses that flag internally
self._lead_drel_ema.initialized = True
self._lead_v_ema.initialized = True
self._lead_alead_ema.initialized = True
self._log(f"Reset lead EMAs with raw values: d={d_lead_raw:.2f}, v={v_lead_raw:.2f}, a={a_lead_raw:.2f}")
except AttributeError:
self._log("Warning: Could not directly set '.x' on FirstOrderFilter. Reset may not be immediate.")
# If direct access fails, update might be the only way, causing a slight delay in reset
self._lead_drel_ema.update(d_lead_raw)
self._lead_v_ema.update(v_lead_raw)
self._lead_alead_ema.update(a_lead_raw)
def set_personality(self, v_ego, personality):
self.personality = personality
if self.enabled:
self.personality = log.LongitudinalPersonality.aggressive if v_ego > 16.67 else self.personality
return self.personality
# Note: Removed 'model_predicted_max_curvature_upcoming_raw' from signature
def get_mode(self, v_ego_raw: float, lead_one_data_raw, steering_angle_deg_raw: float, standstill_raw: bool,
long_personality: int, allow_throttle_planner: bool,
model_path_plan_raw: dict, a_target_from_prev_cycle: float, model_predicts_stop_prev: bool,
fcw_active_prev: bool) -> str:
"""
Determines the appropriate MPC mode ('acc' or 'blended') based on current conditions.
ACC is primary, Blended is assist.
"""
if not self.enabled:
# Should not be called if not enabled, but return primary mode as safeguard
return 'acc'
# 0. Initialize suggested mode with AEM's current internal state
suggested_mode = self._current_mode
# 1. Update common EMA filters
self._v_ego_ema.update(v_ego_raw)
self._steering_angle_abs_ema.update(abs(steering_angle_deg_raw))
# Use absolute value of model error for thresholding
# self._v_model_error_ema.update(abs(v_model_error_raw))
# 2. Process Lead Data & Update Lead EMAs
lead_status = lead_one_data_raw.status
current_lead_id = lead_one_data_raw.radarTrackId if lead_status else -1
d_lead_raw = lead_one_data_raw.dRel if lead_status else AEM.LEAD_DIST_DEFAULT_NO_LEAD
v_lead_raw = lead_one_data_raw.vLead if lead_status else self._v_ego_ema.x # Default to filtered ego if no lead
a_lead_raw = lead_one_data_raw.aLeadK if lead_status else 0.0
model_prob_lead = lead_one_data_raw.modelProb if lead_status else 0.0
if lead_status:
# Reset EMA if lead ID changes significantly (from a valid previous ID)
if current_lead_id != self._lead_id_prev and self._lead_id_prev != -1:
self._log(f"Lead ID changed: {self._lead_id_prev} -> {current_lead_id}.")
self._reset_lead_emas(d_lead_raw, v_lead_raw, a_lead_raw)
# Reset EMA if acquiring lead from no-lead state
elif self._lead_id_prev == -1 and current_lead_id != -1:
self._log(f"Lead acquired: ID {current_lead_id}.")
self._reset_lead_emas(d_lead_raw, v_lead_raw, a_lead_raw)
# Update filters with current raw data
self._lead_drel_ema.update(d_lead_raw)
self._lead_v_ema.update(v_lead_raw)
self._lead_alead_ema.update(a_lead_raw)
self._lead_absence_frames = 0
else: # No lead currently
self._lead_absence_frames += 1
# If lead was just lost, reset EMAs to default values
if self._lead_id_prev != -1:
self._log(f"Lead lost (Prev ID: {self._lead_id_prev}). Resetting lead EMAs to defaults.")
# Reset using the helper function ensures consistency
self._reset_lead_emas(AEM.LEAD_DIST_DEFAULT_NO_LEAD, self._v_ego_ema.x, 0.0)
else: # Still no lead, continue updating towards defaults
self._lead_drel_ema.update(AEM.LEAD_DIST_DEFAULT_NO_LEAD)
self._lead_v_ema.update(self._v_ego_ema.x) # Update towards filtered ego speed
self._lead_alead_ema.update(0.0) # Update towards zero accel
# Update previous lead ID for next cycle comparison *after* using it
self._lead_id_prev = current_lead_id
# 3. Get Filtered Values for decision making
v_ego = self._v_ego_ema.x
d_lead = self._lead_drel_ema.x
v_lead = self._lead_v_ema.x # Filtered absolute lead speed
a_lead = self._lead_alead_ema.x
steering_angle_abs = self._steering_angle_abs_ema.x
# v_model_error = self._v_model_error_ema.x
ttc = self._calculate_ttc(d_lead, v_ego, v_lead)
is_lead_one_vision_only = lead_status and current_lead_id == -1
# 4. Infer Current Model Intentions from raw plan
raw_model_stop_intention_current_cycle = False
if model_path_plan_raw and 'v' in model_path_plan_raw:
model_v_traj = model_path_plan_raw['v']
if len(model_v_traj) >= 5:
avg_final_model_v = np.mean(model_v_traj[-5:])
final_model_v = model_v_traj[-1]
# Consider stop if avg end speed is near creep and final point is very low
raw_model_stop_intention_current_cycle = avg_final_model_v < AEM.SPEED_THRESHOLD_CREEP and \
final_model_v < AEM.SPEED_THRESHOLD_CREEP * 0.7
elif len(model_v_traj) > 0: # Fallback for shorter trajectories
raw_model_stop_intention_current_cycle = np.isclose(model_v_traj[-1], 0.0, atol=0.3)
# --- 5. Mode Selection Logic ---
min_prob_for_action = AEM.MIN_VISION_LEAD_PROB_ACTION if is_lead_one_vision_only else 0.0
# A. Evaluate conditions to switch TO BLENDED (from ACC)
if self._current_mode == 'acc':
needs_blended_assist = False
reason = "None" # Default reason
# Scenario 1: Emergency/Dangerous Lead Situation
if lead_status and ttc < AEM.LEAD_TTC_CRITICAL and v_ego > AEM.SPEED_THRESHOLD_LOW and model_prob_lead >= min_prob_for_action:
needs_blended_assist, reason = True, f"Critical TTC ({ttc:.2f}s)"
elif lead_status and a_lead < AEM.LEAD_ACCEL_HARD_BRAKE and d_lead < (v_ego * 2.5) and model_prob_lead >= min_prob_for_action:
needs_blended_assist, reason = True, f"Hard lead brake ({a_lead:.2f}), d={d_lead:.1f}"
elif fcw_active_prev:
needs_blended_assist, reason = True, "FCW previously active"
# Scenario 2: Sudden Lead Cut-in/Appearance
# Check only if not already triggered by emergency
if not needs_blended_assist and lead_status and current_lead_id != self._lead_id_prev and self._lead_id_prev != -1 and \
ttc < AEM.LEAD_TTC_CAUTION and d_lead < (AEM.LEAD_DIST_VERY_CLOSE * 2.5) and model_prob_lead >= min_prob_for_action:
needs_blended_assist, reason = True, f"Sudden cut-in (TTC={ttc:.2f}, d={d_lead:.1f})"
# Scenario 3: Low-Speed/Urban/Congestion (Lead)
if not needs_blended_assist and lead_status and v_ego < AEM.SPEED_THRESHOLD_LOW and \
d_lead < (AEM.LEAD_DIST_VERY_CLOSE * 1.8) and model_prob_lead >= min_prob_for_action:
needs_blended_assist, reason = True, f"Low speed ({v_ego:.1f}) close lead ({d_lead:.1f})"
# Scenario 4: Model Predicts Stop
if not needs_blended_assist and \
(raw_model_stop_intention_current_cycle or model_predicts_stop_prev) and \
v_ego > AEM.SPEED_THRESHOLD_CREEP:
needs_blended_assist, reason = True, f"Model predicts stop (curr={raw_model_stop_intention_current_cycle}, prev={model_predicts_stop_prev})"
# Scenario 5: High Curvature/Urban Turns (Curvature input removed)
if not needs_blended_assist and \
steering_angle_abs > AEM.STEERING_ANGLE_ABS_HIGH_CURVATURE and \
v_ego < AEM.SPEED_THRESHOLD_CITY:
needs_blended_assist, reason = True, f"High steering angle ({steering_angle_abs:.1f})"
# Scenario 6: Planner Already Braking (Prev Cycle)
if not needs_blended_assist and \
a_target_from_prev_cycle < AEM.LEAD_ACCEL_MILD_BRAKE and \
not standstill_raw and v_ego > AEM.SPEED_THRESHOLD_CREEP:
needs_blended_assist, reason = True, f"Planner prev brake ({a_target_from_prev_cycle:.2f})"
# Scenario 7: MPC Favored E2E (Prev Cycle) & still complex
# if not needs_blended_assist and mpc_source_prev == 'e2e':
# is_complex = (v_ego < AEM.SPEED_THRESHOLD_CITY or \
# (lead_status and ttc < AEM.LEAD_TTC_CAUTION and model_prob_lead >= min_prob_for_action) or \
# (steering_angle_abs > AEM.STEERING_ANGLE_ABS_HIGH_CURVATURE * 0.6)) # Removed curvature check
# if is_complex:
# needs_blended_assist, reason = True, "Prev E2E source & ongoing complexity"
# Scenario 8: High Gas Disengage Prob. (Model)
if not needs_blended_assist and not allow_throttle_planner and \
(not lead_status or (lead_status and v_ego < (v_lead + AEM.REL_SPEED_SIGNIFICANT_DIFFERENCE * 0.5))):
needs_blended_assist, reason = True, "Model advises against throttle"
if needs_blended_assist:
suggested_mode = 'blended'
self._log(f"ACC->BLENDED Trigger: {reason}")
# B. Evaluate conditions to switch TO ACC (from Blended)
elif self._current_mode == 'blended':
# Assume staying in blended unless conditions strongly favor returning to ACC
suggested_mode = 'blended'
# Check if any critical Blended-triggering condition is still fundamentally active
blended_condition_still_active = False
active_blended_reason = "None"
if lead_status and ttc < AEM.LEAD_TTC_CRITICAL and v_ego > AEM.SPEED_THRESHOLD_LOW and model_prob_lead >= min_prob_for_action: blended_condition_still_active, active_blended_reason = True, "Critical TTC"
elif lead_status and a_lead < AEM.LEAD_ACCEL_HARD_BRAKE and model_prob_lead >= min_prob_for_action: blended_condition_still_active, active_blended_reason = True, "Hard Lead Brake"
elif fcw_active_prev: blended_condition_still_active, active_blended_reason = True, "Prev FCW"
elif (raw_model_stop_intention_current_cycle or model_predicts_stop_prev) and v_ego > AEM.SPEED_THRESHOLD_CREEP: blended_condition_still_active, active_blended_reason = True, "Model Predicts Stop"
elif steering_angle_abs > AEM.STEERING_ANGLE_ABS_HIGH_CURVATURE and v_ego < AEM.SPEED_THRESHOLD_CITY: blended_condition_still_active, active_blended_reason = True, "High Steering Angle"
elif a_target_from_prev_cycle < AEM.LEAD_ACCEL_MILD_BRAKE and not standstill_raw and v_ego > AEM.SPEED_THRESHOLD_CREEP: blended_condition_still_active, active_blended_reason = True, "Prev Planner Brake"
elif not allow_throttle_planner and (not lead_status or (lead_status and v_ego < (v_lead + AEM.REL_SPEED_SIGNIFICANT_DIFFERENCE * 0.5))): blended_condition_still_active, active_blended_reason = True, "Gas Disengage Prob"
elif lead_status and v_ego < AEM.SPEED_THRESHOLD_LOW and \
d_lead < (AEM.LEAD_DIST_VERY_CLOSE * 1.8) and \
model_prob_lead >= min_prob_for_action: # Using filtered values (v_ego, d_lead) as in other checks
blended_condition_still_active, active_blended_reason = True, f"Persisting Low speed ({v_ego:.1f}) close lead ({d_lead:.1f})"
# Low speed congestion is implicitly handled by other checks usually involving TTC or stops
if not blended_condition_still_active:
safe_to_return_to_acc = False
reason = ""
# Scenario 10: Highway Cruising - Excellent Conditions
if v_ego > AEM.SPEED_THRESHOLD_HIGHWAY and \
steering_angle_abs < (AEM.STEERING_ANGLE_ABS_HIGH_CURVATURE * 0.3) and \
(not lead_status or d_lead > (AEM.LEAD_DIST_FAR_HIGHWAY * 0.8) or ttc > (AEM.LEAD_TTC_CAUTION * 1.5)):
safe_to_return_to_acc, reason = True, "Highway cruise, clear path"
# Scenario 11: Stable Following - Safe Distance Achieved
elif lead_status and v_ego > AEM.SPEED_THRESHOLD_LOW and \
ttc > AEM.LEAD_TTC_CAUTION and \
d_lead > (AEM.LEAD_DIST_VERY_CLOSE * 2.0) and \
abs(a_lead) < (AEM.LEAD_ACCEL_PULLING_AWAY * 0.8) and \
abs(v_ego - v_lead) < (AEM.REL_SPEED_SIGNIFICANT_DIFFERENCE * 0.75) and \
steering_angle_abs < (AEM.STEERING_ANGLE_ABS_HIGH_CURVATURE * 0.5):
safe_to_return_to_acc, reason = True, f"Stable following (TTC={ttc:.2f}, d={d_lead:.1f})"
# Scenario 12: Prolonged Lead Absence
elif not lead_status:
personality_factor = 1.3 if long_personality == 0 else (0.7 if long_personality == 2 else 1.0)
fallback_frames = AEM.LEAD_LOST_FRAMES_TO_FALLBACK_BASE * personality_factor
if self._lead_absence_frames > fallback_frames and v_ego > AEM.SPEED_THRESHOLD_LOW:
safe_to_return_to_acc, reason = True, f"Prolonged lead absence ({self._lead_absence_frames} frames)"
# Scenario 13: Persistent High Model Velocity Error
# elif v_model_error > AEM.MODEL_VEL_ERROR_THRESHOLD:
# safe_to_return_to_acc, reason = True, f"High model vel error ({v_model_error:.2f})"
# Default fallback if no active blended condition and no specific ACC condition met
elif not safe_to_return_to_acc:
safe_to_return_to_acc, reason = True, "No active Blended condition found"
if safe_to_return_to_acc:
suggested_mode = 'acc'
self._log(f"BLENDED->ACC Trigger: {reason}")
else:
self._log(f"Staying BLENDED due to active condition: {active_blended_reason}")
# --- 6. Apply Hysteresis ---
if suggested_mode != self._current_mode:
# If target mode changes, reset counter
if self._target_mode_suggestion != suggested_mode:
self._target_mode_suggestion = suggested_mode
self._mode_switch_counter = 1
self._log(f"Target mode suggestion: {self._target_mode_suggestion}. Counter: {self._mode_switch_counter}")
# If target mode remains the same, increment counter
else:
self._mode_switch_counter += 1
# Log counter increment for debugging flapping
# self._log(f"Target mode {self._target_mode_suggestion} persists. Counter: {self._mode_switch_counter}")
# Check if threshold is met to execute switch
if self._mode_switch_counter >= AEM.HYSTERESIS_FRAMES_TO_SWITCH:
self._log(f"\n-----------------------\nExecuting switch from {self._current_mode} to {self._target_mode_suggestion}\n-----------------------")
self._current_mode = self._target_mode_suggestion
# Reset hysteresis state after switch
self._mode_switch_counter = 0
self._target_mode_suggestion = None
# else: remain in _current_mode until counter threshold met
else: # Suggested mode is the same as current mode
# If there was a pending switch suggestion, cancel it
if self._target_mode_suggestion is not None:
self._log(f"Mode suggestion {suggested_mode} matches current mode {self._current_mode}, cancelling pending switch to {self._target_mode_suggestion}")
# Reset hysteresis state
self._target_mode_suggestion = None
self._mode_switch_counter = 0
# Return the potentially updated current mode
return self._current_mode

View File

@@ -0,0 +1,57 @@
#!/usr/bin/env python3
"""
Copyright (c) 2019, rav4kumar, Rick Lan, dragonpilot community, and a number of other of contributors.
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, and/or sublicense,
for non-commercial purposes only, subject to the following conditions:
- The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
- Commercial use (e.g. use in a product, service, or activity intended to
generate revenue) is prohibited without explicit written permission from
the copyright holder.
THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
"""
import numpy as np
NEARSIDE_PROB = 0.2
EDGE_PROB = 0.35
class RoadEdgeDetector:
def __init__(self, enabled = False):
self._is_enabled = enabled
self.left_edge_detected = False
self.right_edge_detected = False
def update(self, road_edge_stds, lane_line_probs):
if not self._is_enabled:
return
left_road_edge_prob = np.clip(1.0 - road_edge_stds[0], 0.0, 1.0)
left_lane_nearside_prob = lane_line_probs[0]
right_road_edge_prob = np.clip(1.0 - road_edge_stds[1], 0.0, 1.0)
right_lane_nearside_prob = lane_line_probs[3]
self.left_edge_detected = bool(
left_road_edge_prob > EDGE_PROB and
left_lane_nearside_prob < NEARSIDE_PROB and
right_lane_nearside_prob >= left_lane_nearside_prob
)
self.right_edge_detected = bool(
right_road_edge_prob > EDGE_PROB and
right_lane_nearside_prob < NEARSIDE_PROB and
left_lane_nearside_prob >= right_lane_nearside_prob
)
def set_enabled(self, enabled):
self._is_enabled = enabled
def is_enabled(self):
return self._is_enabled

View File

@@ -0,0 +1,139 @@
#!/usr/bin/env python3
"""
Copyright (c) 2025, Rick Lan
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, and/or sublicense,
for non-commercial purposes only, subject to the following conditions:
- The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
- Commercial use (e.g. use in a product, service, or activity intended to
generate revenue) is prohibited without explicit written permission from
the copyright holder.
THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
"""
import subprocess
import time
from cereal import car, messaging
from openpilot.common.realtime import Ratekeeper
import threading
AudibleAlert = car.CarControl.HUDControl.AudibleAlert
class Beepd:
def __init__(self):
self.current_alert = AudibleAlert.none
self.enable_gpio()
def enable_gpio(self):
try:
subprocess.run("echo 42 | sudo tee /sys/class/gpio/export",
shell=True,
stderr=subprocess.DEVNULL,
stdout=subprocess.DEVNULL,
encoding='utf8')
except Exception:
pass
subprocess.run("echo \"out\" | sudo tee /sys/class/gpio/gpio42/direction",
shell=True,
stderr=subprocess.DEVNULL,
stdout=subprocess.DEVNULL,
encoding='utf8')
def _beep(self, on):
val = "1" if on else "0"
subprocess.run(f"echo \"{val}\" | sudo tee /sys/class/gpio/gpio42/value",
shell=True,
stderr=subprocess.DEVNULL,
stdout=subprocess.DEVNULL,
encoding='utf8')
def engage(self):
self._beep(True)
time.sleep(0.05)
self._beep(False)
def disengage(self):
for _ in range(2):
self._beep(True)
time.sleep(0.01)
self._beep(False)
time.sleep(0.01)
def warning(self):
for _ in range(3):
self._beep(True)
time.sleep(0.01)
self._beep(False)
time.sleep(0.01)
def warning_immediate(self):
for _ in range(5):
self._beep(True)
time.sleep(0.01)
self._beep(False)
time.sleep(0.01)
def dispatch_beep(self, func):
threading.Thread(target=func, daemon=True).start()
def update_alert(self, new_alert):
current_alert_played_once = self.current_alert == AudibleAlert.none
if self.current_alert != new_alert and (new_alert != AudibleAlert.none or current_alert_played_once):
self.current_alert = new_alert
# if new_alert == AudibleAlert.engage:
# self.dispatch_beep(self.engage)
# if new_alert == AudibleAlert.disengage:
# self.dispatch_beep(self.disengage)
if new_alert == AudibleAlert.warningImmediate:
self.dispatch_beep(self.warning_immediate)
def get_audible_alert(self, sm):
if sm.updated['selfdriveState']:
new_alert = sm['selfdriveState'].alertSound.raw
self.update_alert(new_alert)
def test_beepd_thread(self):
frame = 0
rk = Ratekeeper(20)
pm = messaging.PubMaster(['selfdriveState'])
while True:
cs = messaging.new_message('selfdriveState')
if frame == 20:
cs.selfdriveState.alertSound = AudibleAlert.engage
if frame == 40:
cs.selfdriveState.alertSound = AudibleAlert.disengage
if frame == 60:
cs.selfdriveState.alertSound = AudibleAlert.prompt
if frame == 80:
cs.selfdriveState.alertSound = AudibleAlert.disengage
if frame == 85:
cs.selfdriveState.alertSound = AudibleAlert.prompt
pm.send("selfdriveState", cs)
frame += 1
rk.keep_time()
def beepd_thread(self, test=False):
if test:
threading.Thread(target=self.test_beepd_thread, daemon=True).start()
sm = messaging.SubMaster(['selfdriveState'])
rk = Ratekeeper(20)
while True:
sm.update(0)
self.get_audible_alert(sm)
rk.keep_time()
def main():
s = Beepd()
s.beepd_thread(test=False)
if __name__ == "__main__":
main()

View File

@@ -27,6 +27,25 @@ function agnos_init {
fi
}
no_amp() {
output=$(i2cget -y 0 0x10 0x00 2>/dev/null)
if [ -z "$output" ]; then
return 0
else
return 1
fi
}
function check_device_mode {
if no_amp; then
echo "O3 Lite Mode"
export LITE=1
export DISABLE_DRIVER=1
else
echo "C3 Mode"
fi
}
function launch {
# Remove orphaned git lock if it exists on boot
[ -f "$DIR/.git/index.lock" ] && rm -f $DIR/.git/index.lock
@@ -71,6 +90,7 @@ function launch {
# hardware specific init
if [ -f /AGNOS ]; then
check_device_mode
agnos_init
fi

View File

@@ -5,6 +5,9 @@ export MKL_NUM_THREADS=1
export NUMEXPR_NUM_THREADS=1
export OPENBLAS_NUM_THREADS=1
export VECLIB_MAXIMUM_THREADS=1
if [ -s /data/params/d/dp_device_model_selected ]; then
export FINGERPRINT="$(cat /data/params/d/dp_device_model_selected)"
fi
if [ -z "$AGNOS_VERSION" ]; then
export AGNOS_VERSION="12.8"

View File

@@ -61,7 +61,7 @@ class CarController(CarControllerBase):
# Below are the HUD messages. We copy the stock message and modify
if self.CP.carFingerprint != CAR.NISSAN_ALTIMA:
if self.frame % 2 == 0:
can_sends.append(nissancan.create_lkas_hud_msg(self.packer, CS.lkas_hud_msg, CC.enabled, hud_control.leftLaneVisible, hud_control.rightLaneVisible,
can_sends.append(nissancan.create_lkas_hud_msg(self.packer, CS.lkas_hud_msg, CC.latActive, hud_control.leftLaneVisible, hud_control.rightLaneVisible,
hud_control.leftLaneDepart, hud_control.rightLaneDepart))
if self.frame % 50 == 0:

View File

@@ -0,0 +1,173 @@
"""
Copyright (c) 2025, Rick Lan
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, and/or sublicense,
for non-commercial purposes only, subject to the following conditions:
- The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
- Commercial use (e.g. use in a product, service, or activity intended to
generate revenue) is prohibited without explicit written permission from
the copyright holder.
THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
"""
from opendbc.car.interfaces import RadarInterfaceBase
from opendbc.can.parser import CANParser
from opendbc.car.structs import RadarData
from typing import List, Tuple
# car head to radar
DREL_OFFSET = -1.35
# max object amount will process
MAX_OBJECTS = 100
# lat distance, typically max lane width is 3.7m
MAX_LAT_DIST = 3.6
# objects to ignore thats really close to the vehicle (after DREL_OFFSET applied)
MIN_DIST = 2.5
# when a object has really large negative v_rel means its stationary / standstill
# so with the values below (v_rel = -10, lat_dist = 2.), we are trying to ignore:
# when the ego vehicle is driving above 36 km/h (22.37 mph), we will ignore objects that lateral distance is above 2m on left or right.
STATIONARY_OBJ_VREL = -10.
STATIONARY_OBJ_LAT_DIST = 2.
# when we detect an object that's really closed to the ego vehicle
# we ignore the objects that's away from left or right
CLOSED_OBJ_DREL = 10
CLOSED_OBJ_YREL = 2.
# ignore objects that has small radar cross sections (-64 ~ 63.5)
MIN_RCS = -5.
# ignore oncoming objects
IGNORE_OBJ_STATE = 2
# ignore objects that we haven't seen for 5 secs
NOT_SEEN_INIT = 33*5
def _create_radar_parser():
messages = [("Status", float('nan')), ("ObjectData", float('nan'))]
messages += [(f"ObjectData_{i}", float('nan')) for i in range(MAX_OBJECTS)]
return CANParser('u_radar', messages, 1)
class RadarInterface(RadarInterfaceBase):
def __init__(self, CP):
super().__init__(CP)
self.updated_messages = set()
self.rcp = _create_radar_parser()
self._pts_cache = dict()
self._pts_not_seen = {key: 0 for key in range(255)}
self._should_clear_cache = False
def _create_parsable_object_can_strings(self, can_strings: List[Tuple]) -> Tuple[List[Tuple], int]:
"""Optimized object string parsing with minimal allocations."""
if not can_strings or not isinstance(can_strings[0], tuple) or len(can_strings[0]) < 2:
return [], 0
# Pre-allocate list with known maximum size
new_list = []
new_list_append = new_list.append # Local reference for faster access
records = can_strings[0][1]
id_num = 1
for record in records:
if id_num > MAX_OBJECTS:
break
if record[0] == 0x60B:
new_list_append((id_num + 383, record[1], record[2]))
id_num += 1
return [(can_strings[0][0], new_list)], len(new_list)
# called by card.py, 100hz
def update(self, can_strings):
vls = self.rcp.update(can_strings)
self.updated_messages.update(vls)
if 1546 in self.updated_messages:
self._should_clear_cache = True
if 1547 in self.updated_messages:
parsable_can_string, size = self._create_parsable_object_can_strings(can_strings)
self.rcp.update(parsable_can_string)
# clean cache when we see a 0x60a then a 0x60b
if self._should_clear_cache:
self._pts_cache.clear()
self._should_clear_cache = False
for i in range(size):
cpt = self.rcp.vl[f'ObjectData_{i}']
track_id = int(cpt['ID'])
d_rel = float(cpt['DistLong']) + DREL_OFFSET
y_rel = -float(cpt['DistLat'])
obj_class = int(cpt['Class'])
# ignore oncoming objects
if int(cpt['DynProp']) == IGNORE_OBJ_STATE:
continue
# only apply filters below when object is a point (0) not a vehicle (1)
if obj_class == 0:
# ignore really closed objects
if d_rel < MIN_DIST:
continue
# ignore objects with really small radar cross sections
if float(cpt['RCS']) < MIN_RCS:
continue
# ignore far left/right objects
if abs(y_rel) > MAX_LAT_DIST:
continue
# ignore closed left/right objects when closed
if d_rel < CLOSED_OBJ_DREL and abs(y_rel) > CLOSED_OBJ_YREL:
continue
# add to cache
if track_id not in self._pts_cache:
self._pts_cache[track_id] = RadarData.RadarPoint()
self._pts_cache[track_id].trackId = track_id
self._pts_not_seen[track_id] = NOT_SEEN_INIT
self._pts_cache[track_id].yvRel = float(cpt['VRelLat'])
self._pts_cache[track_id].dRel = d_rel
self._pts_cache[track_id].yRel = y_rel
self._pts_cache[track_id].vRel = float(cpt['VRelLong'])
self._pts_cache[track_id].aRel = float('nan')
self._pts_cache[track_id].measured = True
self.updated_messages.clear()
if self.frame % 2 == 0:
keys_to_remove = [key for key in self.pts if key not in self._pts_cache]
for key in keys_to_remove:
self._pts_not_seen[key] -= 1
if self._pts_not_seen[key] <= 0:
del self.pts[key]
self.pts.update(self._pts_cache)
ret = RadarData()
if not self.rcp.can_valid:
ret.errors.canError = True
ret.points = list(self.pts.values())
return ret
return None

View File

@@ -20,4 +20,6 @@ CarControlT = capnp.lib.capnp._StructModule
CarParamsT = capnp.lib.capnp._StructModule
class DPFlags:
LateralALKA = 1
ExtRadar = 2
pass

View File

@@ -266,7 +266,7 @@ class CarController(CarControllerBase):
if self.frame % 20 == 0 or send_ui:
can_sends.append(toyotacan.create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible,
hud_control.rightLaneVisible, hud_control.leftLaneDepart,
hud_control.rightLaneDepart, CC.enabled, CS.lkas_hud))
hud_control.rightLaneDepart, lat_active, CS.lkas_hud))
if (self.frame % 100 == 0 or send_ui) and (self.CP.enableDsu or self.CP.flags & ToyotaFlags.DISABLE_RADAR.value):
can_sends.append(toyotacan.create_fcw_command(self.packer, fcw_alert))

View File

@@ -77,6 +77,8 @@ class ToyotaFlags(IntFlag):
RAISED_ACCEL_LIMIT = 1024
SECOC = 2048
ALKA = 2 ** 12
def dbc_dict(pt, radar):
return {Bus.pt: pt, Bus.radar: radar}

File diff suppressed because it is too large Load Diff

View File

@@ -8,3 +8,5 @@ class ALTERNATIVE_EXPERIENCE:
DISABLE_STOCK_AEB = 2
RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX = 8
ALLOW_AEB = 16
ALKA = 2 ** 10

View File

@@ -60,8 +60,9 @@ static bool rt_torque_rate_limit_check(int val, int val_last, const int MAX_RT_D
bool steer_torque_cmd_checks(int desired_torque, int steer_req, const TorqueSteeringLimits limits) {
bool violation = false;
uint32_t ts = microsecond_timer_get();
bool alka = (alternative_experience & ALT_EXP_ALKA) != 0;
if (controls_allowed) {
if (controls_allowed || alka) {
// Some safety models support variable torque limit based on vehicle speed
int max_torque = limits.max_torque;
if (limits.dynamic_max_torque) {
@@ -96,7 +97,7 @@ bool steer_torque_cmd_checks(int desired_torque, int steer_req, const TorqueStee
}
// no torque if controls is not allowed
if (!controls_allowed && (desired_torque != 0)) {
if (!(controls_allowed || alka) && (desired_torque != 0)) {
violation = true;
}
@@ -138,7 +139,7 @@ bool steer_torque_cmd_checks(int desired_torque, int steer_req, const TorqueStee
}
// reset to 0 if either controls is not allowed or there's a violation
if (violation || !controls_allowed) {
if (violation || !(controls_allowed || alka)) {
valid_steer_req_count = 0;
invalid_steer_req_count = 0;
desired_torque_last = 0;
@@ -176,7 +177,9 @@ static bool rt_angle_rate_limit_check(AngleSteeringLimits limits) {
bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const AngleSteeringLimits limits) {
bool violation = false;
if (controls_allowed && steer_control_enabled) {
bool alka = (alternative_experience & ALT_EXP_ALKA) != 0;
if ((controls_allowed || alka) && steer_control_enabled) {
// convert floating point angle rate limits to integers in the scale of the desired angle on CAN,
// add 1 to not false trigger the violation. also fudge the speed by 1 m/s so rate limits are
// always slightly above openpilot's in case we read an updated speed in between angle commands
@@ -262,12 +265,12 @@ bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const
}
// No angle control allowed when controls are not allowed
if (!controls_allowed) {
if (!(controls_allowed || alka)) {
violation |= steer_control_enabled;
}
// reset to current angle if either controls is not allowed or there's a violation
if (violation || !controls_allowed) {
if (violation || !(controls_allowed || alka)) {
if (limits.inactive_angle_is_zero) {
desired_angle_last = 0;
} else {
@@ -304,7 +307,10 @@ bool steer_angle_cmd_checks_vm(int desired_angle, bool steer_control_enabled, co
bool violation = false;
if (controls_allowed && steer_control_enabled) {
bool alka = (alternative_experience & ALT_EXP_ALKA) != 0;
if ((controls_allowed || alka) && steer_control_enabled) {
// *** ISO lateral jerk limit ***
// calculate maximum angle rate per second
const float max_curvature_rate_sec = MAX_LATERAL_JERK / (fudged_speed * fudged_speed);
@@ -340,12 +346,12 @@ bool steer_angle_cmd_checks_vm(int desired_angle, bool steer_control_enabled, co
}
// No angle control allowed when controls are not allowed
if (!controls_allowed) {
if (!(controls_allowed || alka)) {
violation |= steer_control_enabled;
}
// reset to current angle if either controls is not allowed or there's a violation
if (violation || !controls_allowed) {
if (violation || !(controls_allowed || alka)) {
desired_angle_last = CLAMP(angle_meas.values[0], -limits.max_angle, limits.max_angle);
}

View File

@@ -238,7 +238,8 @@ static bool honda_tx_hook(const CANPacket_t *msg) {
// STEER: safety check
if ((msg->addr == 0xE4U) || (msg->addr == 0x194U)) {
if (!controls_allowed) {
bool alka = (alternative_experience & ALT_EXP_ALKA) != 0;
if (!(controls_allowed || alka)) {
bool steer_applied = msg->data[0] | msg->data[1];
if (steer_applied) {
tx = false;

View File

@@ -303,6 +303,8 @@ extern struct sample_t angle_meas; // last 6 steer angles/curvatures
// This flag allows AEB to be commanded from openpilot.
#define ALT_EXP_ALLOW_AEB 16
#define ALT_EXP_ALKA 1024
extern int alternative_experience;
// time since safety mode has been changed

View File

@@ -18,6 +18,11 @@ void detect_board_type(void) {
if (!detect_with_pull(GPIOB, 1, PULL_UP) && !detect_with_pull(GPIOB, 7, PULL_UP)) {
hw_type = HW_TYPE_DOS;
current_board = &board_dos;
// rick - for Lite, it detected as UNO before 0.9.9
// Confirmed with mr. one, we are safe to do so for Lite
} else if(!detect_with_pull(GPIOB, 15, PULL_UP)) {
hw_type = HW_TYPE_DOS;
current_board = &board_dos;
}
// Return A13 to the alt mode to fix SWD

View File

@@ -643,6 +643,9 @@ class Panda:
def get_type(self):
ret = self._handle.controlRead(Panda.REQUEST_IN, 0xc1, 0, 0, 0x40)
# rick - UNO to DOS for lite
if ret == bytearray(b'\x05'):
ret = bytearray(b'\x06')
# old bootstubs don't implement this endpoint, see comment in Panda.device
if self._bcd_hw_type is not None and (ret is None or len(ret) != 1):
ret = self._bcd_hw_type

View File

@@ -20,6 +20,7 @@ from opendbc.car.interfaces import CarInterfaceBase, RadarInterfaceBase
from openpilot.selfdrive.pandad import can_capnp_to_list, can_list_to_can_capnp
from openpilot.selfdrive.car.cruise import VCruiseHelper
from openpilot.selfdrive.car.car_specific import MockCarState
from opendbc.safety import ALTERNATIVE_EXPERIENCE
REPLAY = "REPLAY" in os.environ
@@ -101,6 +102,9 @@ class Car:
with car.CarParams.from_bytes(cached_params_raw) as _cached_params:
cached_params = _cached_params
if self.params.get_bool("dp_lat_alka"):
dp_params |= structs.DPFlags.LateralALKA
self.CI = get_car(*self.can_callbacks, obd_callback(self.params), alpha_long_allowed, is_release, num_pandas, dp_params, cached_params)
self.RI = interfaces[self.CI.CP.carFingerprint].RadarInterface(self.CI.CP)
self.CP = self.CI.CP
@@ -111,7 +115,14 @@ class Car:
self.CI, self.CP = CI, CI.CP
self.RI = RI
if self.params.get_bool("dp_lon_ext_radar"):
from opendbc.car.radar_interface import RadarInterface
self.RI = RadarInterface(self.CI.CP)
self.CP.alternativeExperience = 0
if dp_params & structs.DPFlags.LateralALKA:
self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.ALKA
openpilot_enabled_toggle = self.params.get_bool("OpenpilotEnabledToggle")
controller_available = self.CI.CC is not None and openpilot_enabled_toggle and not self.CP.dashcamOnly
self.CP.passive = not controller_available or self.CP.dashcamOnly

View File

@@ -38,7 +38,7 @@ class Controls:
self.sm = messaging.SubMaster(['liveParameters', 'liveTorqueParameters', 'modelV2', 'selfdriveState',
'liveCalibration', 'livePose', 'longitudinalPlan', 'carState', 'carOutput',
'driverMonitoringState', 'onroadEvents', 'driverAssistance'], poll='selfdriveState')
self.pm = messaging.PubMaster(['carControl', 'controlsState'])
self.pm = messaging.PubMaster(['carControl', 'controlsState', 'dpControlsState'])
self.steer_limited_by_controls = False
self.curvature = 0.0
@@ -57,6 +57,9 @@ class Controls:
elif self.CP.lateralTuning.which() == 'torque':
self.LaC = LatControlTorque(self.CP, self.CI)
self.alka_enabled = self.params.get_bool("dp_lat_alka")
self.alka_active = False
def update(self):
self.sm.update(15)
if self.sm.updated["liveCalibration"]:
@@ -92,7 +95,9 @@ class Controls:
# Check which actuators can be enabled
standstill = abs(CS.vEgo) <= max(self.CP.minSteerSpeed, 0.3) or CS.standstill
CC.latActive = self.sm['selfdriveState'].active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \
self.alka_active = self.alka_enabled and CS.cruiseState.available and not standstill and CS.gearShifter != car.CarState.GearShifter.reverse
lat_active = self.sm['selfdriveState'].active or self.alka_active
CC.latActive = lat_active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \
(not standstill or self.CP.steerAtStandstill)
CC.longActive = CC.enabled and not any(e.overrideLongitudinal for e in self.sm['onroadEvents']) and self.CP.openpilotLongitudinalControl
@@ -175,6 +180,13 @@ class Controls:
# TODO: both controlsState and carControl valids should be set by
# sm.all_checks(), but this creates a circular dependency
# dpControlsState
dat = messaging.new_message('dpControlsState')
dat.valid = True
ncs = dat.dpControlsState
ncs.alkaActive = self.alka_active
self.pm.send('dpControlsState', dat)
# controlsState
dat = messaging.new_message('controlsState')
dat.valid = CS.canValid

View File

@@ -1,6 +1,7 @@
from cereal import log
from openpilot.common.constants import CV
from openpilot.common.realtime import DT_MDL
import time
LaneChangeState = log.LaneChangeState
LaneChangeDirection = log.LaneChangeDirection
@@ -31,7 +32,7 @@ DESIRES = {
class DesireHelper:
def __init__(self):
def __init__(self, dp_lat_lca_speed=LANE_CHANGE_SPEED_MIN, dp_lat_lca_auto_sec=0.):
self.lane_change_state = LaneChangeState.off
self.lane_change_direction = LaneChangeDirection.none
self.lane_change_timer = 0.0
@@ -39,20 +40,26 @@ class DesireHelper:
self.keep_pulse_timer = 0.0
self.prev_one_blinker = False
self.desire = log.Desire.none
self.dp_lat_lca_speed = float(dp_lat_lca_speed * CV.MPH_TO_MS)
self.dp_lat_lca_auto_sec = dp_lat_lca_auto_sec
self.dp_lat_lca_auto_sec_start = 0.
def update(self, carstate, lateral_active, lane_change_prob):
def update(self, carstate, lateral_active, lane_change_prob, left_edge_detected, right_edge_detected):
v_ego = carstate.vEgo
one_blinker = carstate.leftBlinker != carstate.rightBlinker
below_lane_change_speed = v_ego < LANE_CHANGE_SPEED_MIN
below_lane_change_speed = True if self.dp_lat_lca_speed == 0. else v_ego < self.dp_lat_lca_speed
if not lateral_active or self.lane_change_timer > LANE_CHANGE_TIME_MAX:
self.lane_change_state = LaneChangeState.off
self.lane_change_direction = LaneChangeDirection.none
else:
# LaneChangeState.off
c_time = time.monotonic()
if self.lane_change_state == LaneChangeState.off and one_blinker and not self.prev_one_blinker and not below_lane_change_speed:
self.lane_change_state = LaneChangeState.preLaneChange
self.lane_change_ll_prob = 1.0
if self.dp_lat_lca_auto_sec > 0.:
self.dp_lat_lca_auto_sec_start = c_time
# LaneChangeState.preLaneChange
elif self.lane_change_state == LaneChangeState.preLaneChange:
@@ -64,8 +71,16 @@ class DesireHelper:
((carstate.steeringTorque > 0 and self.lane_change_direction == LaneChangeDirection.left) or
(carstate.steeringTorque < 0 and self.lane_change_direction == LaneChangeDirection.right))
blindspot_detected = ((carstate.leftBlindspot and self.lane_change_direction == LaneChangeDirection.left) or
(carstate.rightBlindspot and self.lane_change_direction == LaneChangeDirection.right))
blindspot_detected = (((carstate.leftBlindspot or left_edge_detected) and self.lane_change_direction == LaneChangeDirection.left) or
((carstate.rightBlindspot or right_edge_detected) and self.lane_change_direction == LaneChangeDirection.right))
# reset timer
if self.dp_lat_lca_auto_sec > 0.:
if blindspot_detected:
self.dp_lat_lca_auto_sec_start = c_time
else:
if (c_time - self.dp_lat_lca_auto_sec_start) >= self.dp_lat_lca_auto_sec:
torque_applied = True
if not one_blinker or below_lane_change_speed:
self.lane_change_state = LaneChangeState.off

View File

@@ -14,6 +14,8 @@ from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDX
from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, get_accel_from_plan
from openpilot.selfdrive.car.cruise import V_CRUISE_MAX, V_CRUISE_UNSET
from openpilot.common.swaglog import cloudlog
from dragonpilot.selfdrive.controls.lib.acm import ACM
from dragonpilot.selfdrive.controls.lib.aem import AEM
LON_MPC_STEP = 0.2 # first step is 0.2s
A_CRUISE_MAX_VALS = [1.6, 1.2, 0.8, 0.6]
@@ -27,6 +29,9 @@ _A_TOTAL_MAX_V = [1.7, 3.2]
_A_TOTAL_MAX_BP = [20., 40.]
class DPFlags:
ACM = 1
ACM_DOWNHILL = 2 ** 1
AEM = 2 ** 2
pass
def get_max_accel(v_ego):
@@ -70,6 +75,8 @@ class LongitudinalPlanner:
self.a_desired_trajectory = np.zeros(CONTROL_N)
self.j_desired_trajectory = np.zeros(CONTROL_N)
self.solverExecutionTime = 0.0
self.acm = ACM()
self.aem = AEM()
@staticmethod
def parse_model(model_msg):
@@ -92,7 +99,39 @@ class LongitudinalPlanner:
return x, v, a, j, throttle_prob
def update(self, sm, dp_flags = 0):
mode = 'blended' if sm['selfdriveState'].experimentalMode else 'acc'
v_ego = sm['carState'].vEgo
# --- Calculate current cycle variables needed by AEM ---
x, v, a, j, throttle_prob = self.parse_model(sm['modelV2'])
# Don't clip at low speeds since throttle_prob doesn't account for creep
self.allow_throttle = throttle_prob > ALLOW_THROTTLE_THRESHOLD or v_ego <= MIN_ALLOW_THROTTLE_SPEED
# --- AEM Logic: Determine MPC mode ---
if sm['selfdriveState'].experimentalMode:
mode = 'blended'
else:
mode = 'acc'
if (dp_flags & DPFlags.AEM) and not self.aem.enabled:
self.aem.enabled = True
if self.aem.enabled:
steer_angle_without_offset = sm['carState'].steeringAngleDeg - sm['liveParameters'].angleOffsetDeg
model_path_plan_for_aem = {'x': x, 'v': v, 'a': a, 'j': j}
current_cycle_mode = self.aem.get_mode(
v_ego_raw=v_ego,
lead_one_data_raw=sm['radarState'].leadOne,
steering_angle_deg_raw=steer_angle_without_offset,
standstill_raw=sm['carState'].standstill,
long_personality=self.aem.personality,
allow_throttle_planner=self.allow_throttle,
model_path_plan_raw=model_path_plan_for_aem,
a_target_from_prev_cycle=self.output_a_target,
model_predicts_stop_prev=self.output_should_stop,
fcw_active_prev=self.fcw,
)
mode = current_cycle_mode
if len(sm['carControl'].orientationNED) == 3:
accel_coast = get_coast_accel(sm['carControl'].orientationNED[1])
@@ -112,6 +151,20 @@ class LongitudinalPlanner:
# PCM cruise speed may be updated a few cycles later, check if initialized
reset_state = reset_state or not v_cruise_initialized
# Update ACM status
if not sm['selfdriveState'].experimentalMode:
if not self.acm.enabled and dp_flags & DPFlags.ACM:
self.acm.enabled = True
self.acm.downhill_only = bool(dp_flags & DPFlags.ACM_DOWNHILL)
else:
self.acm.enabled = False
user_control = long_control_off if self.CP.openpilotLongitudinalControl else not sm['selfdriveState'].enabled
self.acm.update_states(sm['carControl'], sm['radarState'], user_control, v_ego, v_cruise)
if self.acm.just_disabled:
reset_state = True
# No change cost when user is controlling the speed, or when standstill
prev_accel_constraint = not (reset_state or sm['carState'].standstill)
@@ -129,9 +182,10 @@ class LongitudinalPlanner:
# Prevent divergence, smooth in current v_ego
self.v_desired_filter.x = max(0.0, self.v_desired_filter.update(v_ego))
x, v, a, j, throttle_prob = self.parse_model(sm['modelV2'])
# Don't clip at low speeds since throttle_prob doesn't account for creep
self.allow_throttle = throttle_prob > ALLOW_THROTTLE_THRESHOLD or v_ego <= MIN_ALLOW_THROTTLE_SPEED
# AEM - move to top so it can access them
# x, v, a, j, throttle_prob = self.parse_model(sm['modelV2'])
# # Don't clip at low speeds since throttle_prob doesn't account for creep
# self.allow_throttle = throttle_prob > ALLOW_THROTTLE_THRESHOLD or v_ego <= MIN_ALLOW_THROTTLE_SPEED
if not self.allow_throttle:
clipped_accel_coast = max(accel_coast, accel_clip[0])
@@ -141,14 +195,18 @@ class LongitudinalPlanner:
if force_slow_decel:
v_cruise = 0.0
self.mpc.set_weights(prev_accel_constraint, personality=sm['selfdriveState'].personality)
self.aem.set_personality(v_ego, sm['selfdriveState'].personality)
self.mpc.set_weights(prev_accel_constraint, personality=self.aem.personality)
self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired)
self.mpc.update(sm['radarState'], v_cruise, x, v, a, j, personality=sm['selfdriveState'].personality)
self.mpc.update(sm['radarState'], v_cruise, x, v, a, j, personality=self.aem.personality)
self.v_desired_trajectory = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC, self.mpc.v_solution)
self.a_desired_trajectory = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC, self.mpc.a_solution)
self.j_desired_trajectory = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC[:-1], self.mpc.j_solution)
# Apply ACM post-processing to the acceleration trajectory if active
self.a_desired_trajectory = self.acm.update_a_desired_trajectory(self.a_desired_trajectory)
# TODO counter is only needed because radar is glitchy, remove once radar is gone
self.fcw = self.mpc.crash_cnt > 2 and not sm['carState'].standstill
if self.fcw:
@@ -172,6 +230,9 @@ class LongitudinalPlanner:
output_a_target = min(output_a_target_mpc, output_a_target_e2e)
self.output_should_stop = output_should_stop_e2e or output_should_stop_mpc
# Apply ACM to the final output acceleration target as well
output_a_target = self.acm.update_output_a_target(output_a_target)
for idx in range(2):
accel_clip[idx] = np.clip(accel_clip[idx], self.prev_accel_clip[idx] - 0.05, self.prev_accel_clip[idx] + 0.05)
self.output_a_target = np.clip(output_a_target, accel_clip[0], accel_clip[1])

View File

@@ -23,7 +23,12 @@ def main():
poll='modelV2')
dp_flags = 0
if params.get_bool("dp_lon_acm"):
dp_flags |= DPFlags.ACM
if params.get_bool("dp_lon_acm_downhill"):
dp_flags |= DPFlags.ACM_DOWNHILL
if params.get_bool("dp_lon_aem"):
dp_flags |= DPFlags.AEM
while True:
sm.update()
if sm.updated['modelV2']:

View File

@@ -30,6 +30,7 @@ from openpilot.selfdrive.modeld.fill_model_msg import fill_model_msg, fill_pose_
from openpilot.selfdrive.modeld.constants import ModelConstants, Plan
from openpilot.selfdrive.modeld.models.commonmodel_pyx import DrivingModelFrame, CLContext
from openpilot.selfdrive.modeld.runners.tinygrad_helpers import qcom_tensor_from_opencl_address
from dragonpilot.selfdrive.controls.lib.road_edge_detector import RoadEdgeDetector
PROCESS_NAME = "selfdrive.modeld.modeld"
@@ -220,7 +221,7 @@ def main(demo=False):
cloudlog.warning(f"connected extra cam with buffer size: {vipc_client_extra.buffer_len} ({vipc_client_extra.width} x {vipc_client_extra.height})")
# messaging
pm = PubMaster(["modelV2", "drivingModelData", "cameraOdometry"])
pm = PubMaster(["modelV2", "drivingModelData", "cameraOdometry", "modelExt"])
sm = SubMaster(["deviceState", "carState", "roadCameraState", "liveCalibration", "driverMonitoringState", "carControl", "liveDelay"])
publish_state = PublishState()
@@ -251,7 +252,10 @@ def main(demo=False):
long_delay = CP.longitudinalActuatorDelay + LONG_SMOOTH_SECONDS
prev_action = log.ModelDataV2.Action()
DH = DesireHelper()
dp_lat_lca_speed = int(params.get("dp_lat_lca_speed"))
dp_lat_lca_auto_sec = float(params.get("dp_lat_lca_auto_sec"))
DH = DesireHelper(dp_lat_lca_speed=dp_lat_lca_speed, dp_lat_lca_auto_sec=dp_lat_lca_auto_sec)
RED = RoadEdgeDetector(params.get_bool("dp_lat_road_edge_detection"))
while True:
# Keep receiving frames until we are at least 1 frame ahead of previous extra frame
@@ -337,6 +341,7 @@ def main(demo=False):
modelv2_send = messaging.new_message('modelV2')
drivingdata_send = messaging.new_message('drivingModelData')
posenet_send = messaging.new_message('cameraOdometry')
model_ext_send = messaging.new_message('modelExt')
action = get_action_from_model(model_output, prev_action, lat_delay + DT_MDL, long_delay + DT_MDL, v_ego)
prev_action = action
@@ -348,7 +353,10 @@ def main(demo=False):
l_lane_change_prob = desire_state[log.Desire.laneChangeLeft]
r_lane_change_prob = desire_state[log.Desire.laneChangeRight]
lane_change_prob = l_lane_change_prob + r_lane_change_prob
DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob)
RED.update(modelv2_send.modelV2.roadEdgeStds, modelv2_send.modelV2.laneLineProbs)
model_ext_send.modelExt.leftEdgeDetected = RED.left_edge_detected
model_ext_send.modelExt.rightEdgeDetected = RED.right_edge_detected
DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob, RED.left_edge_detected, RED.right_edge_detected)
modelv2_send.modelV2.meta.laneChangeState = DH.lane_change_state
modelv2_send.modelV2.meta.laneChangeDirection = DH.lane_change_direction
drivingdata_send.drivingModelData.meta.laneChangeState = DH.lane_change_state
@@ -358,6 +366,7 @@ def main(demo=False):
pm.send('modelV2', modelv2_send)
pm.send('drivingModelData', drivingdata_send)
pm.send('cameraOdometry', posenet_send)
pm.send('modelExt', model_ext_send)
last_vipc_frame_id = meta_main.frame_id

View File

@@ -0,0 +1,142 @@
#!/usr/bin/env python3
import time
import cereal.messaging as messaging
from openpilot.common.params import Params
from openpilot.common.realtime import config_realtime_process, Ratekeeper, DT_DMON
from cereal import log
EventName = log.OnroadEvent.EventName
class SimpleDriverMonitoring:
def __init__(self):
# Timing configuration (in seconds)
self.FIRST_WARNING_TIME = 45.0
self.SECOND_WARNING_TIME = 60.0
self.THIRD_WARNING_TIME = 75.0
# State variables
self.awareness = 1.0 # Full awareness
self.current_events = []
# self.last_interaction_time = 0
self.hands_on_steering = False
# Warning thresholds (normalized to 0-1 scale)
self.threshold_prompt = self.FIRST_WARNING_TIME / self.THIRD_WARNING_TIME # ~0.643 for first warning
self.threshold_critical = self.SECOND_WARNING_TIME / self.THIRD_WARNING_TIME # ~0.857 for second warning
# Step change (how much awareness decreases per step)
self.step_change = DT_DMON / self.THIRD_WARNING_TIME
params = Params()
self.is_rhd = params.get_bool("dp_device_is_rhd")
self.monitoring_disabled = params.get_bool("dp_device_monitoring_disabled")
def update_events(self, reset_condition, op_engaged):
self.current_events = []
if self.monitoring_disabled:
return
# If not engaged, reset awareness and return
if not op_engaged:
self.awareness = 1.0
return
# Reset awareness on any reset condition (standstill, any input)
if reset_condition:
self.awareness = 1.0
return
# Only decrease awareness if we're not detecting hands on steering
self.awareness = max(self.awareness - self.step_change, 0.0)
# Determine alert level based on awareness
if self.awareness <= 0.0:
# Third warning (red alert) at 70 seconds
self.current_events.append(EventName.driverUnresponsive)
elif self.awareness <= (1.0 - self.threshold_critical):
# Second warning (orange alert) at 60 seconds
self.current_events.append(EventName.promptDriverUnresponsive)
elif self.awareness <= (1.0 - self.threshold_prompt):
# First warning (green alert) at 45 seconds
self.current_events.append(EventName.preDriverUnresponsive)
def get_state_packet(self, valid=True):
# Create driver monitoring state message
dat = messaging.new_message('driverMonitoringState', valid=valid)
events = []
for event_name in self.current_events:
event = log.OnroadEvent.new_message()
event.name = event_name
events.append(event)
dat.driverMonitoringState = {
"events": events,
"faceDetected": False, # Not using face detection
"isDistracted": self.awareness <= (1.0 - self.threshold_prompt),
"distractedType": 0, # Not using distraction types
"awarenessStatus": 1.0, #self.awareness, (always 1.0 so no decel)
"posePitchOffset": 0.0,
"posePitchValidCount": 0,
"poseYawOffset": 0.0,
"poseYawValidCount": 0,
"stepChange": self.step_change,
"awarenessActive": self.awareness,
"awarenessPassive": self.awareness,
"isLowStd": True,
"hiStdCount": 0,
"isActiveMode": True,
"isRHD": self.is_rhd,
}
return dat
def dmonitoringd_thread():
# Configure process priority
config_realtime_process([0, 1, 2, 3], 5)
# Initialize parameters and messaging
pm = messaging.PubMaster(['driverMonitoringState'])
sm = messaging.SubMaster(['carState', 'selfdriveState'])
# Initialize driver monitoring system
DM = SimpleDriverMonitoring()
# Create ratekeeper for 20Hz operation
rk = Ratekeeper(20, None)
# Main loop running at 20Hz
while True:
sm.update()
# Check if steering is touched (only monitoring steering for hands-on)
# Reset conditions: not engaged, standstill, or any input
reset_condition = (
sm['carState'].standstill or
sm['carState'].steeringPressed or
sm['carState'].gasPressed or
sm['carState'].brakePressed or
sm['carState'].leftBlinker or
sm['carState'].rightBlinker
)
# Process driver monitoring - monitoring only steering for hands-on
# but resetting on any input
DM.update_events(
reset_condition=reset_condition,
op_engaged=sm['selfdriveState'].enabled
)
# Publish driver monitoring state
dat = DM.get_state_packet()
pm.send('driverMonitoringState', dat)
# Maintain 20Hz
rk.keep_time()
def main():
dmonitoringd_thread()
if __name__ == '__main__':
main()

View File

@@ -372,6 +372,7 @@ void process_peripheral_state(Panda *panda, PubMaster *pm, bool no_fan_control)
static uint16_t prev_fan_speed = 999;
static int ir_pwr = 0;
static int prev_ir_pwr = 999;
const bool lite = getenv("LITE");
static FirstOrderFilter integ_lines_filter(0, 30.0, 0.05);
@@ -386,7 +387,7 @@ void process_peripheral_state(Panda *panda, PubMaster *pm, bool no_fan_control)
}
}
if (sm.updated("driverCameraState")) {
if (!lite && sm.updated("driverCameraState")) {
auto event = sm["driverCameraState"];
int cur_integ_lines = event.getDriverCameraState().getIntegLines();
@@ -403,14 +404,14 @@ void process_peripheral_state(Panda *panda, PubMaster *pm, bool no_fan_control)
}
// Disable IR on input timeout
if (nanos_since_boot() - last_driver_camera_t > 1e9) {
if (!lite && nanos_since_boot() - last_driver_camera_t > 1e9) {
ir_pwr = 0;
}
if (ir_pwr != prev_ir_pwr || sm.frame % 100 == 0) {
int16_t ir_panda = util::map_val(ir_pwr, 0, 100, 0, MAX_IR_PANDA_VAL);
int16_t ir_panda = util::map_val(ir_pwr, 0, 100, 0, MAX_IR_PANDA_VAL);
panda->set_ir_pwr(ir_panda);
Hardware::set_ir_power(ir_pwr);
Hardware::set_ir_power(ir_pwr);
prev_ir_pwr = ir_pwr;
}
}

View File

@@ -23,6 +23,7 @@ from openpilot.selfdrive.selfdrived.alertmanager import AlertManager, set_offroa
from openpilot.system.hardware import HARDWARE
from openpilot.system.version import get_build_metadata
from opendbc.safety import ALTERNATIVE_EXPERIENCE
REPLAY = "REPLAY" in os.environ
SIMULATION = "SIMULATION" in os.environ
@@ -58,6 +59,8 @@ class SelfdriveD:
self.car_events = CarSpecificEvents(self.CP)
self.alka = bool(self.CP.alternativeExperience & ALTERNATIVE_EXPERIENCE.ALKA)
self.pose_calibrator = PoseCalibrator()
self.calibrated_pose: Pose | None = None
self.excessive_actuation_check = ExcessiveActuationCheck()
@@ -74,16 +77,18 @@ class SelfdriveD:
# TODO: de-couple selfdrived with card/conflate on carState without introducing controls mismatches
self.car_state_sock = messaging.sub_sock('carState', timeout=20)
ignore = self.sensor_packets + self.gps_packets + ['alertDebug']
ignore = self.sensor_packets + self.gps_packets + ['alertDebug'] + ['modelExt']
if SIMULATION:
ignore += ['driverCameraState', 'managerState']
if REPLAY:
# no vipc in replay will make them ignored anyways
ignore += ['roadCameraState', 'wideRoadCameraState']
if os.getenv("DISABLE_DRIVER") or os.getenv("LITE"):
ignore += ['driverCameraState']
self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration',
'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', 'liveDelay',
'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters',
'controlsState', 'carControl', 'driverAssistance', 'alertDebug', 'userBookmark', 'audioFeedback'] + \
'controlsState', 'carControl', 'driverAssistance', 'alertDebug', 'userBookmark', 'audioFeedback', 'modelExt'] + \
self.camera_packets + self.sensor_packets + self.gps_packets,
ignore_alive=ignore, ignore_avg_freq=ignore,
ignore_valid=ignore, frequency=int(1/DT_CTRL))
@@ -119,7 +124,7 @@ class SelfdriveD:
self.experimental_mode = False
self.personality = self.params.get("LongitudinalPersonality", return_default=True)
self.recalibrating_seen = False
self.state_machine = StateMachine()
self.state_machine = StateMachine(self.alka)
self.rk = Ratekeeper(100, print_delay_threshold=None)
# some comma three with NVMe experience NVMe dropouts mid-drive that
@@ -261,8 +266,8 @@ class SelfdriveD:
# Handle lane change
if self.sm['modelV2'].meta.laneChangeState == LaneChangeState.preLaneChange:
direction = self.sm['modelV2'].meta.laneChangeDirection
if (CS.leftBlindspot and direction == LaneChangeDirection.left) or \
(CS.rightBlindspot and direction == LaneChangeDirection.right):
if ((CS.leftBlindspot or self.sm['modelExt'].leftEdgeDetected) and direction == LaneChangeDirection.left) or \
((CS.rightBlindspot or self.sm['modelExt'].rightEdgeDetected) and direction == LaneChangeDirection.right):
self.events.add(EventName.laneChangeBlocked)
else:
if direction == LaneChangeDirection.left:

View File

@@ -9,10 +9,11 @@ ACTIVE_STATES = (State.enabled, State.softDisabling, State.overriding)
ENABLED_STATES = (State.preEnabled, *ACTIVE_STATES)
class StateMachine:
def __init__(self):
def __init__(self, alka = False):
self.current_alert_types = [ET.PERMANENT]
self.state = State.disabled
self.soft_disable_timer = 0
self.alka = alka
def update(self, events: Events):
# decrement the soft disable timer at every step, as it's reset on
@@ -92,7 +93,7 @@ class StateMachine:
# Check if openpilot is engaged and actuators are enabled
enabled = self.state in ENABLED_STATES
active = self.state in ACTIVE_STATES
if active:
if active or self.alka:
self.current_alert_types.append(ET.WARNING)
return enabled, active

View File

@@ -26,6 +26,7 @@ Export('widgets')
qt_libs = [widgets, qt_util] + base_libs
qt_src = ["main.cc", "ui.cc", "qt/sidebar.cc", "qt/body.cc",
"qt/offroad/model_selector.cc",
"qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc",
"qt/offroad/software_settings.cc", "qt/offroad/developer_panel.cc", "qt/offroad/onboarding.cc", "qt/offroad/dp_panel.cc",
"qt/offroad/driverview.cc", "qt/offroad/experimental_mode.cc", "qt/offroad/firehose.cc",

View File

@@ -106,7 +106,19 @@ void DPPanel::add_lateral_toggles() {
QString::fromUtf8("🐉 ") + tr("Lateral Ctrl"),
"",
},
{
"dp_lat_alka",
tr("Always-on Lane Keeping Assist (ALKA)"),
"",
},
{
"dp_lat_road_edge_detection",
tr("Road Edge Detection (RED)"),
tr("Block lane change assist when the system detects the road edge.\nNOTE: This will show 'Car Detected in Blindspot' warning.")
},
};
auto lca_speed_toggle = new ParamSpinBoxControl("dp_lat_lca_speed", tr("LCA Speed:"), tr("Off = Disable LCA\n1 mph ≈ 1.2 km/h"), "", 0, 100, 5, tr(" mph"), tr("Off"));
lca_sec_toggle = new ParamDoubleSpinBoxControl("dp_lat_lca_auto_sec", QString::fromUtf8(" ") + tr("Auto Lane Change after:"), tr("Off = Disable Auto Lane Change."), "", 0, 5.0, 0.5, tr(" sec"), tr("Off"));
QWidget *label = nullptr;
bool has_toggle = false;
@@ -115,6 +127,9 @@ void DPPanel::add_lateral_toggles() {
if (param.isEmpty()) {
label = new LabelControl(title, "");
addItem(label);
addItem(lca_speed_toggle);
addItem(lca_sec_toggle);
has_toggle = true;
continue;
}
@@ -139,6 +154,26 @@ void DPPanel::add_longitudinal_toggles() {
QString::fromUtf8("🐉 ") + tr("Longitudinal Ctrl"),
"",
},
{
"dp_lon_ext_radar",
tr("Use External Radar"),
tr("See https://github.com/eFiniLan/openpilot-ext-radar-addon for more information."),
},
{
"dp_lon_acm",
QString::fromUtf8("🚧 ") + tr("Enable Adaptive Coasting Mode (ACM)"),
tr("Adaptive Coasting Mode (ACM) reduces braking to allow smoother coasting when appropriate.\nDOES NOT WORK with Experimental Mode enabled."),
},
{
"dp_lon_acm_downhill",
QString::fromUtf8(" ") + tr("Downhill Only"),
tr("Limited to downhill driving."),
},
{
"dp_lon_aem",
QString::fromUtf8("🚧 ") + tr("Adaptive Experimental Mode (AEM)"),
tr("Adaptive mode switcher between ACC and Blended based on driving context."),
},
};
QWidget *label = nullptr;
@@ -150,6 +185,15 @@ void DPPanel::add_longitudinal_toggles() {
addItem(label);
continue;
}
if (param == "dp_lon_ext_radar" && !vehicle_has_radar_unavailable) {
continue;
}
if ((param == "dp_lon_acm" || param == "dp_lon_acm_downhill") && !vehicle_has_long_ctrl) {
continue;
}
if (param == "dp_lon_aem" && !vehicle_has_long_ctrl) {
continue;
}
has_toggle = true;
auto toggle = new ParamControl(param, title, desc, "", this);
@@ -172,7 +216,23 @@ void DPPanel::add_ui_toggles() {
QString::fromUtf8("🐉 ") + tr("UI"),
"",
},
{
"dp_ui_radar_tracks",
tr("Display Radar Tracks"),
"",
},
{
"dp_ui_rainbow",
tr("Rainbow Driving Path like Tesla"),
tr("Why not?"),
},
};
std::vector<QString> display_off_mode_texts{tr("Std."), tr("MAIN+"), tr("OP+"), tr("MAIN-"), tr("OP-")};
ButtonParamControl* display_off_mode_setting = new ButtonParamControl("dp_ui_display_mode", tr("Display Mode"),
tr("Std. - Stock behavior.\nMAIN+ - ACC MAIN on = Display ON.\nOP+ - OP enabled = Display ON.\nMAIN- - ACC MAIN on = Display OFF\nOP- - OP enabled = Display OFF."),
"",
display_off_mode_texts, 200);
auto hide_hud = new ParamSpinBoxControl("dp_ui_hide_hud_speed_kph", tr("Hide HUD When Moves above:"), tr("To prevent screen burn-in, hide Speed, MAX Speed, and Steering/DM Icons when the car moves.\nOff = Stock Behavior\n1 km/h ≈ 0.6 mph"), "", 0, 120, 5, tr(" km/h"), tr("Off"));
QWidget *label = nullptr;
bool has_toggle = false;
@@ -181,6 +241,13 @@ void DPPanel::add_ui_toggles() {
if (param.isEmpty()) {
label = new LabelControl(title, "");
addItem(label);
addItem(display_off_mode_setting);
has_toggle = true;
addItem(hide_hud);
has_toggle = true;
continue;
}
if (param == "dp_ui_radar_tracks" && !vehicle_has_long_ctrl) {
continue;
}
@@ -205,15 +272,56 @@ void DPPanel::add_device_toggles() {
QString::fromUtf8("🐉 ") + tr("Device"),
"",
},
{
"dp_device_is_rhd",
tr("Enable Right-Hand Drive Mode"),
tr("Allow openpilot to obey right-hand traffic conventions on right driver seat."),
},
{
"dp_device_monitoring_disabled",
tr("Disable Driver Monitoring"),
"",
},
{
"dp_device_beep",
tr("Enable Beep (Warning)"),
"",
}
};
std::vector<QString> audible_alert_mode_texts{tr("Std."), tr("Warning"), tr("Off")};
ButtonParamControl* audible_alert_mode_setting = new ButtonParamControl("dp_device_audible_alert_mode", tr("Audible Alert Mode"),
tr("Warning - Only emits sound when there is a warning.\nOff - Does not emit any sound at all."),
"",
audible_alert_mode_texts);
auto auto_shutdown_toggle = new ParamSpinBoxControl("dp_device_auto_shutdown_in", tr("Auto Shutdown In:"), tr("0 mins = Immediately"), "", -5, 300, 5, tr(" mins"), tr("Off"));
std::vector<QString> dashy_mode_texts{tr("Off"), tr("Lite"), tr("Full")};
ButtonParamControl* dashy_mode_settings = new ButtonParamControl("dp_dev_dashy", tr("dashy"),
tr("dashy - dragonpilot's all-in-one system hub for you.\n\nVisit http://<device_ip>:5088 to access.\n\nOff - Turn off dashy completely.\nLite: File Manager only.\nFull: File Manager + Live Stream."),
"",
dashy_mode_texts);
auto delay_loggerd_toggle = new ParamSpinBoxControl("dp_dev_delay_loggerd", tr("Delay Starting Loggerd for:"), tr("Delays the startup of loggerd and its related processes when the device goes on-road.\nThis prevents the initial moments of a drive from being recorded, protecting location privacy at the start of a trip."), "", 0, 300, 5, tr(" secs"), tr("Off"));
QWidget *label = nullptr;
bool has_toggle = false;
const bool lite = getenv("LITE");
for (auto &[param, title, desc] : toggle_defs) {
if (param.isEmpty()) {
label = new LabelControl(title, "");
addItem(label);
addItem(auto_shutdown_toggle);
has_toggle = true;
addItem(dashy_mode_settings);
has_toggle = true;
addItem(delay_loggerd_toggle);
has_toggle = true;
continue;
}
if ((param == "dp_device_is_rhd" || param == "dp_device_monitoring_disabled" || param == "dp_device_beep") && !lite) {
continue;
}
@@ -224,6 +332,10 @@ void DPPanel::add_device_toggles() {
addItem(toggle);
toggles[param.toStdString()] = toggle;
}
if (!getenv("DISABLE_DRIVER")) { // lite check
addItem(audible_alert_mode_setting);
has_toggle = true;
}
// If no toggles were added, hide the label
if (!has_toggle && label) {
@@ -281,12 +393,19 @@ void DPPanel::showEvent(QShowEvent *event) {
void DPPanel::updateStates() {
// do fs_watch here
fs_watch->addParam("dp_lat_lca_speed");
fs_watch->addParam("dp_lon_ext_radar");
fs_watch->addParam("dp_lon_acm");
if (!isVisible()) {
return;
}
// do state change logic here
lca_sec_toggle->setVisible(std::atoi(params.get("dp_lat_lca_speed").c_str()) > 0);
if (vehicle_has_long_ctrl) {
toggles["dp_lon_acm_downhill"]->setVisible(params.getBool("dp_lon_acm"));
}
}

View File

@@ -28,4 +28,6 @@ private:
void add_device_toggles();
void updateStates();
void showEvent(QShowEvent *event) override;
ParamDoubleSpinBoxControl* lca_sec_toggle;
};

View File

@@ -0,0 +1,230 @@
/*
Copyright (c) 2025 Rick Lan
This software is licensed under the Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License (CC BY-NC-SA 4.0).
You are free to share and adapt this work for non-commercial purposes, provided you give appropriate credit and distribute any modifications under the same license.
To view a copy of this license, visit:
http://creativecommons.org/licenses/by-nc-sa/4.0/
---
**Commercial Licensing:**
Use of this software for commercial purposes is strictly prohibited without a separate, paid license.
To purchase a commercial license, please contact ricklan@gmail.com.
*/
#include "selfdrive/ui/qt/offroad/model_selector.h"
// Define style constants to improve maintainability
namespace {
const QString SELECTOR_BTN_STYLE = "background-color: #00309a; font-size: 48px;";
const QString MODEL_LIST_STYLE = "font-size: 64px;";
const QString SCROLLBAR_STYLE = "width: 96px;";
const QString GROUP_HEADER_BG_COLOR = "#c8c8c8"; // Light gray
const QString GROUP_HEADER_TEXT_COLOR = "#000000"; // Black
// Role for storing the actual model name without indentation
const int ModelNameRole = Qt::UserRole;
}
ModelSelector::ModelSelector(QWidget *parent) : QWidget(parent) {
setupUI();
setupModelListPanel();
connectSignals();
}
QWidget* ModelSelector::setupUI() {
QVBoxLayout* main_layout = new QVBoxLayout(this);
main_layout->addSpacing(10);
// Selector button
QWidget* model_selector_btn_widget = new QWidget;
QHBoxLayout* model_selector_btn_layout = new QHBoxLayout();
QLabel* vehicle_model_label = new QLabel(tr("Vehicle Model:"));
vehicle_model_label->setStyleSheet("margin-right: 2px; font-size: 48px;");
model_selector_btn_layout->addWidget(vehicle_model_label);
QString model_selected = QString::fromUtf8(Params().get("dp_device_model_selected").c_str());
model_selector_btn = new QPushButton(model_selected.isEmpty() ? tr("[AUTO DETECT]") : model_selected);
model_selector_btn->setObjectName("ModelSelectorBtn");
model_selector_btn->setStyleSheet(SELECTOR_BTN_STYLE);
model_selector_btn_layout->addWidget(model_selector_btn);
model_selector_btn_layout->setAlignment(Qt::AlignCenter);
model_selector_btn_layout->setStretch(1, 1);
model_selector_btn_widget->setLayout(model_selector_btn_layout);
main_layout->addWidget(model_selector_btn_widget);
main_layout->addSpacing(10);
main_layout->addStretch(); // Add stretch to push everything to the top
setLayout(main_layout);
return model_selector_btn_widget;
}
void ModelSelector::setupModelListPanel() {
// Create model list panel
model_list_panel = new QWidget();
QVBoxLayout* model_list_layout = new QVBoxLayout(model_list_panel);
model_list_layout->setContentsMargins(50, 25, 50, 25);
model_list = new QListWidget(model_list_panel);
// Set styles using the constants
QString listStyle = QString("QListWidget { %1 } QScrollBar:vertical { %2 }")
.arg(MODEL_LIST_STYLE)
.arg(SCROLLBAR_STYLE);
model_list->setStyleSheet(listStyle);
model_list->setFixedHeight(750);
model_list_layout->addWidget(model_list);
model_list_frame = new ScrollView(model_list_panel, nullptr);
}
void ModelSelector::loadModelList() {
if (model_list->count() > 0) {
// If list is already populated, just update the selection
updateCurrentSelection();
return;
}
// Add auto-detect option
QListWidgetItem* autoDetectItem = new QListWidgetItem(tr("[AUTO DETECT]"));
autoDetectItem->setData(ModelNameRole, tr("[AUTO DETECT]"));
model_list->addItem(autoDetectItem);
Params params;
QString model_list_str = QString::fromStdString(params.get("dp_device_model_list"));
QJsonDocument document = QJsonDocument::fromJson(model_list_str.toUtf8());
if (document.isArray()) {
QJsonArray models = document.array();
for (const auto& groupValue : models) {
QJsonObject group = groupValue.toObject();
QString groupName = group["group"].toString();
// Add group header item
QListWidgetItem* groupHeader = new QListWidgetItem(groupName);
groupHeader->setFlags(Qt::NoItemFlags); // Make non-selectable
groupHeader->setBackground(QColor(GROUP_HEADER_BG_COLOR));
groupHeader->setForeground(QColor(GROUP_HEADER_TEXT_COLOR));
groupHeader->setTextAlignment(Qt::AlignCenter);
model_list->addItem(groupHeader);
// Add models in this group
QJsonArray groupModels = group["models"].toArray();
for (const auto& model : groupModels) {
QString modelName = model.toString();
// Create item with visual indentation
QListWidgetItem* modelItem = new QListWidgetItem(" " + modelName);
// Store actual model name without indentation in user role
modelItem->setData(ModelNameRole, modelName);
model_list->addItem(modelItem);
}
}
}
// Set the current selection after loading
updateCurrentSelection();
}
// New helper method to update the selection
void ModelSelector::updateCurrentSelection() {
// Get the currently selected model from params
Params params;
QString currentModel = QString::fromStdString(params.get("dp_device_model_selected"));
// If empty, select the AUTO DETECT option
if (currentModel.isEmpty()) {
model_list->setCurrentRow(0); // AUTO DETECT is the first item
return;
}
// Otherwise, find and select the matching model
for (int i = 0; i < model_list->count(); i++) {
QListWidgetItem* item = model_list->item(i);
// Only check selectable items (not group headers)
if (item->flags() & Qt::ItemIsSelectable) {
QString modelName = item->data(ModelNameRole).toString();
if (modelName == currentModel) {
model_list->setCurrentItem(item);
break;
}
}
}
}
void ModelSelector::clearModelList() {
model_list->clear();
}
void ModelSelector::updateButtonText(const QString& text) {
model_selector_btn->setText(text);
}
QWidget* ModelSelector::getModelListPanel() {
return model_list_frame;
}
void ModelSelector::setPanelWidget(QStackedWidget* panel) {
panel_widget = panel;
if (panel_widget && model_list_frame->parent() != panel_widget) {
model_list_frame->setParent(panel_widget);
panel_widget->addWidget(model_list_frame);
}
}
void ModelSelector::setNavButtonGroup(QButtonGroup* buttons) {
nav_btns = buttons;
}
void ModelSelector::connectSignals() {
connect(model_selector_btn, &QPushButton::clicked, [this]() {
if (panel_widget) {
// Load the model list when needed
loadModelList();
panel_widget->setCurrentWidget(model_list_frame);
}
emit buttonClicked();
});
connect(model_list, &QListWidget::itemClicked, [this](QListWidgetItem* item) {
// Only process clicks on selectable items (not group headers)
if (item->flags() & Qt::ItemIsSelectable) {
// Get model name from the data role rather than trimming text
QString model_name = item->data(ModelNameRole).toString();
QString param_value = (model_name == tr("[AUTO DETECT]")) ? QString() : model_name;
// Update param and button text
Params().put("dp_device_model_selected", param_value.toStdString());
updateButtonText(param_value.isEmpty() ? tr("[AUTO DETECT]") : model_name);
// Emit signal that model was selected
emit modelSelected(model_name);
// Go back to the previous panel
if (nav_btns && nav_btns->checkedButton()) {
nav_btns->checkedButton()->click();
} else if (nav_btns && nav_btns->buttons().size() > 0) {
// Default to first panel if none selected
nav_btns->buttons().first()->click();
}
}
});
if (model_list_frame) {
model_list_frame->installEventFilter(this);
}
}
bool ModelSelector::eventFilter(QObject *obj, QEvent *event) {
if (obj == model_list_frame) {
if (event->type() == QEvent::Hide) {
clearModelList();
}
}
return QWidget::eventFilter(obj, event);
}

View File

@@ -0,0 +1,73 @@
/*
Copyright (c) 2025 Rick Lan
This software is licensed under the Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License (CC BY-NC-SA 4.0).
You are free to share and adapt this work for non-commercial purposes, provided you give appropriate credit and distribute any modifications under the same license.
To view a copy of this license, visit:
http://creativecommons.org/licenses/by-nc-sa/4.0/
---
**Commercial Licensing:**
Use of this software for commercial purposes is strictly prohibited without a separate, paid license.
To purchase a commercial license, please contact ricklan@gmail.com.
*/
#pragma once
#include <QWidget>
#include <QPushButton>
#include <QListWidget>
#include <QVBoxLayout>
#include <QHBoxLayout>
#include <QLabel>
#include <QJsonDocument>
#include <QJsonArray>
#include <QJsonObject>
#include <QListWidgetItem>
#include <QDebug>
#include <QStackedWidget>
#include <QButtonGroup> // Add this include for QButtonGroup
#include <QEvent>
#include "common/params.h"
#include "selfdrive/ui/qt/widgets/scrollview.h"
class ModelSelector : public QWidget {
Q_OBJECT
public:
explicit ModelSelector(QWidget *parent = nullptr);
// Get the model list panel widget
QWidget* getModelListPanel();
// Set the panel widget to switch to when selecting models
void setPanelWidget(QStackedWidget* panel);
// Set the button group to return to after model selection
void setNavButtonGroup(QButtonGroup* nav_btns);
signals:
void buttonClicked();
void modelSelected(const QString& model_name);
private:
QPushButton* model_selector_btn;
QListWidget* model_list;
QWidget* model_list_panel;
ScrollView* model_list_frame;
QStackedWidget* panel_widget = nullptr;
QButtonGroup* nav_btns = nullptr;
QWidget* setupUI();
void setupModelListPanel();
void loadModelList();
void updateCurrentSelection();
void clearModelList();
void connectSignals();
void updateButtonText(const QString& text);
protected:
bool eventFilter(QObject *obj, QEvent *event) override;
};

View File

@@ -16,6 +16,7 @@
#include "selfdrive/ui/qt/offroad/developer_panel.h"
#include "selfdrive/ui/qt/offroad/firehose.h"
#include "selfdrive/ui/qt/offroad/dp_panel.h"
#include "selfdrive/ui/qt/offroad/model_selector.h"
TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) {
// param, title, desc, icon, restart needed
@@ -103,8 +104,11 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) {
// set up uiState update for personality setting
QObject::connect(uiState(), &UIState::uiUpdate, this, &TogglesPanel::updateState);
const bool lite = getenv("LITE");
for (auto &[param, title, desc, icon, needs_restart] : toggle_defs) {
if ((param == "AlwaysOnDM" || param == "RecordFront" || param == "RecordAudio" || param == "RecordAudioFeedback") && lite) {
continue;
}
auto toggle = new ParamControl(param, title, desc, icon, this);
bool locked = params.getBool((param + "Lock").toStdString());
@@ -223,6 +227,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) {
addItem(new LabelControl(tr("Dongle ID"), getDongleId().value_or(tr("N/A"))));
addItem(new LabelControl(tr("Serial"), params.get("HardwareSerial").c_str()));
const bool lite = getenv("LITE");
pair_device = new ButtonControl(tr("Pair Device"), tr("PAIR"),
tr("Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer."));
connect(pair_device, &ButtonControl::clicked, [=]() {
@@ -232,12 +237,12 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) {
addItem(pair_device);
// offroad-only buttons
if (!lite) {
auto dcamBtn = new ButtonControl(tr("Driver Camera"), tr("PREVIEW"),
tr("Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)"));
connect(dcamBtn, &ButtonControl::clicked, [=]() { emit showDriverView(); });
addItem(dcamBtn);
}
resetCalibBtn = new ButtonControl(tr("Reset Calibration"), tr("RESET"), "");
connect(resetCalibBtn, &ButtonControl::showDescriptionEvent, this, &DevicePanel::updateCalibDescription);
connect(resetCalibBtn, &ButtonControl::clicked, [&]() {
@@ -535,7 +540,26 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) {
sidebar_widget->setFixedWidth(500);
main_layout->addWidget(sidebar_widget);
main_layout->addWidget(panel_widget);
// Create right column with model selector on top and panel_widget below
QWidget* right_column = new QWidget(this);
QVBoxLayout* right_layout = new QVBoxLayout(right_column);
right_layout->setContentsMargins(0, 0, 0, 0);
right_layout->setSpacing(20); // Space between model selector and panel
// Create the ModelSelector button at the top of right column
ModelSelector* model_selector = new ModelSelector(this);
right_layout->addWidget(model_selector);
// Set up panel widget and nav button references
model_selector->setPanelWidget(panel_widget);
model_selector->setNavButtonGroup(nav_btns);
// Add panel_widget below the model selector
right_layout->addWidget(panel_widget, 1); // Give panel_widget stretch priority
// Add right column to main layout
main_layout->addWidget(right_column);
setStyleSheet(R"(
* {

View File

@@ -95,6 +95,7 @@ private:
QLabel *onroadLbl;
LabelControl *versionLbl;
ButtonControl *installBtn;
ButtonControl *onOffRoadBtn;
ButtonControl *downloadBtn;
ButtonControl *targetBranchBtn;

View File

@@ -29,6 +29,16 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) {
versionLbl = new LabelControl(tr("Current Version"), "");
addItem(versionLbl);
// on/off road mode switch
onOffRoadBtn = new ButtonControl(tr("Onroad/Offroad Mode"), tr("Go Offroad"));
connect(onOffRoadBtn, &ButtonControl::clicked, [&]() {
if (ConfirmationDialog::confirm(tr("Are you sure you want to switch mode?"), tr("CONFIRM"), this)) {
bool val = params.getBool("dp_device_go_off_road");
params.putBool("dp_device_go_off_road", !val);
}
});
addItem(onOffRoadBtn);
// download update btn
downloadBtn = new ButtonControl(tr("Download"), tr("CHECK"));
connect(downloadBtn, &ButtonControl::clicked, [=]() {
@@ -111,6 +121,7 @@ void SoftwarePanel::updateLabels() {
fs_watch->addParam("UpdateFailedCount");
fs_watch->addParam("UpdaterState");
fs_watch->addParam("UpdateAvailable");
fs_watch->addParam("dp_device_go_off_road");
if (!isVisible()) {
return;
@@ -120,6 +131,13 @@ void SoftwarePanel::updateLabels() {
onroadLbl->setVisible(is_onroad);
downloadBtn->setVisible(!is_onroad);
// on/off road text change
if (params.getBool("dp_device_go_off_road")) {
onOffRoadBtn->setText(tr("Go Onroad"));
} else {
onOffRoadBtn->setText(tr("Go Offroad"));
}
// download update
QString updater_state = QString::fromStdString(params.get("UpdaterState"));
bool failed = std::atoi(params.get("UpdateFailedCount").c_str()) > 0;

View File

@@ -24,7 +24,9 @@ AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget *par
void AnnotatedCameraWidget::updateState(const UIState &s) {
// update engageability/experimental mode button
experimental_btn->updateState(s);
dmon.updateState(s);
if (!s.scene.lite) {
dmon.updateState(s);
}
}
void AnnotatedCameraWidget::initializeGL() {
@@ -130,9 +132,17 @@ void AnnotatedCameraWidget::paintGL() {
painter.setPen(Qt::NoPen);
model.draw(painter, rect());
dmon.draw(painter, rect());
hud.updateState(*s);
hud.draw(painter, rect());
bool hide_hud = s->scene.dp_ui_hide_hud_speed_kph > 0 && sm["carState"].getCarState().getVEgo() > s->scene.dp_ui_hide_hud_speed_kph * 0.278;
if (!hide_hud) {
if (!s->scene.lite) {
dmon.draw(painter, rect());
}
hud.updateState(*s);
hud.draw(painter, rect());
experimental_btn->setVisible(true);
} else {
experimental_btn->setVisible(false);
}
double cur_draw_t = millis_since_boot();
double dt = cur_draw_t - prev_draw_t;

View File

@@ -48,6 +48,11 @@ void ModelRenderer::draw(QPainter &painter, const QRect &surface_rect) {
}
}
if (s->scene.dp_ui_radar_tracks) {
const auto &live_tracks = sm["liveTracks"].getLiveTracks();
drawLiveTracks(painter, live_tracks, model, surface_rect);
}
painter.restore();
}
@@ -107,7 +112,39 @@ void ModelRenderer::drawLaneLines(QPainter &painter) {
void ModelRenderer::drawPath(QPainter &painter, const cereal::ModelDataV2::Reader &model, int height) {
QLinearGradient bg(0, height, 0, 0);
if (experimental_mode) {
auto *s = uiState();
if (s->scene.dp_ui_rainbow) {
constexpr int NUM_COLORS = 25;
constexpr int ALPHA = 128;
float v_ego = (*uiState()->sm)["carState"].getCarState().getVEgo();
if (!dp_rainbow_init) {
dp_rainbow_color_list.reserve(NUM_COLORS);
for (int i = 0; i < NUM_COLORS; ++i) {
qreal t = static_cast<qreal>(i) / (NUM_COLORS - 1);
dp_rainbow_color_list.append(QColor::fromHsvF(t, 1.0, 1.0, ALPHA / 255.0));
}
dp_rainbow_init = true;
}
bg.setSpread(QGradient::RepeatSpread);
// bigger = faster, however it is still limited to the global UI_FREQ (refresh rate)
// only way to make it move faster is to reduce NUM_COLORS, but that will also reduce the color smoothness.
qreal rotation_speed = std::max(0.01f, v_ego) / UI_FREQ;
dp_rainbow_rotation -= rotation_speed;
if (dp_rainbow_rotation < 0.0) {
dp_rainbow_rotation += 1.0;
dp_rainbow_color_list.append(dp_rainbow_color_list.takeFirst());
}
// fill color
const qreal step = 1.0 / (NUM_COLORS - 1);
for (int i = 0; i < NUM_COLORS; ++i) {
bg.setColorAt(i * step, dp_rainbow_color_list.at(i));
}
} else if (experimental_mode) {
// The first half of track_vertices are the points for the right side of the path
const auto &acceleration = model.getAcceleration().getX();
const int max_len = std::min<int>(track_vertices.length() / 2, acceleration.size());
@@ -186,6 +223,56 @@ QColor ModelRenderer::blendColors(const QColor &start, const QColor &end, float
(1 - t) * start.alphaF() + t * end.alphaF());
}
void ModelRenderer::drawLiveTracks(QPainter &painter,
const cereal::RadarData::Reader &live_tracks,
const cereal::ModelDataV2::Reader &model_data,
const QRect &surface_rect) {
// Get the model's predicted path for Z-coordinate calculation
const auto& model_path_position = model_data.getPosition();
// Set text properties
painter.setPen(Qt::white);
painter.setFont(QFont("Inter", 24, QFont::Bold));
// Iterate through each radar point from live_tracks
for (const auto& point : live_tracks.getPoints()) {
float dRel = point.getDRel();
float yRel = point.getYRel();
float yvRel = point.getYvRel();
float vRel = point.getVRel();
// Calculate Z-coordinate using the model's path
float z_on_path = path_offset_z; // Default base offset
// Ensure dRel is non-negative for indexing
if (dRel >= 0) {
z_on_path += model_path_position.getZ()[get_path_length_idx(model_path_position, dRel)];
}
QPointF screen_pos;
// mapToScreen projects a point from car space to screen space
if (mapToScreen(dRel, -yRel, z_on_path, &screen_pos)) { // yRel is negated as in update_leads
// Basic drawing: Draw a small circle for the point
painter.setBrush(QColor(255, 0, 0, 200)); // Cyan color for live tracks
painter.drawEllipse(screen_pos, 10, 10); // Draw a small circle of radius 5
// Prepare text to display
QString infoText = QString("ID: %1\nd: %2 m\ny: %3 m\ndV: %4 m/s\nyV: %5 m/s")
.arg(point.getTrackId())
.arg(dRel, 0, 'f', 2)
.arg(yRel, 0, 'f', 2)
.arg(vRel, 0, 'f', 2)
.arg(yvRel, 0, 'f', 2);
// Draw text near the point
// Adjust text position for better visibility (e.g., slightly offset from the point)
QRectF textRect(screen_pos.x() + 10, screen_pos.y() - 20, 250, 250); // Adjust size as needed
painter.drawText(textRect, Qt::AlignLeft, infoText);
}
}
}
void ModelRenderer::drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data,
const QPointF &vd, const QRect &surface_rect) {
const float speedBuff = 10.;

View File

@@ -15,6 +15,7 @@ private:
bool mapToScreen(float in_x, float in_y, float in_z, QPointF *out);
void mapLineToPolygon(const cereal::XYZTData::Reader &line, float y_off, float z_off,
QPolygonF *pvd, int max_idx, bool allow_invert = true);
void drawLiveTracks(QPainter &painter, const cereal::RadarData::Reader &live_tracks, const cereal::ModelDataV2::Reader &model_data, const QRect &surface_rect);
void drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd, const QRect &surface_rect);
void update_leads(const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line);
void update_model(const cereal::ModelDataV2::Reader &model, const cereal::RadarState::LeadData::Reader &lead);
@@ -36,4 +37,7 @@ private:
QPointF lead_vertices[2] = {};
Eigen::Matrix3f car_space_transform = Eigen::Matrix3f::Zero();
QRectF clip_region;
QVector<QColor> dp_rainbow_color_list;
qreal dp_rainbow_rotation = 0;
bool dp_rainbow_init = false;
};

View File

@@ -39,16 +39,48 @@ OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) {
QObject::connect(uiState(), &UIState::offroadTransition, this, &OnroadWindow::offroadTransition);
}
void OnroadWindow::updateDpIndicatorSideState(bool blinker_state, bool bsm_state, bool &show, bool &show_prev, int &count, QColor &color) {
if (!blinker_state && !bsm_state) {
show = false;
count = 0;
} else {
count += 1;
}
if (bsm_state && blinker_state) {
show = count % DP_INDICATOR_BLINK_RATE_FAST == 0? !show : show;
color = DP_INDICATOR_COLOR_BSM;
} else if (blinker_state) {
show = count % DP_INDICATOR_BLINK_RATE_STD == 0? !show : show;
color = DP_INDICATOR_COLOR_BLINKER;
} else if (bsm_state) {
show = true;
color = DP_INDICATOR_COLOR_BSM;
} else {
show = false;
}
}
void OnroadWindow::updateDpIndicatorStates(const UIState &s) {
const auto cs = (*s.sm)["carState"].getCarState();
updateDpIndicatorSideState(cs.getLeftBlinker(), cs.getLeftBlindspot(), dp_indicator_show_left, dp_indicator_show_left_prev, dp_indicator_count_left, dp_indicator_color_left);
updateDpIndicatorSideState(cs.getRightBlinker(), cs.getRightBlindspot(), dp_indicator_show_right, dp_indicator_show_right_prev, dp_indicator_count_right, dp_indicator_color_right);
}
void OnroadWindow::updateState(const UIState &s) {
if (!s.scene.started) {
return;
}
dp_indicator_show_left_prev = dp_indicator_show_left;
dp_indicator_show_right_prev = dp_indicator_show_right;
updateDpIndicatorStates(s);
bool indicator_states_changed = dp_indicator_show_left != dp_indicator_show_left_prev || dp_indicator_show_right != dp_indicator_show_right_prev;
alerts->updateState(s);
nvg->updateState(s);
QColor bgColor = bg_colors[s.status];
if (bg != bgColor) {
QColor bgColor = bg_colors[s.scene.alka_active && s.status == STATUS_DISENGAGED? STATUS_ALKA : s.status];
if (bg != bgColor || indicator_states_changed) {
// repaint border
bg = bgColor;
update();
@@ -61,5 +93,7 @@ void OnroadWindow::offroadTransition(bool offroad) {
void OnroadWindow::paintEvent(QPaintEvent *event) {
QPainter p(this);
p.fillRect(rect(), QColor(bg.red(), bg.green(), bg.blue(), 255));
p.fillRect(rect(), QColor(bg.red(), bg.green(), bg.blue(), 180));
if (dp_indicator_show_left) p.fillRect(QRect(0, 0, width() * 0.2, height()), dp_indicator_color_left);
if (dp_indicator_show_right) p.fillRect(QRect(width() * 0.8, 0, width() * 0.2, height()), dp_indicator_color_right);
}

View File

@@ -1,11 +1,18 @@
#pragma once
#include <QColor>
#include "selfdrive/ui/qt/onroad/alerts.h"
#include "selfdrive/ui/qt/onroad/annotated_camera.h"
class OnroadWindow : public QWidget {
Q_OBJECT
const int DP_INDICATOR_BLINK_RATE_STD = 8;
const int DP_INDICATOR_BLINK_RATE_FAST = 4;
const QColor DP_INDICATOR_COLOR_BLINKER = QColor(0, 0xff, 0, 255);
const QColor DP_INDICATOR_COLOR_BSM = QColor(0xff, 0xff, 0, 255);
public:
OnroadWindow(QWidget* parent = 0);
@@ -16,6 +23,19 @@ private:
QColor bg = bg_colors[STATUS_DISENGAGED];
QHBoxLayout* split;
void updateDpIndicatorSideState(bool blinker_state, bool bsm_state, bool &show, bool &show_prev, int &count, QColor &color);
void updateDpIndicatorStates(const UIState &s);
// left
int dp_indicator_count_left = 0;
QColor dp_indicator_color_left = DP_INDICATOR_COLOR_BLINKER;
bool dp_indicator_show_left = false;
bool dp_indicator_show_left_prev = false;
// right
int dp_indicator_count_right = 0;
QColor dp_indicator_color_right = DP_INDICATOR_COLOR_BLINKER;
bool dp_indicator_show_right = false;
bool dp_indicator_show_right_prev = false;
private slots:
void offroadTransition(bool offroad);
void updateState(const UIState &s);

View File

@@ -27,7 +27,8 @@ QString getVersion() {
}
QString getBrand() {
return QObject::tr("dragonpilot");
const bool lite = getenv("LITE");
return QObject::tr("dragonpilot") + (lite ? QString::fromStdString(" - Lite") : QString(""));
}
QString getUserAgent() {

View File

@@ -10,6 +10,7 @@ from openpilot.common.filter_simple import FirstOrderFilter
from openpilot.common.realtime import Ratekeeper
from openpilot.common.retry import retry
from openpilot.common.swaglog import cloudlog
from openpilot.common.params import Params
from openpilot.system import micd
@@ -62,6 +63,11 @@ class Soundd:
self.spl_filter_weighted = FirstOrderFilter(0, 2.5, FILTER_DT, initialized=False)
try:
self._dp_device_audible_alert_mode = int(Params().get("dp_device_audible_alert_mode"))
except:
self._dp_device_audible_alert_mode = 0
def load_sounds(self):
self.loaded_sounds: dict[int, np.ndarray] = {}
@@ -96,6 +102,10 @@ class Soundd:
written_frames += frames_to_write
self.current_sound_frame += frames_to_write
# dp - set vol to 0 instead
if self._dp_device_audible_alert_mode == 2 or (self._dp_device_audible_alert_mode == 1 and self.current_alert in [AudibleAlert.engage, AudibleAlert.disengage]):
self.current_volume = 0
return ret * self.current_volume
def callback(self, data_out: np.ndarray, frames: int, time, status) -> None:

View File

@@ -60,6 +60,7 @@ static void update_state(UIState *s) {
scene.light_sensor = -1;
}
scene.started = sm["deviceState"].getDeviceState().getStarted() && scene.ignition;
scene.alka_active = sm["dpControlsState"].getDpControlsState().getAlkaActive();
auto params = Params();
scene.recording_audio = params.getBool("RecordAudio") && scene.started;
@@ -68,6 +69,11 @@ static void update_state(UIState *s) {
void ui_update_params(UIState *s) {
auto params = Params();
s->scene.is_metric = params.getBool("IsMetric");
s->scene.lite = getenv("LITE");
s->scene.display_mode = std::atoi(params.get("dp_ui_display_mode").c_str());
s->scene.dp_ui_hide_hud_speed_kph = std::atoi(params.get("dp_ui_hide_hud_speed_kph").c_str());
s->scene.dp_ui_rainbow = params.getBool("dp_ui_rainbow");
s->scene.dp_ui_radar_tracks = params.getBool("dp_ui_radar_tracks");
}
void UIState::updateStatus() {
@@ -102,6 +108,8 @@ UIState::UIState(QObject *parent) : QObject(parent) {
"modelV2", "controlsState", "liveCalibration", "radarState", "deviceState",
"pandaStates", "carParams", "driverMonitoringState", "carState", "driverStateV2",
"wideRoadCameraState", "managerState", "selfdriveState", "longitudinalPlan",
"dpControlsState",
"liveTracks",
});
prime_state = new PrimeState(this);
language = QString::fromStdString(Params().get("LanguageSetting"));
@@ -180,6 +188,62 @@ void Device::updateBrightness(const UIState &s) {
}
}
// Display Mode
// 0 Std. - Stock behavior.
// 1 MAIN+ - ACC MAIN on = Display ON
// 2 OP+ - OP enabled = Display ON
// 3 MAIN- - ACC MAIN on = Display OFF
// 4 OP- - OP enabled = Display OFF
bool Device::applyDisplayMode(const UIState &s, int timeout) {
// standard
if (s.scene.display_mode == 0 || !s.scene.ignition) {
return (s.scene.ignition || timeout > 0);
}
bool cruise_available = false;
bool cruise_enabled = false;
auto &sm = *(s.sm);
if (sm.updated("carState")) {
auto cs = sm["carState"].getCarState().getCruiseState();
cruise_available = cs.getAvailable();
cruise_enabled = cs.getEnabled();
}
if (sm["selfdriveState"].getSelfdriveState().getAlertSize() != cereal::SelfdriveState::AlertSize::NONE) {
resetInteractiveTimeout(5);
return true;
}
// 1 MAIN+ - ACC MAIN on = Display ON
if (s.scene.display_mode == 1 && cruise_available) {
return s.scene.ignition;
}
// 2 OP+ - OP enabled = Display ON
if (s.scene.display_mode == 2 && cruise_enabled) {
return s.scene.ignition;
}
// 3 MAIN- - ACC MAIN on = Display OFF
if (s.scene.display_mode == 3 && cruise_available) {
return false;
}
// 4 OP- - OP enabled = Display OFF
if (s.scene.display_mode == 4 && cruise_enabled) {
return false;
}
if (s.scene.display_mode >= 3) {
// 3,4
return s.scene.ignition;
} else {
// 1,2
return false;
}
}
void Device::updateWakefulness(const UIState &s) {
bool ignition_just_turned_off = !s.scene.ignition && ignition_on;
ignition_on = s.scene.ignition;
@@ -190,7 +254,7 @@ void Device::updateWakefulness(const UIState &s) {
emit interactiveTimeout();
}
setAwake(s.scene.ignition || interactive_timeout > 0);
setAwake(applyDisplayMode(s, interactive_timeout));
}
UIState *uiState() {

View File

@@ -42,12 +42,14 @@ typedef enum UIStatus {
STATUS_DISENGAGED,
STATUS_OVERRIDE,
STATUS_ENGAGED,
STATUS_ALKA,
} UIStatus;
const QColor bg_colors [] = {
[STATUS_DISENGAGED] = QColor(0x17, 0x33, 0x49, 0xc8),
[STATUS_OVERRIDE] = QColor(0x91, 0x9b, 0x95, 0xf1),
[STATUS_ENGAGED] = QColor(0x17, 0x86, 0x44, 0xf1),
[STATUS_ALKA] = QColor(0x22, 0xa0, 0xdc, 0xf1),
};
typedef struct UIScene {
@@ -60,6 +62,12 @@ typedef struct UIScene {
float light_sensor = -1;
bool started, ignition, is_metric, recording_audio;
uint64_t started_frame;
bool lite = false;
bool alka_active = false;
int display_mode = 0;
int dp_ui_hide_hud_speed_kph = 0;
bool dp_ui_rainbow = false;
bool dp_ui_radar_tracks = false;
} UIScene;
class UIState : public QObject {
@@ -115,6 +123,7 @@ private:
FirstOrderFilter brightness_filter;
QFuture<void> brightness_future;
bool applyDisplayMode(const UIState &s, int timeout);
void updateBrightness(const UIState &s);
void updateWakefulness(const UIState &s);
void setAwake(bool on);

View File

@@ -12,6 +12,7 @@ from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert
from openpilot.system.hardware import HARDWARE, PC
from openpilot.system.hardware.hw import Paths
from openpilot.common.swaglog import cloudlog
import os
UNREGISTERED_DONGLE_ID = "UnregisteredDevice"
@@ -48,6 +49,9 @@ def register(show_spinner=False) -> str | None:
spinner = Spinner()
spinner.update("registering device")
if os.getenv("LITE"):
params.put("DongleId", UNREGISTERED_DONGLE_ID)
return dongle_id
# Create registration token, in the future, this key will make JWTs directly
with open(Paths.persist_root()+"/comma/id_rsa.pub") as f1, open(Paths.persist_root()+"/comma/id_rsa") as f2:
public_key = f1.read()
@@ -74,7 +78,7 @@ def register(show_spinner=False) -> str | None:
try:
register_token = jwt.encode({'register': True, 'exp': datetime.now(UTC).replace(tzinfo=None) + timedelta(hours=1)}, private_key, algorithm='RS256')
cloudlog.info("getting pilotauth")
resp = api_get("v2/pilotauth/", method='POST', timeout=15,
resp = api_get("v2/pilotauth/", method='POST', timeout=5,
imei=imei1, imei2=imei2, serial=serial, public_key=public_key, register_token=register_token)
if resp.status_code in (402, 403):

View File

@@ -270,6 +270,7 @@ void camerad_thread() {
// *** per-cam init ***
std::vector<std::unique_ptr<CameraState>> cams;
for (const auto &config : ALL_CAMERA_CONFIGS) {
if (!config.enabled) continue;
auto cam = std::make_unique<CameraState>(&m, config);
cam->init(&v, device_id, ctx);
cams.emplace_back(std::move(cam));

View File

@@ -59,7 +59,7 @@ const CameraConfig DRIVER_CAMERA_CONFIG = {
.focal_len = 1.71,
.publish_name = "driverCameraState",
.init_camera_state = &cereal::Event::Builder::initDriverCameraState,
.enabled = !getenv("DISABLE_DRIVER"),
.enabled = (!getenv("DISABLE_DRIVER") && !getenv("LITE")),
.phy = CAM_ISP_IFE_IN_RES_PHY_2,
.vignetting_correction = false,
.output_type = ISP_BPS_PROCESSED,

View File

@@ -210,6 +210,8 @@ def hardware_thread(end_event, hw_queue) -> None:
fan_controller = None
dp_device_go_off_road = False
while not end_event.is_set():
sm.update(PANDA_STATES_TIMEOUT)
@@ -335,13 +337,15 @@ def hardware_thread(end_event, hw_queue) -> None:
startup_conditions["registered_device"] = PC or (params.get("DongleId") != UNREGISTERED_DONGLE_ID)
# TODO: this should move to TICI.initialize_hardware, but we currently can't import params there
if TICI and HARDWARE.get_device_type() == "tici":
if TICI and HARDWARE.get_device_type() == "tici" and not os.getenv("LITE"):
if not os.path.isfile("/persist/comma/living-in-the-moment"):
if not Path("/data/media").is_mount():
set_offroad_alert_if_changed("Offroad_StorageMissing", True)
# Handle offroad/onroad transition
should_start = all(onroad_conditions.values())
if count % 6 == 0:
dp_device_go_off_road = params.get_bool("dp_device_go_off_road")
should_start = not dp_device_go_off_road and all(onroad_conditions.values())
if started_ts is None:
should_start = should_start and all(startup_conditions.values())

View File

@@ -28,6 +28,8 @@ class PowerMonitoring:
self.car_voltage_mV = 12e3 # Low-passed version of peripheralState voltage
self.car_voltage_instant_mV = 12e3 # Last value of peripheralState voltage
self.integration_lock = threading.Lock()
self.dp_device_auto_shutdown_in = int(self.params.get("dp_device_auto_shutdown_in") or -5) * 60
self.dp_device_auto_shutdown = self.dp_device_auto_shutdown_in >= 0
car_battery_capacity_uWh = self.params.get("CarBatteryCapacity") or 0
@@ -112,6 +114,8 @@ class PowerMonitoring:
now = time.monotonic()
should_shutdown = False
offroad_time = (now - offroad_timestamp)
if started_seen and self.dp_device_auto_shutdown and offroad_time > self.dp_device_auto_shutdown_in:
return True
low_voltage_shutdown = (self.car_voltage_mV < (VBATT_PAUSE_CHARGING * 1e3) and
offroad_time > VOLTAGE_SHUTDOWN_MIN_OFFROAD_TIME_S)
should_shutdown |= offroad_time > MAX_TIME_OFFROAD_S

View File

@@ -94,7 +94,7 @@ class Tici(HardwareBase):
@cached_property
def amplifier(self):
if self.get_device_type() == "mici":
if self.get_device_type() == "mici" or os.getenv("LITE"):
return None
return Amplifier()
@@ -190,7 +190,7 @@ class Tici(HardwareBase):
return str(self.get_modem().Get(MM_MODEM, 'EquipmentIdentifier', dbus_interface=DBUS_PROPS, timeout=TIMEOUT))
def get_network_info(self):
if self.get_device_type() == "mici":
if self.get_device_type() == "mici" or os.getenv("LITE"):
return None
try:
modem = self.get_modem()
@@ -282,6 +282,8 @@ class Tici(HardwareBase):
return None
def get_modem_temperatures(self):
if os.getenv("LITE"):
return []
timeout = 0.2 # Default timeout is too short
try:
modem = self.get_modem()

View File

@@ -22,6 +22,8 @@ extern "C" {
const int env_debug_encoder = (getenv("DEBUG_ENCODER") != NULL) ? atoi(getenv("DEBUG_ENCODER")) : 0;
const int env_dashy = (getenv("DASHY") != NULL) ? atoi(getenv("DASHY")) : 0;
FfmpegEncoder::FfmpegEncoder(const EncoderInfo &encoder_info, int in_width, int in_height)
: VideoEncoder(encoder_info, in_width, in_height) {
frame = av_frame_alloc();
@@ -57,7 +59,13 @@ void FfmpegEncoder::encoder_open() {
this->codec_ctx->height = frame->height;
this->codec_ctx->pix_fmt = AV_PIX_FMT_YUV420P;
this->codec_ctx->time_base = (AVRational){ 1, encoder_info.fps };
int err = avcodec_open2(this->codec_ctx, codec, NULL);
AVDictionary *opts = NULL;
if (env_dashy && codec_id == AV_CODEC_ID_H264) {
av_dict_set(&opts, "preset", "ultrafast", 0);
av_dict_set(&opts, "tune", "zerolatency", 0);
}
int err = avcodec_open2(this->codec_ctx, codec, &opts);
av_dict_free(&opts);
assert(err >= 0);
is_open = true;

View File

@@ -230,8 +230,25 @@ void loggerd_thread() {
std::unique_ptr<Context> ctx(Context::create());
std::unique_ptr<Poller> poller(Poller::create());
const bool lite = getenv("LITE");
const std::set<std::string> lite_skip_names = {
"driverCameraState",
"driverEncodeIdx",
"driverStateV2",
"driverMonitoringState",
"driverEncodeData",
"livestreamDriverEncodeIdx",
"livestreamDriverEncodeData",
// audio logs
"userBookmark",
"soundPressure",
"rawAudioData",
"audioFeedback",
};
// subscribe to all socks
for (const auto& [_, it] : services) {
if (lite && lite_skip_names.count(it.name)) continue;
const bool encoder = util::ends_with(it.name, "EncodeData");
const bool livestream_encoder = util::starts_with(it.name, "livestream");
const bool record_audio = (it.name == "rawAudioData") && Params().getBool("RecordAudio");
@@ -261,7 +278,9 @@ void loggerd_thread() {
std::vector<RemoteEncoder*> encoders_with_audio;
for (const auto &cam : cameras_logged) {
for (const auto &encoder_info : cam.encoder_infos) {
encoder_infos_dict[encoder_info.publish_name] = encoder_info;
const std::string &name = encoder_info.publish_name;
if (lite && lite_skip_names.count(name)) continue;
encoder_infos_dict[name] = encoder_info;
s.max_waiting++;
}
}

View File

@@ -93,7 +93,7 @@ const EncoderInfo main_wide_road_encoder_info = {
const EncoderInfo main_driver_encoder_info = {
.publish_name = "driverEncodeData",
.filename = "dcamera.hevc",
.record = Params().getBool("RecordFront"),
.record = !getenv("LITE") && Params().getBool("RecordFront"),
.get_settings = [](int in_width){return EncoderSettings::MainEncoderSettings(in_width);},
INIT_ENCODE_FUNCTIONS(DriverEncode),
};

View File

@@ -19,6 +19,8 @@ from openpilot.system.athena.registration import register, UNREGISTERED_DONGLE_I
from openpilot.common.swaglog import cloudlog, add_file_handler
from openpilot.system.version import get_build_metadata, terms_version, training_version
from openpilot.system.hardware.hw import Paths
from openpilot.system.manager.vehicle_model_collector import VehicleModelCollector
import time
def manager_init() -> None:
@@ -42,6 +44,7 @@ def manager_init() -> None:
default_value = params.get_default_value(k)
if default_value is not None and params.get(k) is None:
params.put(k, default_value)
params.put("dp_device_model_list", VehicleModelCollector().get())
# Create folders needed for msgq
try:
@@ -69,7 +72,8 @@ def manager_init() -> None:
if reg_res:
dongle_id = reg_res
else:
raise Exception(f"Registration failed for device {serial}")
dongle_id = "UnregisteredDevice"
# raise Exception(f"Registration failed for device {serial}")
os.environ['DONGLE_ID'] = dongle_id # Needed for swaglog
os.environ['GIT_ORIGIN'] = build_metadata.openpilot.git_normalized_origin # Needed for swaglog
os.environ['GIT_BRANCH'] = build_metadata.channel # Needed for swaglog
@@ -126,6 +130,15 @@ def manager_thread() -> None:
ensure_running(managed_processes.values(), False, params=params, CP=sm['carParams'], not_run=ignore)
started_prev = False
dp_dev_delay_time_started: float = 0.
dp_dev_delay_loggerd = int(params.get('dp_dev_delay_loggerd') or 0)
# Dictionary of processes to be delayed [process_name: delay_seconds]
dp_dev_delay_start_times: dict[str, float] = {
'loggerd': dp_dev_delay_loggerd,
'encoderd': dp_dev_delay_loggerd
}
ignition_prev = False
while True:
@@ -146,10 +159,22 @@ def manager_thread() -> None:
if started != started_prev:
write_onroad_params(started, params)
dp_ignore: list[str] = []
if started and not started_prev:
dp_dev_delay_time_started = time.monotonic()
elif not started and started_prev:
dp_dev_delay_time_started = 0.
if dp_dev_delay_time_started > 0.:
cur_time = time.monotonic()
for name, delay_time in dp_dev_delay_start_times.items():
if cur_time - dp_dev_delay_time_started < delay_time: # type: ignore
dp_ignore.append(name)
started_prev = started
ignition_prev = ignition
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=list(set(ignore) | set(dp_ignore)))
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)

View File

@@ -55,6 +55,12 @@ def only_onroad(started: bool, params: Params, CP: car.CarParams) -> bool:
def only_offroad(started: bool, params: Params, CP: car.CarParams) -> bool:
return not started
def dashy(started: bool, params: Params, CP: car.CarParams) -> bool:
return int(params.get("dp_dev_dashy") or 0) > 0
def dashy_with_video(started: bool, params: Params, CP: car.CarParams) -> bool:
return int(params.get("dp_dev_dashy") or 0) == 2
def or_(*fns):
return lambda *args: operator.or_(*(fn(*args) for fn in fns))
@@ -66,23 +72,24 @@ procs = [
NativeProcess("loggerd", "system/loggerd", ["./loggerd"], logging),
NativeProcess("encoderd", "system/loggerd", ["./encoderd"], only_onroad),
NativeProcess("stream_encoderd", "system/loggerd", ["./encoderd", "--stream"], notcar),
NativeProcess("stream_encoderd", "system/loggerd", ["./encoderd", "--stream"], or_(notcar, and_(dashy_with_video, only_onroad))),
PythonProcess("logmessaged", "system.logmessaged", always_run),
NativeProcess("camerad", "system/camerad", ["./camerad"], driverview, enabled=not WEBCAM),
PythonProcess("webcamerad", "tools.webcam.camerad", driverview, enabled=WEBCAM),
NativeProcess("logcatd", "system/logcatd", ["./logcatd"], only_onroad, platform.system() != "Darwin"),
NativeProcess("proclogd", "system/proclogd", ["./proclogd"], only_onroad, platform.system() != "Darwin"),
PythonProcess("micd", "system.micd", iscar),
PythonProcess("micd", "system.micd", iscar, enabled=not os.getenv("LITE")),
PythonProcess("timed", "system.timed", always_run, enabled=not PC),
PythonProcess("modeld", "selfdrive.modeld.modeld", only_onroad),
PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(WEBCAM or not PC)),
PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(WEBCAM or not PC) and not os.getenv("LITE")),
PythonProcess("sensord", "system.sensord.sensord", only_onroad, enabled=not PC),
NativeProcess("ui", "selfdrive/ui", ["./ui"], always_run, watchdog_max_dt=(5 if not PC else None)),
PythonProcess("raylib_ui", "selfdrive.ui.ui", always_run, enabled=False, watchdog_max_dt=(5 if not PC else None)),
PythonProcess("soundd", "selfdrive.ui.soundd", only_onroad),
PythonProcess("soundd", "selfdrive.ui.soundd", only_onroad, enabled=not os.getenv("LITE")),
PythonProcess("beepd", "dragonpilot.selfdrive.ui.beepd", only_onroad, enabled=(Params().get_bool("dp_device_beep") and os.getenv("LITE"))),
PythonProcess("locationd", "selfdrive.locationd.locationd", only_onroad),
NativeProcess("_pandad", "selfdrive/pandad", ["./pandad"], always_run, enabled=False),
PythonProcess("calibrationd", "selfdrive.locationd.calibrationd", only_onroad),
@@ -92,7 +99,8 @@ procs = [
PythonProcess("selfdrived", "selfdrive.selfdrived.selfdrived", only_onroad),
PythonProcess("card", "selfdrive.car.card", only_onroad),
PythonProcess("deleter", "system.loggerd.deleter", always_run),
PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", driverview, enabled=(WEBCAM or not PC)),
PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", driverview, enabled=(WEBCAM or not PC) and not os.getenv("LITE")),
PythonProcess("dpmonitoringd", "selfdrive.monitoring.dpmonitoringd", only_onroad, enabled=os.getenv("LITE")),
PythonProcess("qcomgpsd", "system.qcomgpsd.qcomgpsd", qcomgps, enabled=TICI),
PythonProcess("pandad", "selfdrive.pandad.pandad", always_run),
PythonProcess("paramsd", "selfdrive.locationd.paramsd", only_onroad),
@@ -107,13 +115,14 @@ procs = [
PythonProcess("updated", "system.updated.updated", only_offroad, enabled=not PC),
PythonProcess("uploader", "system.loggerd.uploader", always_run),
PythonProcess("statsd", "system.statsd", always_run),
PythonProcess("feedbackd", "selfdrive.ui.feedback.feedbackd", only_onroad),
PythonProcess("feedbackd", "selfdrive.ui.feedback.feedbackd", only_onroad, enabled=not os.getenv("LITE")),
# debug procs
NativeProcess("bridge", "cereal/messaging", ["./bridge"], notcar),
PythonProcess("webrtcd", "system.webrtc.webrtcd", notcar),
NativeProcess("bridge", "cereal/messaging", ["./bridge"], or_(notcar, and_(dashy_with_video, only_onroad))),
PythonProcess("webrtcd", "system.webrtc.webrtcd", or_(notcar, and_(dashy_with_video, only_onroad))),
PythonProcess("webjoystick", "tools.bodyteleop.web", notcar),
PythonProcess("joystick", "tools.joystick.joystick_control", and_(joystick, iscar)),
PythonProcess("dashy", "dragonpilot.dashy.backend.server", dashy),
]
managed_processes = {p.name: p for p in procs}

View File

@@ -0,0 +1,163 @@
"""
Copyright (c) 2025 Rick Lan
This software is licensed under the Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License (CC BY-NC-SA 4.0).
You are free to share and adapt this work for non-commercial purposes, provided you give appropriate credit and distribute any modifications under the same license.
To view a copy of this license, visit:
http://creativecommons.org/licenses/by-nc-sa/4.0/
---
**Commercial Licensing:**
Use of this software for commercial purposes is strictly prohibited without a separate, paid license.
To purchase a commercial license, please contact ricklan@gmail.com.
"""
import os
import importlib
import json
from openpilot.common.basedir import BASEDIR
from openpilot.common.params import Params
class VehicleModelCollector:
def __init__(self):
self.base_package = "opendbc.car"
self.base_path = f"{BASEDIR}/opendbc/car"
self.exclude_brands = ['body', 'mock']
# Define the lookup dictionary for brand-to-group mappings
self.brand_to_group_map = {
"chrysler": [
{"prefix": "DODGE_", "group": "Dodge"},
{"prefix": "RAM_", "group": "Ram"},
{"prefix": "JEEP_", "group": "Jeep"},
],
"gm": [
{"prefix": "BUICK_", "group": "Buick"},
{"prefix": "CADILLAC_", "group": "Cadillac"},
{"prefix": "CHEVROLET_", "group": "Chevrolet"},
{"prefix": "HOLDEN_", "group": "Holden"},
],
"honda": {"prefix": "ACURA_", "group": "Acura"},
"toyota": {"prefix": "LEXUS_", "group": "Lexus"},
"hyundai": [
{"prefix": "KIA_", "group": "Kia"},
{"prefix": "GENESIS_", "group": "Genesis"}
],
"volkswagen": [
{"prefix": "AUDI_", "group": "Audi"},
{"prefix": "SKODA_", "group": "Skoda"},
{"prefix": "SEAT_", "group": "Seat"}
]
}
# Define exceptions for group names
self.group_name_exceptions = {
"gm": "GM",
}
@staticmethod
def is_car_model(car_class, attr):
"""Check if the attribute is a car model (not callable and not a dunder attribute)"""
return not callable(getattr(car_class, attr)) and not attr.startswith("__")
@staticmethod
def move_to_proper_group(models, prefix):
"""
Moves models with a certain prefix to their respective group.
Example: Models starting with 'LEXUS_' should go to 'Lexus' group.
"""
moved_models = []
for model in models[:]: # Iterate over a copy to avoid modifying during iteration
if model.startswith(prefix):
moved_models.append(model)
models.remove(model) # Remove from the original group
return moved_models
def format_group_name(self, group_name):
"""
Formats group names according to the exceptions dictionary.
Groups in the exceptions dictionary are returned in all caps, others are title cased.
"""
return self.group_name_exceptions.get(group_name, group_name.title())
def collect_models(self):
"""Collect all car models and organize them by brand/group"""
# List all subdirectories (car brands)
car_brands = sorted([
name for name in os.listdir(self.base_path)
if os.path.isdir(os.path.join(self.base_path, name)) and not name.startswith("__")
])
grouped_models = {}
# Import CAR from each subdirectory and group models by brand
for brand in car_brands:
if brand in self.exclude_brands:
continue
module_name = f"{self.base_package}.{brand}.values"
try:
module = importlib.import_module(module_name)
if hasattr(module, "CAR"):
car_class = getattr(module, "CAR")
models = sorted([attr for attr in dir(car_class) if self.is_car_model(car_class, attr)])
# Check if the brand has a special group in the lookup map
if brand in self.brand_to_group_map:
group_info = self.brand_to_group_map[brand]
if isinstance(group_info, list): # If multiple prefixes for the brand
for prefix_info in group_info:
moved_models = self.move_to_proper_group(models, prefix_info["prefix"])
if moved_models:
if prefix_info["group"] not in grouped_models:
grouped_models[prefix_info["group"]] = []
grouped_models[prefix_info["group"]].extend(moved_models)
else: # Single prefix for the brand
moved_models = self.move_to_proper_group(models, group_info["prefix"])
if moved_models:
if group_info["group"] not in grouped_models:
grouped_models[group_info["group"]] = []
grouped_models[group_info["group"]].extend(moved_models)
# Add remaining models to the respective brand
if models:
grouped_models[brand] = models
except ModuleNotFoundError:
pass
# Sort the groups alphabetically
sorted_grouped_models = sorted(grouped_models.items(), key=lambda x: x[0])
# Convert to the desired output structure, ensuring models are sorted within each group
output = [{"group": self.format_group_name(group), "models": sorted(models)}
for group, models in sorted_grouped_models]
return output
# def save_to_params(self, output=None):
# """Save the collected model list to Params"""
# if output is None:
# output = self.collect_models()
# Params().put("dp_device_model_list", json.dumps(output))
# return output
#
# def run(self):
# """Collect models and save to params"""
# models = self.collect_models()
# self.save_to_params(models)
# return models
def get_json(self):
return self.collect_models()
def get(self):
return json.dumps(self.collect_models())
# Allow running as a script
if __name__ == "__main__":
collector = VehicleModelCollector()
print(collector.get())

View File

@@ -266,7 +266,8 @@ def init(pigeon: TTYPigeon) -> None:
set_power(False)
time.sleep(0.1)
set_power(True)
time.sleep(0.5)
# rick - make sleep twice long, give LITE more time.
time.sleep(1.0)
init_baudrate(pigeon)
init_pigeon(pigeon)

View File

@@ -42,7 +42,7 @@ class CerealOutgoingMessageProxy:
return msg_dict
def update(self):
async def update(self):
# this is blocking in async context...
self.sm.update(0)
for service, updated in self.sm.updated.items():
@@ -53,7 +53,10 @@ class CerealOutgoingMessageProxy:
outgoing_msg = {"type": service, "logMonoTime": mono_time, "valid": valid, "data": msg_dict}
encoded_msg = json.dumps(outgoing_msg).encode()
for channel in self.channels:
channel.send(encoded_msg)
if isinstance(channel, web.WebSocketResponse):
await channel.send_bytes(encoded_msg)
else:
channel.send(encoded_msg)
class CerealIncomingMessageProxy:
@@ -94,7 +97,7 @@ class CerealProxyRunner:
while True:
try:
self.proxy.update()
await self.proxy.update()
except InvalidStateError:
self.logger.warning("Cereal outgoing proxy invalid state (connection closed)")
break
@@ -229,7 +232,7 @@ async def get_stream(request: 'web.Request'):
stream_dict[session.identifier] = session
return web.json_response({"sdp": answer.sdp, "type": answer.type})
return web.json_response({"sdp": answer.sdp, "type": answer.type}, headers={'Access-Control-Allow-Origin': '*'})
async def get_schema(request: 'web.Request'):
@@ -246,23 +249,47 @@ async def on_shutdown(app: 'web.Application'):
del app['streams']
@web.middleware
async def cors_middleware(request, handler):
response = await handler(request)
response.headers['Access-Control-Allow-Origin'] = '*'
response.headers['Access-Control-Allow-Methods'] = 'GET, POST, PUT, DELETE, OPTIONS'
response.headers['Access-Control-Allow-Headers'] = 'Content-Type, Authorization'
return response
async def handle_cors_preflight(request):
if request.method == 'OPTIONS':
headers = {
'Access-Control-Allow-Origin': '*',
'Access-Control-Allow-Methods': 'GET, POST, PUT, DELETE, OPTIONS',
'Access-Control-Allow-Headers': 'Content-Type, Authorization',
'Access-Control-Max-Age': '86400',
}
return web.Response(status=200, headers=headers)
return await request.app['handler'](request)
def webrtcd_thread(host: str, port: int, debug: bool):
logging.basicConfig(level=logging.CRITICAL, handlers=[logging.StreamHandler()])
logging_level = logging.DEBUG if debug else logging.INFO
logging.getLogger("WebRTCStream").setLevel(logging_level)
logging.getLogger("webrtcd").setLevel(logging_level)
app = web.Application()
app = web.Application(middlewares=[cors_middleware])
app['streams'] = dict()
app['debug'] = debug
app.on_shutdown.append(on_shutdown)
app.router.add_post("/stream", get_stream)
app.router.add_get("/schema", get_schema)
app.router.add_route('OPTIONS', '/{tail:.*}', handle_cors_preflight)
web.run_app(app, host=host, port=port)
def main():
parser = argparse.ArgumentParser(description="WebRTC daemon")
parser.add_argument("--host", type=str, default="0.0.0.0", help="Host to listen on")