mirror of
https://github.com/dzid26/sunnypilot.git
synced 2026-06-08 07:44:55 +08:00
Merge branch 'upstream/openpilot/master' into sync-20260401
# Conflicts: # .github/workflows/auto_pr_review.yaml # .github/workflows/repo-maintenance.yaml # README.md # SConstruct # docs/CARS.md # opendbc_repo # panda # selfdrive/car/card.py # selfdrive/controls/controlsd.py # selfdrive/selfdrived/selfdrived.py # selfdrive/test/process_replay/migration.py # selfdrive/ui/translations/app_fr.po Platform List: sync with latest Sync: `commaai/panda:master` → `sunnypilot/panda:master`
This commit is contained in:
45
.github/workflows/diff_report.yaml
vendored
Normal file
45
.github/workflows/diff_report.yaml
vendored
Normal file
@@ -0,0 +1,45 @@
|
||||
name: diff report
|
||||
|
||||
on:
|
||||
pull_request_target:
|
||||
types: [opened, synchronize, reopened]
|
||||
|
||||
jobs:
|
||||
comment:
|
||||
name: comment
|
||||
runs-on: ubuntu-latest
|
||||
timeout-minutes: 10
|
||||
permissions:
|
||||
contents: read
|
||||
pull-requests: write
|
||||
actions: read
|
||||
steps:
|
||||
- name: Wait for process replay
|
||||
id: wait
|
||||
continue-on-error: true
|
||||
uses: lewagon/wait-on-check-action@v1.3.4
|
||||
with:
|
||||
ref: ${{ github.event.pull_request.head.sha }}
|
||||
check-name: process replay
|
||||
repo-token: ${{ secrets.GITHUB_TOKEN }}
|
||||
allowed-conclusions: success,failure
|
||||
wait-interval: 20
|
||||
- name: Download diff
|
||||
if: steps.wait.outcome == 'success'
|
||||
uses: dawidd6/action-download-artifact@v6
|
||||
with:
|
||||
github_token: ${{ secrets.GITHUB_TOKEN }}
|
||||
workflow: tests.yaml
|
||||
workflow_conclusion: ''
|
||||
pr: ${{ github.event.number }}
|
||||
name: diff_report_${{ github.event.number }}
|
||||
path: .
|
||||
allow_forks: true
|
||||
- name: Comment on PR
|
||||
if: steps.wait.outcome == 'success'
|
||||
uses: thollander/actions-comment-pull-request@v2
|
||||
with:
|
||||
filePath: diff_report.txt
|
||||
comment_tag: diff_report
|
||||
pr_number: ${{ github.event.number }}
|
||||
GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }}
|
||||
22
.github/workflows/repo-maintenance.yaml
vendored
22
.github/workflows/repo-maintenance.yaml
vendored
@@ -9,28 +9,6 @@ env:
|
||||
PYTHONPATH: ${{ github.workspace }}
|
||||
|
||||
jobs:
|
||||
update_translations:
|
||||
runs-on: ubuntu-latest
|
||||
if: github.repository == 'sunnypilot/sunnypilot'
|
||||
steps:
|
||||
- uses: actions/checkout@v6
|
||||
with:
|
||||
submodules: true
|
||||
- run: ./tools/op.sh setup
|
||||
- name: Update translations
|
||||
run: python3 selfdrive/ui/update_translations.py --vanish
|
||||
- name: Create Pull Request
|
||||
uses: peter-evans/create-pull-request@c0f553fe549906ede9cf27b5156039d195d2ece0
|
||||
with:
|
||||
author: github-actions[bot] <github-actions[bot]@users.noreply.github.com>
|
||||
commit-message: "Update translations"
|
||||
title: "[bot] Update translations"
|
||||
body: "Automatic PR from repo-maintenance -> update_translations"
|
||||
branch: "update-translations"
|
||||
base: "master"
|
||||
delete-branch: true
|
||||
labels: bot
|
||||
|
||||
package_updates:
|
||||
name: package_updates
|
||||
runs-on: ubuntu-latest
|
||||
|
||||
10
.github/workflows/tests.yaml
vendored
10
.github/workflows/tests.yaml
vendored
@@ -156,12 +156,22 @@ jobs:
|
||||
id: print-diff
|
||||
if: always()
|
||||
run: cat selfdrive/test/process_replay/diff.txt
|
||||
- name: Print diff report
|
||||
if: always()
|
||||
run: cat selfdrive/test/process_replay/diff_report.txt
|
||||
- uses: actions/upload-artifact@v6
|
||||
if: always()
|
||||
continue-on-error: true
|
||||
with:
|
||||
name: process_replay_diff.txt
|
||||
path: selfdrive/test/process_replay/diff.txt
|
||||
- name: Upload diff report
|
||||
uses: actions/upload-artifact@v6
|
||||
if: always() && github.event_name == 'pull_request'
|
||||
continue-on-error: true
|
||||
with:
|
||||
name: diff_report_${{ github.event.number }}
|
||||
path: selfdrive/test/process_replay/diff_report.txt
|
||||
- name: Checkout ci-artifacts
|
||||
if: github.repository == 'commaai/openpilot' && github.ref == 'refs/heads/master'
|
||||
uses: actions/checkout@v4
|
||||
|
||||
@@ -1,7 +1,8 @@
|
||||
Version 0.11.1 (2026-04-08)
|
||||
Version 0.11.1 (2026-04-22)
|
||||
========================
|
||||
* New driver monitoring model
|
||||
* Improved image processing pipeline for driver camera
|
||||
* Rivian R1S and R1T 2025 support thanks to lukasloetkolben!
|
||||
|
||||
Version 0.11.0 (2026-03-17)
|
||||
========================
|
||||
|
||||
12
SConstruct
12
SConstruct
@@ -47,7 +47,8 @@ pkgs = [importlib.import_module(name) for name in pkg_names]
|
||||
# be distributed with all Linux distros and macOS, or
|
||||
# vendored in commaai/dependencies.
|
||||
allowed_system_libs = {
|
||||
"EGL", "GLESv2", "GL", "Qt5Charts", "Qt5Core", "Qt5Gui", "Qt5Widgets",
|
||||
"EGL", "GLESv2", "GL",
|
||||
"Qt5Charts", "Qt5Core", "Qt5Gui", "Qt5Widgets",
|
||||
"dl", "drm", "gbm", "m", "pthread",
|
||||
}
|
||||
|
||||
@@ -256,8 +257,13 @@ SConscript([
|
||||
|
||||
SConscript(['sunnypilot/SConscript'])
|
||||
|
||||
if Dir('#tools/cabana/').exists() and arch != "larch64":
|
||||
SConscript(['tools/cabana/SConscript'])
|
||||
# Build tools
|
||||
if arch != "larch64":
|
||||
SConscript([
|
||||
'tools/replay/SConscript',
|
||||
'tools/cabana/SConscript',
|
||||
'tools/jotpluggler/SConscript',
|
||||
])
|
||||
|
||||
|
||||
env.CompilationDatabase('compile_commands.json')
|
||||
|
||||
@@ -88,6 +88,7 @@ struct OnroadEvent @0xc4fa6047f024e718 {
|
||||
lowMemory @51;
|
||||
stockAeb @52;
|
||||
stockLkas @98;
|
||||
lateralManeuver @99;
|
||||
ldw @53;
|
||||
carUnrecognized @54;
|
||||
invalidLkasSetting @55;
|
||||
@@ -1241,6 +1242,10 @@ struct DriverAssistance {
|
||||
# FCW, AEB, etc. will go here
|
||||
}
|
||||
|
||||
struct LateralManeuverPlan {
|
||||
desiredCurvature @0 :Float32; # 1/m
|
||||
}
|
||||
|
||||
struct LongitudinalPlan @0xe00b5b3eba12876c {
|
||||
modelMonoTime @9 :UInt64;
|
||||
hasLead @7 :Bool;
|
||||
@@ -1426,6 +1431,8 @@ struct LivePose {
|
||||
posenetOK @5 :Bool = false;
|
||||
sensorsOK @6 :Bool = false;
|
||||
|
||||
timestamp @8 :UInt64;
|
||||
|
||||
debugFilterState @7 :FilterState;
|
||||
|
||||
struct XYZMeasurement {
|
||||
@@ -2169,12 +2176,14 @@ struct DriverStateV2 {
|
||||
facePosition @2 :List(Float32);
|
||||
facePositionStd @3 :List(Float32);
|
||||
faceProb @4 :Float32;
|
||||
leftEyeProb @5 :Float32;
|
||||
rightEyeProb @6 :Float32;
|
||||
leftBlinkProb @7 :Float32;
|
||||
rightBlinkProb @8 :Float32;
|
||||
sunglassesProb @9 :Float32;
|
||||
eyesVisibleProb @14 :Float32;
|
||||
eyesClosedProb @15 :Float32;
|
||||
phoneProb @13 :Float32;
|
||||
leftEyeProbDEPRECATED @5 :Float32;
|
||||
rightEyeProbDEPRECATED @6 :Float32;
|
||||
leftBlinkProbDEPRECATED @7 :Float32;
|
||||
rightBlinkProbDEPRECATED @8 :Float32;
|
||||
sunglassesProbDEPRECATED @9 :Float32;
|
||||
notReadyProbDEPRECATED @12 :List(Float32);
|
||||
occludedProbDEPRECATED @10 :Float32;
|
||||
readyProbDEPRECATED @11 :List(Float32);
|
||||
@@ -2610,6 +2619,8 @@ struct Event {
|
||||
bookmarkButton @148 :UserBookmark;
|
||||
audioFeedback @149 :AudioFeedback;
|
||||
|
||||
lateralManeuverPlan @150 :LateralManeuverPlan;
|
||||
|
||||
# *********** debug ***********
|
||||
testJoystick @52 :Joystick;
|
||||
roadEncodeData @86 :EncodeData;
|
||||
|
||||
@@ -49,6 +49,7 @@ _services: dict[str, tuple] = {
|
||||
"carControl": (True, 100., 10),
|
||||
"carOutput": (True, 100., 10),
|
||||
"longitudinalPlan": (True, 20., 10),
|
||||
"lateralManeuverPlan": (True, 20.),
|
||||
"driverAssistance": (True, 20., 20),
|
||||
"procLog": (True, 0.5, 15, QueueSize.BIG),
|
||||
"gpsLocationExternal": (True, 10., 10),
|
||||
|
||||
@@ -82,6 +82,7 @@ inline static std::unordered_map<std::string, ParamKeyAttributes> keys = {
|
||||
{"LiveParametersV2", {PERSISTENT, BYTES}},
|
||||
{"LiveTorqueParameters", {PERSISTENT | DONT_LOG, BYTES}},
|
||||
{"LocationFilterInitialState", {PERSISTENT, BYTES}},
|
||||
{"LateralManeuverMode", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, BOOL}},
|
||||
{"LongitudinalManeuverMode", {CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION, BOOL}},
|
||||
{"LongitudinalPersonality", {PERSISTENT | BACKUP, INT, std::to_string(static_cast<int>(cereal::LongitudinalPersonality::STANDARD))}},
|
||||
{"NetworkMetered", {PERSISTENT | BACKUP, BOOL}},
|
||||
|
||||
@@ -39,7 +39,7 @@ All of these are examples of good PRs:
|
||||
### First contribution
|
||||
|
||||
[Projects / openpilot bounties](https://github.com/orgs/commaai/projects/26/views/1?pane=info) is the best place to get started and goes in-depth on what's expected when working on a bounty.
|
||||
There are a lot of bounties that don't require a comma 3X or a car.
|
||||
There are a lot of bounties that don't require a comma four or a car.
|
||||
|
||||
## Pull Requests
|
||||
|
||||
|
||||
@@ -6,4 +6,4 @@
|
||||
* **segment**: routes are split into one minute chunks called segments.
|
||||
* **comma connect**: the web viewer for all your routes; check it out at [connect.comma.ai](https://connect.comma.ai).
|
||||
* **panda**: this is the secondary processor on the device that implements the functional safety and directly talks to the car over CAN. See the [panda repo](https://github.com/commaai/panda).
|
||||
* **comma 3X**: the latest hardware by comma.ai for running openpilot. more info at [comma.ai/shop](https://comma.ai/shop).
|
||||
* **comma four**: the latest hardware by comma.ai for running openpilot. more info at [comma.ai/shop/comma-four](https://www.comma.ai/shop/comma-four).
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
|
||||
## How do I use it?
|
||||
|
||||
openpilot is designed to be used on the comma 3X.
|
||||
openpilot is designed to be used on the comma four.
|
||||
|
||||
## How does it work?
|
||||
|
||||
|
||||
@@ -1,15 +1,15 @@
|
||||
# connect to a comma 3X
|
||||
# connect to a comma four
|
||||
|
||||
A comma 3X is a normal [Linux](https://github.com/commaai/agnos-builder) computer that exposes [SSH](https://wiki.archlinux.org/title/Secure_Shell) and a [serial console](https://wiki.archlinux.org/title/Working_with_the_serial_console).
|
||||
A comma four is a normal [Linux](https://github.com/commaai/agnos-builder) computer that exposes [SSH](https://wiki.archlinux.org/title/Secure_Shell) and a [serial console](https://wiki.archlinux.org/title/Working_with_the_serial_console).
|
||||
|
||||
## Serial Console
|
||||
|
||||
On both the comma three and 3X, the serial console is accessible from the main OBD-C port.
|
||||
Connect the comma 3X to your computer with a normal USB C cable, or use a [comma serial](https://comma.ai/shop/comma-serial) for steady 12V power.
|
||||
On both the comma three and comma four, the serial console is accessible from the main OBD-C port.
|
||||
Connect the comma four to your computer with a normal USB C cable, or use a [comma serial](https://comma.ai/shop/comma-serial) for steady 12V power.
|
||||
|
||||
On the comma three, the serial console is exposed through a UART-to-USB chip, and `tools/scripts/serial.sh` can be used to connect.
|
||||
|
||||
On the comma 3X, the serial console is accessible through the [panda](https://github.com/commaai/panda) using the `panda/tests/som_debug.sh` script.
|
||||
On the comma four, the serial console is accessible through the [panda](https://github.com/commaai/panda) using the `panda/tests/som_debug.sh` script.
|
||||
|
||||
* Username: `comma`
|
||||
* Password: `comma`
|
||||
@@ -45,7 +45,7 @@ In order to use ADB on your device, you'll need to perform the following steps u
|
||||
* Here's an example command for connecting to your device using its tethered connection: `adb connect 192.168.43.1:5555`
|
||||
|
||||
> [!NOTE]
|
||||
> The default port for ADB is 5555 on the comma 3X.
|
||||
> The default port for ADB is 5555 on the comma four.
|
||||
|
||||
For more info on ADB, see the [Android Debug Bridge (ADB) documentation](https://developer.android.com/tools/adb).
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@ Replaying is a critical tool for openpilot development and debugging.
|
||||
Just run `tools/replay/replay --demo`.
|
||||
|
||||
## Replaying CAN data
|
||||
*Hardware required: jungle and comma 3X*
|
||||
*Hardware required: jungle and comma four*
|
||||
|
||||
1. Connect your PC to a jungle.
|
||||
2.
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
|
||||
In 30 minutes, we'll get an openpilot development environment set up on your computer and make some changes to openpilot's UI.
|
||||
|
||||
And if you have a comma 3X, we'll deploy the change to your device for testing.
|
||||
And if you have a comma four, we'll deploy the change to your device for testing.
|
||||
|
||||
## 1. Set up your development environment
|
||||
|
||||
|
||||
@@ -7,6 +7,7 @@ source "$DIR/launch_env.sh"
|
||||
function agnos_init {
|
||||
# TODO: move this to agnos
|
||||
sudo rm -f /data/etc/NetworkManager/system-connections/*.nmmeta
|
||||
rm -f /data/scons_cache/config.lock
|
||||
|
||||
# set success flag for current boot slot
|
||||
sudo abctl --set_success
|
||||
|
||||
Submodule msgq_repo updated: ed2777747d...b7688b9bd7
Submodule opendbc_repo updated: b178bc5d4e...2689d9ffc3
2
panda
2
panda
Submodule panda updated: 6ddc631bdd...01a2c250f9
@@ -107,6 +107,7 @@ dev = [
|
||||
]
|
||||
|
||||
tools = [
|
||||
"imgui @ git+https://github.com/commaai/dependencies.git@release-imgui#subdirectory=imgui",
|
||||
"metadrive-simulator @ git+https://github.com/commaai/metadrive.git@minimal ; (platform_machine != 'aarch64')",
|
||||
]
|
||||
|
||||
|
||||
Submodule rednose_repo updated: 6ccb8d0556...7ffefa3d88
@@ -38,6 +38,11 @@ if __name__ == "__main__":
|
||||
continue
|
||||
|
||||
fn = os.path.basename(f)
|
||||
master = get_checkpoint(MASTER_PATH + MODEL_PATH + fn)
|
||||
master_path = MASTER_PATH + MODEL_PATH + fn
|
||||
if os.path.exists(master_path):
|
||||
master = get_checkpoint(master_path)
|
||||
master_col = f"[{master}](https://reporter.comma.life/experiment/{master})"
|
||||
else:
|
||||
master_col = "N/A (new model)"
|
||||
pr = get_checkpoint(BASEDIR + MODEL_PATH + fn)
|
||||
print("|", fn, "|", f"[{master}](https://reporter.comma.life/experiment/{master})", "|", f"[{pr}](https://reporter.comma.life/experiment/{pr})", "|")
|
||||
print("|", fn, "|", master_col, "|", f"[{pr}](https://reporter.comma.life/experiment/{pr})", "|")
|
||||
|
||||
Binary file not shown.
@@ -98,7 +98,6 @@ class Car:
|
||||
break
|
||||
|
||||
alpha_long_allowed = self.params.get_bool("AlphaLongitudinalEnabled")
|
||||
num_pandas = len(messaging.recv_one_retry(self.sm.sock['pandaStates']).pandaStates)
|
||||
|
||||
cached_params = None
|
||||
cached_params_raw = self.params.get("CarParamsCache")
|
||||
@@ -109,7 +108,7 @@ class Car:
|
||||
fixed_fingerprint = (self.params.get("CarPlatformBundle") or {}).get("platform", None)
|
||||
init_params_list_sp = sunnypilot_interfaces.initialize_params(self.params)
|
||||
|
||||
self.CI = get_car(*self.can_callbacks, obd_callback(self.params), alpha_long_allowed, is_release, num_pandas, cached_params,
|
||||
self.CI = get_car(*self.can_callbacks, obd_callback(self.params), alpha_long_allowed, is_release, cached_params,
|
||||
fixed_fingerprint, init_params_list_sp, is_release_sp)
|
||||
sunnypilot_interfaces.setup_interfaces(self.CI, self.params)
|
||||
self.RI = interfaces[self.CI.CP.carFingerprint].RadarInterface(self.CI.CP, self.CI.CP_SP)
|
||||
|
||||
@@ -42,7 +42,7 @@ class Controls(ControlsExt):
|
||||
self.CI = interfaces[self.CP.carFingerprint](self.CP, self.CP_SP)
|
||||
|
||||
self.sm = messaging.SubMaster(['liveDelay', 'liveParameters', 'liveTorqueParameters', 'modelV2', 'selfdriveState',
|
||||
'liveCalibration', 'livePose', 'longitudinalPlan', 'carState', 'carOutput',
|
||||
'liveCalibration', 'livePose', 'longitudinalPlan', 'lateralManeuverPlan', 'carState', 'carOutput',
|
||||
'driverMonitoringState', 'onroadEvents', 'driverAssistance', 'liveDelay'] + self.sm_services_ext,
|
||||
poll='selfdriveState')
|
||||
self.pm = messaging.PubMaster(['carControl', 'controlsState'] + self.pm_services_ext)
|
||||
@@ -135,7 +135,10 @@ class Controls(ControlsExt):
|
||||
|
||||
# Steering PID loop and lateral MPC
|
||||
# Reset desired curvature to current to avoid violating the limits on engage
|
||||
new_desired_curvature = model_v2.action.desiredCurvature if CC.latActive else self.curvature
|
||||
if self.sm.valid['lateralManeuverPlan']:
|
||||
new_desired_curvature = self.sm['lateralManeuverPlan'].desiredCurvature if CC.latActive else self.curvature
|
||||
else:
|
||||
new_desired_curvature = model_v2.action.desiredCurvature if CC.latActive else self.curvature
|
||||
self.desired_curvature, curvature_limited = clip_curvature(CS.vEgo, self.desired_curvature, new_desired_curvature, lp.roll)
|
||||
lat_delay = self.sm["liveDelay"].lateralDelay + LAT_SMOOTH_SECONDS
|
||||
|
||||
|
||||
@@ -11,7 +11,7 @@ class LatControlAngle(LatControl):
|
||||
def __init__(self, CP, CP_SP, CI, dt):
|
||||
super().__init__(CP, CP_SP, CI, dt)
|
||||
self.sat_check_min_speed = 5.
|
||||
self.use_steer_limited_by_safety = CP.brand == "tesla"
|
||||
self.use_steer_limited_by_safety = CP.brand in ("tesla", "hyundai")
|
||||
|
||||
def update(self, active, CS, VM, params, steer_limited_by_safety, desired_curvature, calibrated_pose, curvature_limited, lat_delay):
|
||||
angle_log = log.ControlsState.LateralAngleState.new_message()
|
||||
|
||||
@@ -50,8 +50,10 @@ def simulate_straight_road_msgs(est):
|
||||
lat_accels = TORQUE_TUNE.latAccelFactor * steer_torques
|
||||
for t, steer_torque, lat_accel in zip(ts, steer_torques, lat_accels, strict=True):
|
||||
carOutput.actuatorsOutput.torque = float(-steer_torque)
|
||||
livePose.orientationNED.x = float(np.deg2rad(ROLL_BIAS_DEG))
|
||||
livePose.angularVelocityDevice.z = float(lat_accel / V_EGO)
|
||||
livePose.orientationNED = {'x': float(np.deg2rad(ROLL_BIAS_DEG)), 'valid': True}
|
||||
livePose.angularVelocityDevice = {'z': float(lat_accel / V_EGO), 'valid': True}
|
||||
livePose.inputsOK, livePose.sensorsOK, livePose.posenetOK = True, True, True
|
||||
livePose.timestamp = int(t * 1e9)
|
||||
for which, msg in (('carControl', carControl), ('carOutput', carOutput), ('carState', carState), ('livePose', livePose)):
|
||||
est.handle_log(t, which, msg)
|
||||
|
||||
|
||||
@@ -45,8 +45,6 @@ if __name__ == "__main__":
|
||||
extra[(Ecu.unknown, 0x750, i)] = []
|
||||
extra = {"any": {"debug": extra}}
|
||||
|
||||
num_pandas = len(messaging.recv_one_retry(pandaStates_sock).pandaStates)
|
||||
|
||||
t = time.monotonic()
|
||||
print("Getting vin...")
|
||||
set_obd_multiplexing(True)
|
||||
@@ -56,7 +54,7 @@ if __name__ == "__main__":
|
||||
print()
|
||||
|
||||
t = time.monotonic()
|
||||
fw_vers = get_fw_versions(*can_callbacks, set_obd_multiplexing, query_brand=args.brand, extra=extra, num_pandas=num_pandas, progress=True)
|
||||
fw_vers = get_fw_versions(*can_callbacks, set_obd_multiplexing, query_brand=args.brand, extra=extra, progress=True)
|
||||
_, candidates = match_fw_to_car(fw_vers, vin)
|
||||
|
||||
print()
|
||||
|
||||
@@ -44,7 +44,7 @@ if __name__ == "__main__":
|
||||
parser = argparse.ArgumentParser(description='View back and forth ISO-TP communication between various ECUs given an address')
|
||||
parser.add_argument('route', nargs='?', help='Route name, live if not specified')
|
||||
parser.add_argument('--addrs', nargs='*', default=[], help='List of tx address to view (0x7e0 for engine)')
|
||||
parser.add_argument('--rxoffset', default='')
|
||||
parser.add_argument('--rxoffset', default='0x8')
|
||||
args = parser.parse_args()
|
||||
|
||||
addrs = [int(addr, base=16) if addr.startswith('0x') else int(addr) for addr in args.addrs]
|
||||
|
||||
@@ -28,6 +28,9 @@ INPUT_INVALID_LIMIT = 2.0 # 1 (camodo) / 9 (sensor) bad input[s] ignored
|
||||
INPUT_INVALID_RECOVERY = 10.0 # ~10 secs to resume after exceeding allowed bad inputs by one
|
||||
POSENET_STD_INITIAL_VALUE = 10.0
|
||||
POSENET_STD_HIST_HALF = 20
|
||||
CAM_ODO_POSE_DELAY = 0.1 # dependent on the vision model context frames and temporal frequency (current model is 5 fps with 2 context frames)
|
||||
CAM_ODO_ROT_STD_MULT = 10
|
||||
CAM_ODO_TRANS_STD_MULT = 4
|
||||
|
||||
|
||||
def calculate_invalid_input_decay(invalid_limit, recovery_time, frequency):
|
||||
@@ -155,6 +158,8 @@ class LocationEstimator:
|
||||
self.device_from_calib = rot_from_euler(calib)
|
||||
|
||||
elif which == "cameraOdometry":
|
||||
# camera odometry is delayed depending on the model context frames and temporal frequency
|
||||
t = msg.timestampEof * 1e-9 - CAM_ODO_POSE_DELAY
|
||||
if not self._validate_timestamp(t):
|
||||
return HandleLogResult.TIMING_INVALID
|
||||
|
||||
@@ -177,8 +182,8 @@ class LocationEstimator:
|
||||
self.posenet_stds[-1] = trans_calib_std[0]
|
||||
|
||||
# Multiply by N to avoid to high certainty in kalman filter because of temporally correlated noise
|
||||
rot_calib_std *= 10
|
||||
trans_calib_std *= 2
|
||||
rot_calib_std *= CAM_ODO_ROT_STD_MULT
|
||||
trans_calib_std *= CAM_ODO_TRANS_STD_MULT
|
||||
|
||||
rot_device_std = rotate_std(self.device_from_calib, rot_calib_std)
|
||||
trans_device_std = rotate_std(self.device_from_calib, trans_calib_std)
|
||||
@@ -234,6 +239,7 @@ class LocationEstimator:
|
||||
livePose.inputsOK = inputs_valid
|
||||
livePose.posenetOK = not std_spike or self.car_speed <= 5.0
|
||||
livePose.sensorsOK = sensors_valid
|
||||
livePose.timestamp = int(np.nan_to_num(self.kf.t) * 1e9)
|
||||
|
||||
return msg
|
||||
|
||||
|
||||
@@ -47,13 +47,13 @@ class PoseKalman(KalmanFilter):
|
||||
# process noise
|
||||
Q = np.diag([0.001**2, 0.001**2, 0.001**2,
|
||||
0.01**2, 0.01**2, 0.01**2,
|
||||
0.1**2, 0.1**2, 0.1**2,
|
||||
0.085**2, 0.085**2, 0.085**2,
|
||||
(0.005 / 100)**2, (0.005 / 100)**2, (0.005 / 100)**2,
|
||||
3**2, 3**2, 3**2,
|
||||
0.005**2, 0.005**2, 0.005**2])
|
||||
|
||||
obs_noise = {ObservationKind.PHONE_GYRO: np.diag([0.025**2, 0.025**2, 0.025**2]),
|
||||
ObservationKind.PHONE_ACCEL: np.diag([.5**2, .5**2, .5**2]),
|
||||
ObservationKind.PHONE_ACCEL: np.diag([0.75**2, 0.75**2, 0.75**2]),
|
||||
ObservationKind.CAMERA_ODO_TRANSLATION: np.diag([0.5**2, 0.5**2, 0.5**2]),
|
||||
ObservationKind.CAMERA_ODO_ROTATION: np.diag([0.05**2, 0.05**2, 0.05**2])}
|
||||
|
||||
|
||||
@@ -65,6 +65,7 @@ class VehicleParamsLearner:
|
||||
|
||||
def handle_log(self, t: float, which: str, msg: capnp._DynamicStructReader):
|
||||
if which == 'livePose':
|
||||
t = msg.timestamp * 1e-9
|
||||
device_pose = Pose.from_live_pose(msg)
|
||||
calibrated_pose = self.calibrator.build_calibrated_pose(device_pose)
|
||||
|
||||
|
||||
@@ -3,6 +3,7 @@ from collections import defaultdict
|
||||
from enum import Enum
|
||||
|
||||
from openpilot.tools.lib.logreader import LogReader
|
||||
from openpilot.selfdrive.locationd.lagd import masked_symmetric_moving_average
|
||||
from openpilot.selfdrive.test.process_replay.migration import migrate_all
|
||||
from openpilot.selfdrive.test.process_replay.process_replay import replay_process_with_name
|
||||
|
||||
@@ -15,6 +16,7 @@ SELECT_COMPARE_FIELDS = {
|
||||
'inputs_flag': ['inputsOK'],
|
||||
'sensors_flag': ['sensorsOK'],
|
||||
}
|
||||
SMOOTH_FIELDS = ['yaw_rate', 'roll']
|
||||
JUNK_IDX = 100
|
||||
CONSISTENT_SPIKES_COUNT = 10
|
||||
|
||||
@@ -32,6 +34,8 @@ class Scenario(Enum):
|
||||
|
||||
|
||||
def get_select_fields_data(logs):
|
||||
def sig_smooth(signal):
|
||||
return masked_symmetric_moving_average(signal, np.ones_like(signal), 5, 1.0)
|
||||
def get_nested_keys(msg, keys):
|
||||
val = None
|
||||
for key in keys:
|
||||
@@ -44,6 +48,8 @@ def get_select_fields_data(logs):
|
||||
data[key].append(get_nested_keys(msg, fields))
|
||||
for key in data:
|
||||
data[key] = np.array(data[key][JUNK_IDX:], dtype=float)
|
||||
if key in SMOOTH_FIELDS:
|
||||
data[key] = sig_smooth(data[key])
|
||||
return data
|
||||
|
||||
|
||||
@@ -110,7 +116,7 @@ class TestLocationdScenarios:
|
||||
"""
|
||||
orig_data, replayed_data = run_scenarios(Scenario.BASE, self.logs)
|
||||
assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.35))
|
||||
assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.55))
|
||||
assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.35))
|
||||
|
||||
def test_gyro_off(self):
|
||||
"""
|
||||
@@ -135,7 +141,7 @@ class TestLocationdScenarios:
|
||||
"""
|
||||
orig_data, replayed_data = run_scenarios(Scenario.GYRO_SPIKE_MIDWAY, self.logs)
|
||||
assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.35))
|
||||
assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.55))
|
||||
assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.35))
|
||||
assert np.all(replayed_data['inputs_flag'] == orig_data['inputs_flag'])
|
||||
assert np.all(replayed_data['sensors_flag'] == orig_data['sensors_flag'])
|
||||
|
||||
@@ -169,7 +175,7 @@ class TestLocationdScenarios:
|
||||
"""
|
||||
orig_data, replayed_data = run_scenarios(Scenario.ACCEL_SPIKE_MIDWAY, self.logs)
|
||||
assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.35))
|
||||
assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.55))
|
||||
assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.35))
|
||||
|
||||
def test_single_timing_spike(self):
|
||||
"""
|
||||
|
||||
@@ -188,7 +188,9 @@ class TorqueEstimator(ParameterEstimator, TorqueEstimatorExt):
|
||||
self.lag = get_lat_delay(self.params, msg.lateralDelay)
|
||||
# calculate lateral accel from past steering torque
|
||||
elif which == "livePose":
|
||||
if len(self.raw_points['steer_torque']) == self.hist_len:
|
||||
is_valid = msg.angularVelocityDevice.valid and msg.orientationNED.valid and msg.inputsOK and msg.sensorsOK and msg.posenetOK
|
||||
if len(self.raw_points['steer_torque']) == self.hist_len and is_valid:
|
||||
t = msg.timestamp * 1e-9
|
||||
device_pose = Pose.from_live_pose(msg)
|
||||
calibrated_pose = self.calibrator.build_calibrated_pose(device_pose)
|
||||
angular_velocity_calibrated = calibrated_pose.angular_velocity
|
||||
|
||||
@@ -21,7 +21,7 @@ tg_flags = {
|
||||
}.get(arch, 'DEV=CPU CPU_LLVM=1 THREADS=0 IMAGE=0')
|
||||
|
||||
# Get model metadata
|
||||
for model_name in ['driving_vision', 'driving_policy', 'dmonitoring_model']:
|
||||
for model_name in ['driving_vision', 'driving_off_policy', 'driving_on_policy', 'dmonitoring_model']:
|
||||
fn = File(f"models/{model_name}").abspath
|
||||
script_files = [File(Dir("#selfdrive/modeld").File("get_model_metadata.py").abspath)]
|
||||
cmd = f'{tg_flags} python3 {Dir("#selfdrive/modeld").abspath}/get_model_metadata.py {fn}.onnx'
|
||||
@@ -59,19 +59,5 @@ def tg_compile(flags, model_name):
|
||||
)
|
||||
|
||||
# Compile small models
|
||||
for model_name in ['driving_vision', 'driving_policy', 'dmonitoring_model']:
|
||||
for model_name in ['driving_vision', 'driving_off_policy', 'driving_on_policy', 'dmonitoring_model']:
|
||||
tg_compile(tg_flags, model_name)
|
||||
|
||||
# Compile BIG model if USB GPU is available
|
||||
if "USBGPU" in os.environ:
|
||||
import subprocess
|
||||
# because tg doesn't support multi-process
|
||||
devs = subprocess.check_output('python3 -c "from tinygrad import Device; print(list(Device.get_available_devices()))"', shell=True, cwd=env.Dir('#').abspath)
|
||||
if b"AMD" in devs:
|
||||
print("USB GPU detected... building")
|
||||
flags = "DEV=AMD AMD_IFACE=USB AMD_LLVM=1 NOLOCALS=0 IMAGE=0"
|
||||
bp = tg_compile(flags, "big_driving_policy")
|
||||
bv = tg_compile(flags, "big_driving_vision")
|
||||
lenv.SideEffect('lock', [bp, bv]) # tg doesn't support multi-process so build serially
|
||||
else:
|
||||
print("USB GPU not detected... skipping")
|
||||
|
||||
@@ -80,7 +80,7 @@ def parse_model_output(model_output):
|
||||
face_descs = model_output[f'face_descs_{ds_suffix}']
|
||||
parsed[f'face_descs_{ds_suffix}'] = face_descs[:, :-6]
|
||||
parsed[f'face_descs_{ds_suffix}_std'] = safe_exp(face_descs[:, -6:])
|
||||
for key in ['face_prob', 'left_eye_prob', 'right_eye_prob','left_blink_prob', 'right_blink_prob', 'sunglasses_prob', 'using_phone_prob']:
|
||||
for key in ['face_prob', 'eyes_visible_prob', 'eyes_closed_prob', 'using_phone_prob']:
|
||||
parsed[f'{key}_{ds_suffix}'] = sigmoid(model_output[f'{key}_{ds_suffix}'])
|
||||
return parsed
|
||||
|
||||
@@ -90,11 +90,8 @@ def fill_driver_data(msg, model_output, ds_suffix):
|
||||
msg.facePosition = model_output[f'face_descs_{ds_suffix}'][0, 3:5].tolist()
|
||||
msg.facePositionStd = model_output[f'face_descs_{ds_suffix}_std'][0, 3:5].tolist()
|
||||
msg.faceProb = model_output[f'face_prob_{ds_suffix}'][0, 0].item()
|
||||
msg.leftEyeProb = model_output[f'left_eye_prob_{ds_suffix}'][0, 0].item()
|
||||
msg.rightEyeProb = model_output[f'right_eye_prob_{ds_suffix}'][0, 0].item()
|
||||
msg.leftBlinkProb = model_output[f'left_blink_prob_{ds_suffix}'][0, 0].item()
|
||||
msg.rightBlinkProb = model_output[f'right_blink_prob_{ds_suffix}'][0, 0].item()
|
||||
msg.sunglassesProb = model_output[f'sunglasses_prob_{ds_suffix}'][0, 0].item()
|
||||
msg.eyesVisibleProb = model_output[f'eyes_visible_prob_{ds_suffix}'][0, 0].item()
|
||||
msg.eyesClosedProb = model_output[f'eyes_closed_prob_{ds_suffix}'][0, 0].item()
|
||||
msg.phoneProb = model_output[f'using_phone_prob_{ds_suffix}'][0, 0].item()
|
||||
|
||||
def get_driverstate_packet(model_output, frame_id: int, location_ts: int, exec_time: float, gpu_exec_time: float):
|
||||
|
||||
@@ -37,11 +37,13 @@ from openpilot.sunnypilot.modeld_v2.modeld_base import ModelStateBase
|
||||
PROCESS_NAME = "selfdrive.modeld.modeld"
|
||||
SEND_RAW_PRED = os.getenv('SEND_RAW_PRED')
|
||||
|
||||
VISION_PKL_PATH = Path(__file__).parent / 'models/driving_vision_tinygrad.pkl'
|
||||
POLICY_PKL_PATH = Path(__file__).parent / 'models/driving_policy_tinygrad.pkl'
|
||||
VISION_METADATA_PATH = Path(__file__).parent / 'models/driving_vision_metadata.pkl'
|
||||
POLICY_METADATA_PATH = Path(__file__).parent / 'models/driving_policy_metadata.pkl'
|
||||
MODELS_DIR = Path(__file__).parent / 'models'
|
||||
VISION_PKL_PATH = MODELS_DIR / 'driving_vision_tinygrad.pkl'
|
||||
VISION_METADATA_PATH = MODELS_DIR / 'driving_vision_metadata.pkl'
|
||||
ON_POLICY_PKL_PATH = MODELS_DIR / 'driving_on_policy_tinygrad.pkl'
|
||||
ON_POLICY_METADATA_PATH = MODELS_DIR / 'driving_on_policy_metadata.pkl'
|
||||
OFF_POLICY_PKL_PATH = MODELS_DIR / 'driving_off_policy_tinygrad.pkl'
|
||||
OFF_POLICY_METADATA_PATH = MODELS_DIR / 'driving_off_policy_metadata.pkl'
|
||||
|
||||
LAT_SMOOTH_SECONDS = 0.0
|
||||
LONG_SMOOTH_SECONDS = 0.3
|
||||
@@ -156,7 +158,13 @@ class ModelState(ModelStateBase):
|
||||
self.vision_output_slices = vision_metadata['output_slices']
|
||||
vision_output_size = vision_metadata['output_shapes']['outputs'][1]
|
||||
|
||||
with open(POLICY_METADATA_PATH, 'rb') as f:
|
||||
with open(OFF_POLICY_METADATA_PATH, 'rb') as f:
|
||||
off_policy_metadata = pickle.load(f)
|
||||
self.off_policy_input_shapes = off_policy_metadata['input_shapes']
|
||||
self.off_policy_output_slices = off_policy_metadata['output_slices']
|
||||
off_policy_output_size = off_policy_metadata['output_shapes']['outputs'][1]
|
||||
|
||||
with open(ON_POLICY_METADATA_PATH, 'rb') as f:
|
||||
policy_metadata = pickle.load(f)
|
||||
self.policy_input_shapes = policy_metadata['input_shapes']
|
||||
self.policy_output_slices = policy_metadata['output_slices']
|
||||
@@ -180,11 +188,13 @@ class ModelState(ModelStateBase):
|
||||
self.vision_output = np.zeros(vision_output_size, dtype=np.float32)
|
||||
self.policy_inputs = {k: Tensor(v, device='NPY').realize() for k,v in self.numpy_inputs.items()}
|
||||
self.policy_output = np.zeros(policy_output_size, dtype=np.float32)
|
||||
self.off_policy_output = np.zeros(off_policy_output_size, dtype=np.float32)
|
||||
self.parser = Parser()
|
||||
self.frame_buf_params : dict[str, tuple[int, int, int, int]] = {}
|
||||
self.update_imgs = None
|
||||
self.vision_run = pickle.loads(read_file_chunked(str(VISION_PKL_PATH)))
|
||||
self.policy_run = pickle.loads(read_file_chunked(str(POLICY_PKL_PATH)))
|
||||
self.policy_run = pickle.loads(read_file_chunked(str(ON_POLICY_PKL_PATH)))
|
||||
self.off_policy_run = pickle.loads(read_file_chunked(str(OFF_POLICY_PKL_PATH)))
|
||||
|
||||
def slice_outputs(self, model_outputs: np.ndarray, output_slices: dict[str, slice]) -> dict[str, np.ndarray]:
|
||||
parsed_model_outputs = {k: model_outputs[np.newaxis, v] for k,v in output_slices.items()}
|
||||
@@ -233,9 +243,17 @@ class ModelState(ModelStateBase):
|
||||
|
||||
self.policy_output = self.policy_run(**self.policy_inputs).contiguous().realize().uop.base.buffer.numpy().flatten()
|
||||
policy_outputs_dict = self.parser.parse_policy_outputs(self.slice_outputs(self.policy_output, self.policy_output_slices))
|
||||
combined_outputs_dict = {**vision_outputs_dict, **policy_outputs_dict}
|
||||
|
||||
self.off_policy_output = self.off_policy_run(**self.policy_inputs).contiguous().realize().uop.base.buffer.numpy()
|
||||
off_policy_outputs_dict = self.parser.parse_off_policy_outputs(self.slice_outputs(self.off_policy_output, self.off_policy_output_slices))
|
||||
off_policy_outputs_dict.pop('plan')
|
||||
|
||||
|
||||
combined_outputs_dict = {**vision_outputs_dict, **off_policy_outputs_dict, **policy_outputs_dict}
|
||||
if 'planplus' in combined_outputs_dict and 'plan' in combined_outputs_dict:
|
||||
combined_outputs_dict['plan'] = combined_outputs_dict['plan'] + combined_outputs_dict['planplus']
|
||||
if SEND_RAW_PRED:
|
||||
combined_outputs_dict['raw_pred'] = np.concatenate([self.vision_output.copy(), self.policy_output.copy()])
|
||||
combined_outputs_dict['raw_pred'] = np.concatenate([self.vision_output.copy(), self.policy_output.copy(), self.off_policy_output.copy()])
|
||||
|
||||
return combined_outputs_dict
|
||||
|
||||
|
||||
@@ -1 +0,0 @@
|
||||
driving_policy.onnx
|
||||
@@ -1 +0,0 @@
|
||||
driving_vision.onnx
|
||||
Binary file not shown.
BIN
selfdrive/modeld/models/driving_off_policy.onnx
LFS
Normal file
BIN
selfdrive/modeld/models/driving_off_policy.onnx
LFS
Normal file
Binary file not shown.
BIN
selfdrive/modeld/models/driving_on_policy.onnx
LFS
Normal file
BIN
selfdrive/modeld/models/driving_on_policy.onnx
LFS
Normal file
Binary file not shown.
Binary file not shown.
Binary file not shown.
@@ -96,11 +96,17 @@ class Parser:
|
||||
self.parse_mdn('pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,))
|
||||
self.parse_mdn('wide_from_device_euler', outs, in_N=0, out_N=0, out_shape=(ModelConstants.WIDE_FROM_DEVICE_WIDTH,))
|
||||
self.parse_mdn('road_transform', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,))
|
||||
self.parse_categorical_crossentropy('desire_pred', outs, out_shape=(ModelConstants.DESIRE_PRED_LEN,ModelConstants.DESIRE_PRED_WIDTH))
|
||||
self.parse_binary_crossentropy('meta', outs)
|
||||
return outs
|
||||
|
||||
def parse_off_policy_outputs(self, outs: dict[str, np.ndarray]) -> dict[str, np.ndarray]:
|
||||
plan_mhp = self.is_mhp(outs, 'plan', ModelConstants.IDX_N * ModelConstants.PLAN_WIDTH)
|
||||
plan_in_N, plan_out_N = (ModelConstants.PLAN_MHP_N, ModelConstants.PLAN_MHP_SELECTION) if plan_mhp else (0, 0)
|
||||
self.parse_mdn('plan', outs, in_N=plan_in_N, out_N=plan_out_N, out_shape=(ModelConstants.IDX_N, ModelConstants.PLAN_WIDTH))
|
||||
self.parse_mdn('lane_lines', outs, in_N=0, out_N=0, out_shape=(ModelConstants.NUM_LANE_LINES,ModelConstants.IDX_N,ModelConstants.LANE_LINES_WIDTH))
|
||||
self.parse_mdn('road_edges', outs, in_N=0, out_N=0, out_shape=(ModelConstants.NUM_ROAD_EDGES,ModelConstants.IDX_N,ModelConstants.LANE_LINES_WIDTH))
|
||||
self.parse_binary_crossentropy('lane_lines_prob', outs)
|
||||
self.parse_categorical_crossentropy('desire_pred', outs, out_shape=(ModelConstants.DESIRE_PRED_LEN,ModelConstants.DESIRE_PRED_WIDTH))
|
||||
self.parse_binary_crossentropy('meta', outs)
|
||||
self.parse_binary_crossentropy('lead_prob', outs)
|
||||
lead_mhp = self.is_mhp(outs, 'lead', ModelConstants.LEAD_MHP_SELECTION * ModelConstants.LEAD_TRAJ_LEN * ModelConstants.LEAD_WIDTH)
|
||||
lead_in_N, lead_out_N = (ModelConstants.LEAD_MHP_N, ModelConstants.LEAD_MHP_SELECTION) if lead_mhp else (0, 0)
|
||||
@@ -120,5 +126,6 @@ class Parser:
|
||||
|
||||
def parse_outputs(self, outs: dict[str, np.ndarray]) -> dict[str, np.ndarray]:
|
||||
outs = self.parse_vision_outputs(outs)
|
||||
outs = self.parse_off_policy_outputs(outs)
|
||||
outs = self.parse_policy_outputs(outs)
|
||||
return outs
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
from math import atan2
|
||||
from math import atan2, radians
|
||||
import numpy as np
|
||||
|
||||
from cereal import car, log
|
||||
@@ -32,9 +32,8 @@ class DRIVER_MONITOR_SETTINGS:
|
||||
self._DISTRACTED_PROMPT_TIME_TILL_TERMINAL = 6.
|
||||
|
||||
self._FACE_THRESHOLD = 0.7
|
||||
self._EYE_THRESHOLD = 0.65
|
||||
self._SG_THRESHOLD = 0.9
|
||||
self._BLINK_THRESHOLD = 0.865
|
||||
self._EYE_THRESHOLD = 0.5
|
||||
self._BLINK_THRESHOLD = 0.5
|
||||
self._PHONE_THRESH = 0.5
|
||||
|
||||
self._POSE_PITCH_THRESHOLD = 0.3133
|
||||
@@ -43,6 +42,9 @@ class DRIVER_MONITOR_SETTINGS:
|
||||
self._POSE_YAW_THRESHOLD = 0.4020
|
||||
self._POSE_YAW_THRESHOLD_SLACK = 0.5042
|
||||
self._POSE_YAW_THRESHOLD_STRICT = self._POSE_YAW_THRESHOLD
|
||||
self._POSE_YAW_MIN_STEER_DEG = 30
|
||||
self._POSE_YAW_STEER_FACTOR = 0.15
|
||||
self._POSE_YAW_STEER_MAX_OFFSET = 0.3927
|
||||
self._PITCH_NATURAL_OFFSET = 0.011 # initial value before offset is learned
|
||||
self._PITCH_NATURAL_THRESHOLD = 0.449
|
||||
self._YAW_NATURAL_OFFSET = 0.075 # initial value before offset is learned
|
||||
@@ -59,7 +61,6 @@ class DRIVER_MONITOR_SETTINGS:
|
||||
self._POSESTD_THRESHOLD = 0.3
|
||||
self._HI_STD_FALLBACK_TIME = int(10 / self._DT_DMON) # fall back to wheel touch if model is uncertain for 10s
|
||||
self._DISTRACTED_FILTER_TS = 0.25 # 0.6Hz
|
||||
self._ALWAYS_ON_ALERT_MIN_SPEED = 11
|
||||
|
||||
self._POSE_CALIB_MIN_SPEED = 13 # 30 mph
|
||||
self._POSE_OFFSET_MIN_COUNT = int(60 / self._DT_DMON) # valid data counts before calibration completes, 1min cumulative
|
||||
@@ -101,6 +102,7 @@ class DriverPose:
|
||||
self.low_std = True
|
||||
self.cfactor_pitch = 1.
|
||||
self.cfactor_yaw = 1.
|
||||
self.steer_yaw_offset = 0.
|
||||
|
||||
class DriverProb:
|
||||
def __init__(self, raw_priors, max_trackable):
|
||||
@@ -108,11 +110,6 @@ class DriverProb:
|
||||
self.prob_offseter = RunningStatFilter(raw_priors=raw_priors, max_trackable=max_trackable)
|
||||
self.prob_calibrated = False
|
||||
|
||||
class DriverBlink:
|
||||
def __init__(self):
|
||||
self.left = 0.
|
||||
self.right = 0.
|
||||
|
||||
|
||||
# model output refers to center of undistorted+leveled image
|
||||
EFL = 598.0 # focal length in K
|
||||
@@ -147,7 +144,7 @@ class DriverMonitoring:
|
||||
wheelpos_filter_raw_priors = (self.settings._WHEELPOS_DATA_AVG, self.settings._WHEELPOS_DATA_VAR, 2)
|
||||
self.wheelpos = DriverProb(raw_priors=wheelpos_filter_raw_priors, max_trackable=self.settings._WHEELPOS_MAX_COUNT)
|
||||
self.pose = DriverPose(settings=self.settings)
|
||||
self.blink = DriverBlink()
|
||||
self.blink_prob = 0.
|
||||
self.phone_prob = 0.
|
||||
|
||||
self.always_on = always_on
|
||||
@@ -238,7 +235,11 @@ class DriverMonitoring:
|
||||
yaw_error = self.pose.yaw - min(max(self.pose.yaw_offseter.filtered_stat.mean(),
|
||||
self.settings._YAW_MIN_OFFSET), self.settings._YAW_MAX_OFFSET)
|
||||
pitch_error = 0 if pitch_error > 0 else abs(pitch_error) # no positive pitch limit
|
||||
yaw_error = abs(yaw_error)
|
||||
|
||||
if yaw_error * self.pose.steer_yaw_offset > 0: # unidirectional
|
||||
yaw_error = max(abs(yaw_error) - min(abs(self.pose.steer_yaw_offset), self.settings._POSE_YAW_STEER_MAX_OFFSET), 0.)
|
||||
else:
|
||||
yaw_error = abs(yaw_error)
|
||||
|
||||
pitch_threshold = self.settings._POSE_PITCH_THRESHOLD * self.pose.cfactor_pitch if self.pose.calibrated else self.settings._PITCH_NATURAL_THRESHOLD
|
||||
yaw_threshold = self.settings._POSE_YAW_THRESHOLD * self.pose.cfactor_yaw
|
||||
@@ -246,7 +247,7 @@ class DriverMonitoring:
|
||||
if pitch_error > pitch_threshold or yaw_error > yaw_threshold:
|
||||
distracted_types.append(DistractedType.DISTRACTED_POSE)
|
||||
|
||||
if (self.blink.left + self.blink.right)*0.5 > self.settings._BLINK_THRESHOLD:
|
||||
if self.blink_prob > self.settings._BLINK_THRESHOLD:
|
||||
distracted_types.append(DistractedType.DISTRACTED_BLINK)
|
||||
|
||||
if self.phone_prob > self.settings._PHONE_THRESH:
|
||||
@@ -254,7 +255,7 @@ class DriverMonitoring:
|
||||
|
||||
return distracted_types
|
||||
|
||||
def _update_states(self, driver_state, cal_rpy, car_speed, op_engaged, standstill, demo_mode=False):
|
||||
def _update_states(self, driver_state, cal_rpy, car_speed, op_engaged, standstill, demo_mode=False, steering_angle_deg=0.):
|
||||
rhd_pred = driver_state.wheelOnRightProb
|
||||
# calibrates only when there's movement and either face detected
|
||||
if car_speed > self.settings._WHEELPOS_CALIB_MIN_SPEED and (driver_state.leftDriverData.faceProb > self.settings._FACE_THRESHOLD or
|
||||
@@ -277,17 +278,17 @@ class DriverMonitoring:
|
||||
|
||||
self.face_detected = driver_data.faceProb > self.settings._FACE_THRESHOLD
|
||||
self.pose.roll, self.pose.pitch, self.pose.yaw = face_orientation_from_net(driver_data.faceOrientation, driver_data.facePosition, cal_rpy)
|
||||
steer_d = max(abs(steering_angle_deg) - self.settings._POSE_YAW_MIN_STEER_DEG, 0.)
|
||||
self.pose.steer_yaw_offset = radians(steer_d) * -np.sign(steering_angle_deg) * self.settings._POSE_YAW_STEER_FACTOR
|
||||
if self.wheel_on_right:
|
||||
self.pose.yaw *= -1
|
||||
self.pose.steer_yaw_offset *= -1
|
||||
self.wheel_on_right_last = self.wheel_on_right
|
||||
self.pose.pitch_std = driver_data.faceOrientationStd[0]
|
||||
self.pose.yaw_std = driver_data.faceOrientationStd[1]
|
||||
model_std_max = max(self.pose.pitch_std, self.pose.yaw_std)
|
||||
self.pose.low_std = model_std_max < self.settings._POSESTD_THRESHOLD
|
||||
self.blink.left = driver_data.leftBlinkProb * (driver_data.leftEyeProb > self.settings._EYE_THRESHOLD) \
|
||||
* (driver_data.sunglassesProb < self.settings._SG_THRESHOLD)
|
||||
self.blink.right = driver_data.rightBlinkProb * (driver_data.rightEyeProb > self.settings._EYE_THRESHOLD) \
|
||||
* (driver_data.sunglassesProb < self.settings._SG_THRESHOLD)
|
||||
self.blink_prob = driver_data.eyesClosedProb * (driver_data.eyesVisibleProb > self.settings._EYE_THRESHOLD)
|
||||
self.phone_prob = driver_data.phoneProb
|
||||
|
||||
self.distracted_types = self._get_distracted_types()
|
||||
@@ -360,19 +361,19 @@ class DriverMonitoring:
|
||||
if self.awareness > self.threshold_prompt:
|
||||
return
|
||||
|
||||
_reaching_pre = self.awareness - self.step_change <= self.threshold_pre
|
||||
_reaching_audible = self.awareness - self.step_change <= self.threshold_prompt
|
||||
_reaching_terminal = self.awareness - self.step_change <= 0
|
||||
standstill_orange_exemption = standstill and _reaching_audible
|
||||
standstill_exemption = standstill and _reaching_pre
|
||||
always_on_red_exemption = always_on_valid and not op_engaged and _reaching_terminal
|
||||
always_on_lowspeed_exemption = always_on_valid and not op_engaged and car_speed < self.settings._ALWAYS_ON_ALERT_MIN_SPEED
|
||||
|
||||
certainly_distracted = self.driver_distraction_filter.x > 0.63 and self.driver_distracted and self.face_detected
|
||||
maybe_distracted = self.hi_stds > self.settings._HI_STD_FALLBACK_TIME or not self.face_detected
|
||||
|
||||
if certainly_distracted or maybe_distracted:
|
||||
# should always be counting if distracted unless at standstill (lowspeed for always-on) and reaching orange
|
||||
# should always be counting if distracted unless at standstill and reaching green
|
||||
# also will not be reaching 0 if DM is active when not engaged
|
||||
if not (standstill_orange_exemption or always_on_red_exemption or (always_on_lowspeed_exemption and _reaching_audible)):
|
||||
if not (standstill_exemption or always_on_red_exemption):
|
||||
self.awareness = max(self.awareness - self.step_change, -0.1)
|
||||
|
||||
alert = None
|
||||
@@ -385,7 +386,7 @@ class DriverMonitoring:
|
||||
elif self.awareness <= self.threshold_prompt:
|
||||
# prompt orange alert
|
||||
alert = EventName.promptDriverDistracted if self.active_monitoring_mode else EventName.promptDriverUnresponsive
|
||||
elif self.awareness <= self.threshold_pre and not always_on_lowspeed_exemption:
|
||||
elif self.awareness <= self.threshold_pre:
|
||||
# pre green alert
|
||||
alert = EventName.preDriverDistracted if self.active_monitoring_mode else EventName.preDriverUnresponsive
|
||||
|
||||
@@ -451,6 +452,7 @@ class DriverMonitoring:
|
||||
op_engaged=enabled,
|
||||
standstill=standstill,
|
||||
demo_mode=demo,
|
||||
steering_angle_deg=sm['carState'].steeringAngleDeg,
|
||||
)
|
||||
|
||||
# Update distraction events
|
||||
|
||||
@@ -20,10 +20,8 @@ def make_msg(face_detected, distracted=False, model_uncertain=False):
|
||||
ds.leftDriverData.faceOrientation = [0., 0., 0.]
|
||||
ds.leftDriverData.facePosition = [0., 0.]
|
||||
ds.leftDriverData.faceProb = 1. * face_detected
|
||||
ds.leftDriverData.leftEyeProb = 1.
|
||||
ds.leftDriverData.rightEyeProb = 1.
|
||||
ds.leftDriverData.leftBlinkProb = 1. * distracted
|
||||
ds.leftDriverData.rightBlinkProb = 1. * distracted
|
||||
ds.leftDriverData.eyesVisibleProb = 1.
|
||||
ds.leftDriverData.eyesClosedProb = 1. * distracted
|
||||
ds.leftDriverData.faceOrientationStd = [1.*model_uncertain, 1.*model_uncertain, 1.*model_uncertain]
|
||||
ds.leftDriverData.facePositionStd = [1.*model_uncertain, 1.*model_uncertain]
|
||||
# TODO: test both separately when e2e is used
|
||||
@@ -187,10 +185,10 @@ class TestMonitoring:
|
||||
standstill_vector = always_true[:]
|
||||
standstill_vector[int(_redlight_time/DT_DMON):] = [False] * int((TEST_TIMESPAN-_redlight_time)/DT_DMON)
|
||||
events, d_status = self._run_seq(always_distracted, always_false, always_true, standstill_vector)
|
||||
assert events[int((d_status.settings._DISTRACTED_TIME-d_status.settings._DISTRACTED_PRE_TIME_TILL_TERMINAL+1)/DT_DMON)].names[0] == \
|
||||
EventName.preDriverDistracted
|
||||
assert events[int((_redlight_time-0.1)/DT_DMON)].names[0] == EventName.preDriverDistracted
|
||||
assert events[int((_redlight_time+0.5)/DT_DMON)].names[0] == EventName.promptDriverDistracted
|
||||
assert len(events[int((_redlight_time-0.1)/DT_DMON)]) == 0
|
||||
_pre_to_prompt = d_status.settings._DISTRACTED_PRE_TIME_TILL_TERMINAL - d_status.settings._DISTRACTED_PROMPT_TIME_TILL_TERMINAL
|
||||
assert events[int((_redlight_time+0.5)/DT_DMON)].names[0] == EventName.preDriverDistracted
|
||||
assert events[int((_redlight_time+_pre_to_prompt+0.5)/DT_DMON)].names[0] == EventName.promptDriverDistracted
|
||||
|
||||
# engaged, model is somehow uncertain and driver is distracted
|
||||
# - should fall back to wheel touch after uncertain alert
|
||||
|
||||
@@ -78,22 +78,6 @@ class TestPandad:
|
||||
|
||||
assert any(Panda(s).is_internal() for s in Panda.list())
|
||||
|
||||
def test_best_case_startup_time(self):
|
||||
# run once so we're up to date
|
||||
self._run_test(60)
|
||||
|
||||
ts = []
|
||||
for _ in range(10):
|
||||
# should be nearly instant this time
|
||||
dt = self._run_test(5)
|
||||
ts.append(dt)
|
||||
|
||||
# 5s for USB (due to enumeration)
|
||||
# - 0.2s pandad -> pandad
|
||||
# - plus some buffer
|
||||
print("startup times", ts, sum(ts) / len(ts))
|
||||
assert 0.1 < (sum(ts)/len(ts)) < 0.7
|
||||
|
||||
def test_old_spi_protocol(self):
|
||||
# flash firmware with old SPI protocol
|
||||
self._flash_bootstub(os.path.join(HERE, "bootstub.panda_h7_spiv0.bin"))
|
||||
|
||||
@@ -235,6 +235,11 @@ EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = {
|
||||
"Ensure road ahead is clear"),
|
||||
},
|
||||
|
||||
EventName.lateralManeuver: {
|
||||
ET.WARNING: longitudinal_maneuver_alert,
|
||||
ET.PERMANENT: NormalPermanentAlert("Lateral Maneuver Mode"),
|
||||
},
|
||||
|
||||
EventName.selfdriveInitializing: {
|
||||
ET.NO_ENTRY: NoEntryAlert("System Initializing"),
|
||||
},
|
||||
|
||||
@@ -89,7 +89,7 @@ class SelfdriveD(CruiseHelper):
|
||||
# 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'] + ['modelDataV2SP']
|
||||
ignore = self.sensor_packets + self.gps_packets + ['alertDebug', 'lateralManeuverPlan'] + ['modelDataV2SP']
|
||||
if SIMULATION:
|
||||
ignore += ['driverCameraState', 'managerState']
|
||||
if REPLAY:
|
||||
@@ -99,7 +99,7 @@ class SelfdriveD(CruiseHelper):
|
||||
'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', 'liveDelay',
|
||||
'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters',
|
||||
'controlsState', 'carControl', 'driverAssistance', 'alertDebug', 'userBookmark', 'audioFeedback',
|
||||
'modelDataV2SP', 'longitudinalPlanSP'] + \
|
||||
'lateralManeuverPlan', 'modelDataV2SP', 'longitudinalPlanSP'] + \
|
||||
self.camera_packets + self.sensor_packets + self.gps_packets,
|
||||
ignore_alive=ignore, ignore_avg_freq=ignore,
|
||||
ignore_valid=ignore, frequency=int(1/DT_CTRL))
|
||||
@@ -183,7 +183,10 @@ class SelfdriveD(CruiseHelper):
|
||||
self.events.add(EventName.joystickDebug)
|
||||
self.startup_event = None
|
||||
|
||||
if self.sm.recv_frame['alertDebug'] > 0:
|
||||
if self.sm.recv_frame['lateralManeuverPlan'] > 0:
|
||||
self.events.add(EventName.lateralManeuver)
|
||||
self.startup_event = None
|
||||
elif self.sm.recv_frame['alertDebug'] > 0:
|
||||
self.events.add(EventName.longitudinalManeuver)
|
||||
self.startup_event = None
|
||||
|
||||
|
||||
92
selfdrive/test/process_replay/diff_report.py
Normal file
92
selfdrive/test/process_replay/diff_report.py
Normal file
@@ -0,0 +1,92 @@
|
||||
import os
|
||||
from collections import defaultdict
|
||||
|
||||
from opendbc.car.tests.car_diff import format_diff, format_numeric_diffs
|
||||
from openpilot.selfdrive.test.process_replay.compare_logs import compare_logs
|
||||
from openpilot.selfdrive.test.process_replay.process_replay import PROC_REPLAY_DIR
|
||||
|
||||
|
||||
class MsgWrap:
|
||||
"""Adapter so to_dict() includes defaults"""
|
||||
def __init__(self, msg):
|
||||
self._msg = msg
|
||||
def to_dict(self) -> dict:
|
||||
return self._msg.to_dict(verbose=True)
|
||||
|
||||
|
||||
def diff_process(cfg, ref_msgs, new_msgs) -> tuple | None:
|
||||
ref = defaultdict(list)
|
||||
new = defaultdict(list)
|
||||
for m in ref_msgs:
|
||||
if m.which() in cfg.subs:
|
||||
ref[m.which()].append(m)
|
||||
for m in new_msgs:
|
||||
if m.which() in cfg.subs:
|
||||
new[m.which()].append(m)
|
||||
|
||||
diffs = []
|
||||
for sub in cfg.subs:
|
||||
if len(ref[sub]) != len(new[sub]):
|
||||
diffs.append((f"{sub} (message count)", 0, (len(ref[sub]), len(new[sub])), 0))
|
||||
for i, (r, n) in enumerate(zip(ref[sub], new[sub], strict=False)):
|
||||
for d in compare_logs([r], [n], cfg.ignore, tolerance=cfg.tolerance):
|
||||
if d[0] == "change":
|
||||
a, b = d[2]
|
||||
if a != a and b != b:
|
||||
continue
|
||||
diffs.append((d[1], i, d[2], r.logMonoTime))
|
||||
elif d[0] in ("add", "remove"):
|
||||
for item in d[2]:
|
||||
if item[1] != item[1]:
|
||||
continue
|
||||
diffs.append((f"{d[1]}.{item[0]}", i, (d[0], item[1]), r.logMonoTime))
|
||||
return (diffs, ref, new) if diffs else None
|
||||
|
||||
|
||||
def diff_format(diffs, ref, new, field) -> list[str]:
|
||||
if any(part.isdigit() for part in field.split(".")):
|
||||
return format_numeric_diffs(diffs)
|
||||
msg_type = field.split(".")[0]
|
||||
ref_ts = [(m.logMonoTime, MsgWrap(m)) for m in ref.get(msg_type, [])]
|
||||
new_wrapped = [MsgWrap(m) for m in new.get(msg_type, [])]
|
||||
return format_diff(diffs, ref_ts, new_wrapped, field)
|
||||
|
||||
|
||||
def diff_report(replay_diffs, segments) -> None:
|
||||
seg_to_plat = {seg: plat for plat, seg in segments}
|
||||
|
||||
with_diffs, errors, n_passed = [], [], 0
|
||||
for seg, proc, data in replay_diffs:
|
||||
plat = seg_to_plat.get(seg, "UNKNOWN")
|
||||
if data is None:
|
||||
n_passed += 1
|
||||
elif isinstance(data, str):
|
||||
errors.append((plat, seg, proc, data))
|
||||
else:
|
||||
with_diffs.append((plat, seg, proc, data))
|
||||
|
||||
icon = "⚠️" if with_diffs else "✅"
|
||||
lines = [
|
||||
"## Process replay diff report",
|
||||
"Replays driving segments through this PR and compares the behavior to master.",
|
||||
"Please review any changes carefully to ensure they are expected.\n",
|
||||
f"{icon} {len(with_diffs)} changed, {n_passed} passed, {len(errors)} errors",
|
||||
]
|
||||
|
||||
for plat, seg, proc, err in errors:
|
||||
lines.append(f"\nERROR {plat} - {seg} [{proc}]: {err}")
|
||||
|
||||
if with_diffs:
|
||||
lines.append("<details><summary><b>Show changes</b></summary>\n\n```")
|
||||
for plat, seg, proc, (diffs, ref, new) in with_diffs:
|
||||
lines.append(f"\n{plat} - {seg} [{proc}]")
|
||||
by_field = defaultdict(list)
|
||||
for d in diffs:
|
||||
by_field[d[0]].append(d)
|
||||
for field, fd in sorted(by_field.items()):
|
||||
lines.append(f"\n {field} ({len(fd)} diffs)")
|
||||
lines.extend(diff_format(fd, ref, new, field))
|
||||
lines.append("```\n</details>")
|
||||
|
||||
with open(os.path.join(PROC_REPLAY_DIR, "diff_report.txt"), "w") as f:
|
||||
f.write("\n".join(lines))
|
||||
@@ -39,6 +39,7 @@ def migrate_all(lr: LogIterable, manager_states: bool = False, panda_states: boo
|
||||
migrate_carOutput,
|
||||
migrate_controlsState,
|
||||
migrate_carState,
|
||||
migrate_livePose,
|
||||
migrate_liveTracks,
|
||||
migrate_driverAssistance,
|
||||
migrate_drivingModelData,
|
||||
@@ -177,6 +178,7 @@ def migrate_liveLocationKalman(msgs):
|
||||
m = messaging.new_message('livePose')
|
||||
m.valid = msg.valid
|
||||
m.logMonoTime = msg.logMonoTime
|
||||
m.livePose.timestamp = msg.logMonoTime
|
||||
for field in ["orientationNED", "velocityDevice", "accelerationDevice", "angularVelocityDevice"]:
|
||||
lp_field, llk_field = getattr(m.livePose, field), getattr(msg.liveLocationKalmanDEPRECATED, field)
|
||||
lp_field.x, lp_field.y, lp_field.z = llk_field.value or nans
|
||||
@@ -188,6 +190,21 @@ def migrate_liveLocationKalman(msgs):
|
||||
return ops, [], []
|
||||
|
||||
|
||||
@migration(inputs=["livePose"])
|
||||
def migrate_livePose(msgs):
|
||||
ops = []
|
||||
needs_migration = all(msg.livePose.timestamp == 0 for _, msg in msgs if msg.which() == 'livePose')
|
||||
if not needs_migration:
|
||||
return [], [], []
|
||||
|
||||
for index, msg in msgs:
|
||||
if msg.which() == "livePose":
|
||||
new_msg = msg.as_builder()
|
||||
new_msg.livePose.timestamp = msg.logMonoTime
|
||||
ops.append((index, new_msg.as_reader()))
|
||||
return ops, [], []
|
||||
|
||||
|
||||
@migration(inputs=["controlsState"], product="selfdriveState")
|
||||
def migrate_controlsState(msgs):
|
||||
add_ops = []
|
||||
|
||||
@@ -76,7 +76,7 @@ def generate_report(proposed, master, tmp, commit):
|
||||
(lambda x: get_idx_if_non_empty(x.wheelOnRightProb), "wheelOnRightProb"),
|
||||
(lambda x: get_idx_if_non_empty(x.leftDriverData.faceProb), "leftDriverData.faceProb"),
|
||||
(lambda x: get_idx_if_non_empty(x.leftDriverData.faceOrientation, 0), "leftDriverData.faceOrientation0"),
|
||||
(lambda x: get_idx_if_non_empty(x.leftDriverData.leftBlinkProb), "leftDriverData.leftBlinkProb"),
|
||||
(lambda x: get_idx_if_non_empty(x.leftDriverData.eyesClosedProb), "leftDriverData.eyesClosedProb"),
|
||||
(lambda x: get_idx_if_non_empty(x.leftDriverData.phoneProb), "leftDriverData.phoneProb"),
|
||||
(lambda x: get_idx_if_non_empty(x.rightDriverData.faceProb), "rightDriverData.faceProb"),
|
||||
], "driverStateV2")
|
||||
|
||||
@@ -146,6 +146,7 @@ class ProcessContainer:
|
||||
self.cfg = copy.deepcopy(cfg)
|
||||
self.process = copy.deepcopy(managed_processes[cfg.proc_name])
|
||||
self.msg_queue: list[capnp._DynamicStructReader] = []
|
||||
self.last_input_log_mono_time: int = -1
|
||||
self.cnt = 0
|
||||
self.pm: messaging.PubMaster | None = None
|
||||
self.sockets: list[messaging.SubSocket] | None = None
|
||||
@@ -268,6 +269,7 @@ class ProcessContainer:
|
||||
ms = messaging.drain_sock(socket)
|
||||
for m in ms:
|
||||
m = m.as_builder()
|
||||
assert start_time > 0, "start_time must be positive"
|
||||
m.logMonoTime = start_time + int(self.cfg.processing_time * 1e9)
|
||||
output_msgs.append(m.as_reader())
|
||||
return output_msgs
|
||||
@@ -294,10 +296,11 @@ class ProcessContainer:
|
||||
trigger_empty_recv = any(m.which() == self.cfg.main_pub for m in self.msg_queue)
|
||||
|
||||
# get output msgs from previous inputs
|
||||
output_msgs = self.get_output_msgs(msg.logMonoTime)
|
||||
output_msgs = self.get_output_msgs(self.last_input_log_mono_time)
|
||||
|
||||
for m in self.msg_queue:
|
||||
self.pm.send(m.which(), m.as_builder())
|
||||
self.last_input_log_mono_time = max(self.last_input_log_mono_time, m.logMonoTime)
|
||||
# send frames if needed
|
||||
if self.vipc_server is not None and m.which() in self.cfg.vision_pubs:
|
||||
camera_state = getattr(m, m.which())
|
||||
@@ -513,6 +516,7 @@ CONFIGS = [
|
||||
ignore=["logMonoTime"],
|
||||
should_recv_callback=MessageBasedRcvCallback("cameraOdometry"),
|
||||
tolerance=NUMPY_TOLERANCE,
|
||||
processing_time=0.01,
|
||||
),
|
||||
ProcessConfig(
|
||||
proc_name="paramsd",
|
||||
@@ -716,7 +720,7 @@ def _replay_multi_process(
|
||||
|
||||
# flush last set of messages from each process
|
||||
for container in containers:
|
||||
last_time = log_msgs[-1].logMonoTime if len(log_msgs) > 0 else int(time.monotonic() * 1e9)
|
||||
last_time = container.last_input_log_mono_time if container.last_input_log_mono_time > 0 else int(time.monotonic() * 1e9)
|
||||
log_msgs.extend(container.get_output_msgs(last_time))
|
||||
finally:
|
||||
for container in containers:
|
||||
|
||||
@@ -3,6 +3,7 @@ import argparse
|
||||
import concurrent.futures
|
||||
import os
|
||||
import sys
|
||||
import traceback
|
||||
from collections import defaultdict
|
||||
from tqdm import tqdm
|
||||
from typing import Any
|
||||
@@ -11,6 +12,7 @@ from opendbc.car.car_helpers import interface_names
|
||||
from openpilot.common.git import get_commit
|
||||
from openpilot.tools.lib.openpilotci import get_url
|
||||
from openpilot.selfdrive.test.process_replay.compare_logs import compare_logs, format_diff
|
||||
from openpilot.selfdrive.test.process_replay.diff_report import diff_process, diff_report
|
||||
from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS, PROC_REPLAY_DIR, FAKEDATA, replay_process, \
|
||||
check_most_messages_valid
|
||||
from openpilot.tools.lib.filereader import FileReader
|
||||
@@ -72,11 +74,16 @@ EXCLUDED_PROCS = {"modeld", "dmonitoringmodeld"}
|
||||
|
||||
def run_test_process(data):
|
||||
segment, cfg, args, cur_log_fn, ref_log_path, lr_dat = data
|
||||
ref_log_msgs = list(LogReader(ref_log_path))
|
||||
lr = LogReader.from_bytes(lr_dat)
|
||||
res, log_msgs = test_process(cfg, lr, segment, ref_log_path, cur_log_fn, args.ignore_fields, args.ignore_msgs)
|
||||
res, log_msgs = test_process(cfg, lr, segment, ref_log_msgs, cur_log_fn, args.ignore_fields, args.ignore_msgs)
|
||||
# save logs so we can update refs
|
||||
save_log(cur_log_fn, log_msgs)
|
||||
return (segment, cfg.proc_name, res)
|
||||
try:
|
||||
diff_data = diff_process(cfg, ref_log_msgs, log_msgs)
|
||||
except Exception:
|
||||
diff_data = traceback.format_exc()
|
||||
return (segment, cfg.proc_name, res, diff_data)
|
||||
|
||||
|
||||
def get_log_data(segment):
|
||||
@@ -85,14 +92,12 @@ def get_log_data(segment):
|
||||
return (segment, f.read())
|
||||
|
||||
|
||||
def test_process(cfg, lr, segment, ref_log_path, new_log_path, ignore_fields=None, ignore_msgs=None):
|
||||
def test_process(cfg, lr, segment, ref_log_msgs, new_log_path, ignore_fields=None, ignore_msgs=None):
|
||||
if ignore_fields is None:
|
||||
ignore_fields = []
|
||||
if ignore_msgs is None:
|
||||
ignore_msgs = []
|
||||
|
||||
ref_log_msgs = list(LogReader(ref_log_path))
|
||||
|
||||
try:
|
||||
log_msgs = replay_process(cfg, lr, disable_progress=True)
|
||||
except Exception as e:
|
||||
@@ -201,9 +206,11 @@ if __name__ == "__main__":
|
||||
log_paths[segment][cfg.proc_name]['new'] = cur_log_fn
|
||||
|
||||
results: Any = defaultdict(dict)
|
||||
diffs: list = []
|
||||
p2 = pool.map(run_test_process, pool_args)
|
||||
for (segment, proc, result) in tqdm(p2, desc="Running Tests", total=len(pool_args)):
|
||||
for (segment, proc, result, diff_data) in tqdm(p2, desc="Running Tests", total=len(pool_args)):
|
||||
results[segment][proc] = result
|
||||
diffs.append((segment, proc, diff_data))
|
||||
|
||||
diff_short, diff_long, failed = format_diff(results, log_paths, ref_commit)
|
||||
if not args.update_refs:
|
||||
@@ -211,6 +218,11 @@ if __name__ == "__main__":
|
||||
f.write(diff_long)
|
||||
print(diff_short)
|
||||
|
||||
try:
|
||||
diff_report(diffs, segments)
|
||||
except Exception:
|
||||
print(f"failed to generate diff report:\n{traceback.format_exc()}")
|
||||
|
||||
if failed:
|
||||
print("TEST FAILED")
|
||||
else:
|
||||
|
||||
@@ -48,7 +48,7 @@ Font font_display;
|
||||
const bool tici_device = Hardware::get_device_type() == cereal::InitData::DeviceType::TICI ||
|
||||
Hardware::get_device_type() == cereal::InitData::DeviceType::TIZI;
|
||||
|
||||
std::vector<std::string> tici_prebuilt_branches = {"release3", "release-tizi", "release3-staging", "nightly", "nightly-dev"};
|
||||
std::vector<std::string> tici_prebuilt_branches = {"release3", "release-tici", "release3-staging", "nightly", "nightly-dev"};
|
||||
std::string migrated_branch;
|
||||
|
||||
void branchMigration() {
|
||||
|
||||
@@ -71,6 +71,13 @@ class DeveloperLayout(Widget):
|
||||
callback=self._on_long_maneuver_mode,
|
||||
)
|
||||
|
||||
self._lat_maneuver_toggle = toggle_item(
|
||||
lambda: tr("Lateral Maneuver Mode"),
|
||||
description="",
|
||||
initial_state=self._params.get_bool("LateralManeuverMode"),
|
||||
callback=self._on_lat_maneuver_mode,
|
||||
)
|
||||
|
||||
self._alpha_long_toggle = toggle_item(
|
||||
lambda: tr("sunnypilot Longitudinal Control (Alpha)"),
|
||||
description=lambda: tr(DESCRIPTIONS["alpha_longitudinal"]),
|
||||
@@ -93,6 +100,7 @@ class DeveloperLayout(Widget):
|
||||
self._ssh_keys,
|
||||
self._joystick_toggle,
|
||||
self._long_maneuver_toggle,
|
||||
self._lat_maneuver_toggle,
|
||||
self._alpha_long_toggle,
|
||||
self._ui_debug_toggle,
|
||||
], line_separator=True, spacing=0)
|
||||
@@ -113,7 +121,7 @@ class DeveloperLayout(Widget):
|
||||
|
||||
# Hide non-release toggles on release builds
|
||||
# TODO: we can do an onroad cycle, but alpha long toggle requires a deinit function to re-enable radar and not fault
|
||||
for item in (self._joystick_toggle, self._long_maneuver_toggle, self._alpha_long_toggle):
|
||||
for item in (self._joystick_toggle, self._long_maneuver_toggle, self._lat_maneuver_toggle, self._alpha_long_toggle):
|
||||
item.set_visible(not self._is_release)
|
||||
|
||||
# CP gating
|
||||
@@ -130,8 +138,12 @@ class DeveloperLayout(Widget):
|
||||
if not long_man_enabled:
|
||||
self._long_maneuver_toggle.action_item.set_state(False)
|
||||
self._params.put_bool("LongitudinalManeuverMode", False)
|
||||
|
||||
lat_man_enabled = ui_state.is_offroad()
|
||||
self._lat_maneuver_toggle.action_item.set_enabled(lat_man_enabled)
|
||||
else:
|
||||
self._long_maneuver_toggle.action_item.set_enabled(False)
|
||||
self._lat_maneuver_toggle.action_item.set_enabled(False)
|
||||
self._alpha_long_toggle.set_visible(False)
|
||||
|
||||
# TODO: make a param control list item so we don't need to manage internal state as much here
|
||||
@@ -141,6 +153,7 @@ class DeveloperLayout(Widget):
|
||||
("SshEnabled", self._ssh_toggle),
|
||||
("JoystickDebugMode", self._joystick_toggle),
|
||||
("LongitudinalManeuverMode", self._long_maneuver_toggle),
|
||||
("LateralManeuverMode", self._lat_maneuver_toggle),
|
||||
("AlphaLongitudinalEnabled", self._alpha_long_toggle),
|
||||
("ShowDebugInfo", self._ui_debug_toggle),
|
||||
):
|
||||
@@ -162,11 +175,23 @@ class DeveloperLayout(Widget):
|
||||
self._params.put_bool("JoystickDebugMode", state)
|
||||
self._params.put_bool("LongitudinalManeuverMode", False)
|
||||
self._long_maneuver_toggle.action_item.set_state(False)
|
||||
self._params.put_bool("LateralManeuverMode", False)
|
||||
self._lat_maneuver_toggle.action_item.set_state(False)
|
||||
|
||||
def _on_long_maneuver_mode(self, state: bool):
|
||||
self._params.put_bool("LongitudinalManeuverMode", state)
|
||||
self._params.put_bool("JoystickDebugMode", False)
|
||||
self._joystick_toggle.action_item.set_state(False)
|
||||
self._params.put_bool("LateralManeuverMode", False)
|
||||
self._lat_maneuver_toggle.action_item.set_state(False)
|
||||
|
||||
def _on_lat_maneuver_mode(self, state: bool):
|
||||
self._params.put_bool("LateralManeuverMode", state)
|
||||
self._params.put_bool("ExperimentalMode", False)
|
||||
self._params.put_bool("JoystickDebugMode", False)
|
||||
self._joystick_toggle.action_item.set_state(False)
|
||||
self._params.put_bool("LongitudinalManeuverMode", False)
|
||||
self._long_maneuver_toggle.action_item.set_state(False)
|
||||
|
||||
def _on_alpha_long_enabled(self, state: bool):
|
||||
if state:
|
||||
|
||||
@@ -55,6 +55,9 @@ class DeveloperLayoutMici(NavScroller):
|
||||
self._long_maneuver_toggle = BigToggle("longitudinal maneuver mode",
|
||||
initial_state=ui_state.params.get_bool("LongitudinalManeuverMode"),
|
||||
toggle_callback=self._on_long_maneuver_mode)
|
||||
self._lat_maneuver_toggle = BigToggle("lateral maneuver mode",
|
||||
initial_state=ui_state.params.get_bool("LateralManeuverMode"),
|
||||
toggle_callback=self._on_lat_maneuver_mode)
|
||||
self._alpha_long_toggle = BigToggle("alpha longitudinal",
|
||||
initial_state=ui_state.params.get_bool("AlphaLongitudinalEnabled"),
|
||||
toggle_callback=self._on_alpha_long_enabled)
|
||||
@@ -68,6 +71,7 @@ class DeveloperLayoutMici(NavScroller):
|
||||
self._ssh_keys_btn,
|
||||
self._joystick_toggle,
|
||||
self._long_maneuver_toggle,
|
||||
self._lat_maneuver_toggle,
|
||||
self._alpha_long_toggle,
|
||||
self._debug_mode_toggle,
|
||||
])
|
||||
@@ -78,12 +82,13 @@ class DeveloperLayoutMici(NavScroller):
|
||||
("SshEnabled", self._ssh_toggle),
|
||||
("JoystickDebugMode", self._joystick_toggle),
|
||||
("LongitudinalManeuverMode", self._long_maneuver_toggle),
|
||||
("LateralManeuverMode", self._lat_maneuver_toggle),
|
||||
("AlphaLongitudinalEnabled", self._alpha_long_toggle),
|
||||
("ShowDebugInfo", self._debug_mode_toggle),
|
||||
)
|
||||
onroad_blocked_toggles = (self._adb_toggle, self._joystick_toggle)
|
||||
release_blocked_toggles = (self._joystick_toggle, self._long_maneuver_toggle, self._alpha_long_toggle)
|
||||
engaged_blocked_toggles = (self._long_maneuver_toggle, self._alpha_long_toggle)
|
||||
release_blocked_toggles = (self._joystick_toggle, self._long_maneuver_toggle, self._lat_maneuver_toggle, self._alpha_long_toggle)
|
||||
engaged_blocked_toggles = (self._long_maneuver_toggle, self._lat_maneuver_toggle, self._alpha_long_toggle)
|
||||
|
||||
# Hide non-release toggles on release builds
|
||||
for item in release_blocked_toggles:
|
||||
@@ -129,8 +134,12 @@ class DeveloperLayoutMici(NavScroller):
|
||||
if not long_man_enabled:
|
||||
self._long_maneuver_toggle.set_checked(False)
|
||||
ui_state.params.put_bool("LongitudinalManeuverMode", False)
|
||||
|
||||
lat_man_enabled = ui_state.is_offroad()
|
||||
self._lat_maneuver_toggle.set_enabled(lat_man_enabled)
|
||||
else:
|
||||
self._long_maneuver_toggle.set_enabled(False)
|
||||
self._lat_maneuver_toggle.set_enabled(False)
|
||||
self._alpha_long_toggle.set_visible(False)
|
||||
|
||||
# Refresh toggles from params to mirror external changes
|
||||
@@ -141,11 +150,24 @@ class DeveloperLayoutMici(NavScroller):
|
||||
ui_state.params.put_bool("JoystickDebugMode", state)
|
||||
ui_state.params.put_bool("LongitudinalManeuverMode", False)
|
||||
self._long_maneuver_toggle.set_checked(False)
|
||||
ui_state.params.put_bool("LateralManeuverMode", False)
|
||||
self._lat_maneuver_toggle.set_checked(False)
|
||||
|
||||
def _on_long_maneuver_mode(self, state: bool):
|
||||
ui_state.params.put_bool("LongitudinalManeuverMode", state)
|
||||
ui_state.params.put_bool("JoystickDebugMode", False)
|
||||
self._joystick_toggle.set_checked(False)
|
||||
ui_state.params.put_bool("LateralManeuverMode", False)
|
||||
self._lat_maneuver_toggle.set_checked(False)
|
||||
restart_needed_callback(state)
|
||||
|
||||
def _on_lat_maneuver_mode(self, state: bool):
|
||||
ui_state.params.put_bool("LateralManeuverMode", state)
|
||||
ui_state.params.put_bool("ExperimentalMode", False)
|
||||
ui_state.params.put_bool("JoystickDebugMode", False)
|
||||
self._joystick_toggle.set_checked(False)
|
||||
ui_state.params.put_bool("LongitudinalManeuverMode", False)
|
||||
self._long_maneuver_toggle.set_checked(False)
|
||||
restart_needed_callback(state)
|
||||
|
||||
def _on_alpha_long_enabled(self, state: bool):
|
||||
|
||||
@@ -39,8 +39,6 @@ class BaseDriverCameraDialog(Widget):
|
||||
self._eye_fill_texture = None
|
||||
self._eye_orange_texture = None
|
||||
self._eye_size = 74
|
||||
self._glasses_texture = None
|
||||
self._glasses_size = 171
|
||||
|
||||
self._load_eye_textures()
|
||||
|
||||
@@ -154,8 +152,6 @@ class BaseDriverCameraDialog(Widget):
|
||||
self._eye_fill_texture = gui_app.texture("icons_mici/onroad/eye_fill.png", self._eye_size, self._eye_size)
|
||||
if self._eye_orange_texture is None:
|
||||
self._eye_orange_texture = gui_app.texture("icons_mici/onroad/eye_orange.png", self._eye_size, self._eye_size)
|
||||
if self._glasses_texture is None:
|
||||
self._glasses_texture = gui_app.texture("icons_mici/onroad/glasses.png", self._glasses_size, self._glasses_size)
|
||||
|
||||
def _draw_face_detection(self, rect: rl.Rectangle):
|
||||
dm_state = ui_state.sm["driverMonitoringState"]
|
||||
@@ -202,31 +198,21 @@ class BaseDriverCameraDialog(Widget):
|
||||
eye_offset_x = 10
|
||||
eye_offset_y = 10
|
||||
eye_spacing = self._eye_size + 15
|
||||
eyes_prob = driver_data.eyesVisibleProb
|
||||
|
||||
left_eye_x = rect.x + eye_offset_x
|
||||
left_eye_y = rect.y + eye_offset_y
|
||||
left_eye_prob = driver_data.leftEyeProb
|
||||
|
||||
right_eye_x = rect.x + eye_offset_x + eye_spacing
|
||||
right_eye_y = rect.y + eye_offset_y
|
||||
right_eye_prob = driver_data.rightEyeProb
|
||||
|
||||
# Draw eyes with opacity based on probability
|
||||
for eye_x, eye_y, eye_prob in [(left_eye_x, left_eye_y, left_eye_prob), (right_eye_x, right_eye_y, right_eye_prob)]:
|
||||
fill_opacity = eye_prob
|
||||
orange_opacity = 1.0 - eye_prob
|
||||
|
||||
fill_opacity = eyes_prob
|
||||
orange_opacity = 1.0 - eyes_prob
|
||||
for eye_x, eye_y in [(left_eye_x, left_eye_y), (right_eye_x, right_eye_y)]:
|
||||
rl.draw_texture_v(self._eye_orange_texture, (eye_x, eye_y), rl.Color(255, 255, 255, int(255 * orange_opacity)))
|
||||
rl.draw_texture_v(self._eye_fill_texture, (eye_x, eye_y), rl.Color(255, 255, 255, int(255 * fill_opacity)))
|
||||
|
||||
# Draw sunglasses indicator based on sunglasses probability
|
||||
# Position glasses centered between the two eyes at top left
|
||||
glasses_x = rect.x + eye_offset_x - 4
|
||||
glasses_y = rect.y
|
||||
glasses_pos = rl.Vector2(glasses_x, glasses_y)
|
||||
glasses_prob = driver_data.sunglassesProb
|
||||
rl.draw_texture_v(self._glasses_texture, glasses_pos, rl.Color(70, 80, 161, int(255 * glasses_prob)))
|
||||
|
||||
|
||||
class DriverCameraDialog(NavWidget, BaseDriverCameraDialog):
|
||||
def __init__(self):
|
||||
|
||||
@@ -120,7 +120,7 @@ class HudRenderer(Widget):
|
||||
|
||||
self._txt_wheel: rl.Texture = gui_app.texture('icons_mici/wheel.png', 50, 50)
|
||||
self._txt_wheel_critical: rl.Texture = gui_app.texture('icons_mici/wheel_critical.png', 50, 50)
|
||||
self._txt_exclamation_point: rl.Texture = gui_app.texture('icons_mici/exclamation_point.png', 44, 44)
|
||||
self._txt_exclamation_point: rl.Texture = gui_app.texture('icons_mici/exclamation_point.png', 9, 44)
|
||||
|
||||
self._wheel_alpha_filter = FirstOrderFilter(0, 0.05, 1 / gui_app.target_fps)
|
||||
self._wheel_y_filter = FirstOrderFilter(0, 0.1, 1 / gui_app.target_fps)
|
||||
|
||||
@@ -8,7 +8,7 @@ from openpilot.selfdrive.ui.sunnypilot.layouts.settings.vehicle.brands.base impo
|
||||
from openpilot.selfdrive.ui.ui_state import ui_state
|
||||
from openpilot.system.ui.lib.multilang import tr
|
||||
from openpilot.system.ui.sunnypilot.widgets.list_view import multiple_button_item_sp
|
||||
from opendbc.car.hyundai.values import CAR, CANFD_UNSUPPORTED_LONGITUDINAL_CAR, UNSUPPORTED_LONGITUDINAL_CAR
|
||||
from opendbc.car.hyundai.values import CAR, UNSUPPORTED_LONGITUDINAL_CAR
|
||||
|
||||
|
||||
class HyundaiSettings(BrandSettings):
|
||||
@@ -31,7 +31,7 @@ class HyundaiSettings(BrandSettings):
|
||||
bundle = ui_state.params.get("CarPlatformBundle")
|
||||
if bundle:
|
||||
platform = bundle.get("platform")
|
||||
self.alpha_long_available = CAR[platform] not in (UNSUPPORTED_LONGITUDINAL_CAR | CANFD_UNSUPPORTED_LONGITUDINAL_CAR)
|
||||
self.alpha_long_available = CAR[platform] not in set().union(*UNSUPPORTED_LONGITUDINAL_CAR.values())
|
||||
elif ui_state.CP is not None:
|
||||
self.alpha_long_available = ui_state.CP.alphaLongitudinalAvailable
|
||||
|
||||
|
||||
@@ -1,124 +1,106 @@
|
||||
import pytest
|
||||
import json
|
||||
import os
|
||||
import re
|
||||
import xml.etree.ElementTree as ET
|
||||
import string
|
||||
import requests
|
||||
from openpilot.common.parameterized import parameterized_class
|
||||
from openpilot.system.ui.lib.multilang import TRANSLATIONS_DIR, LANGUAGES_FILE
|
||||
from pathlib import Path
|
||||
|
||||
with open(str(LANGUAGES_FILE)) as f:
|
||||
translation_files = json.load(f)
|
||||
import pytest
|
||||
|
||||
UNFINISHED_TRANSLATION_TAG = "<translation type=\"unfinished\"" # non-empty translations can be marked unfinished
|
||||
LOCATION_TAG = "<location "
|
||||
FORMAT_ARG = re.compile("%[0-9]+")
|
||||
from openpilot.selfdrive.ui.translations.potools import parse_po
|
||||
from openpilot.system.ui.lib.multilang import LANGUAGES_FILE, TRANSLATIONS_DIR
|
||||
|
||||
PERCENT_PLACEHOLDER_RE = re.compile(r"%(?:n|\d+)")
|
||||
BAD_ENTITY_RE = re.compile(r'@(\w+);')
|
||||
LINE_NUMBER_REF_RE = re.compile(r'^#:\s+.+:\d+(?:\s|$)')
|
||||
FORMATTER = string.Formatter()
|
||||
PO_DIR = Path(str(TRANSLATIONS_DIR))
|
||||
|
||||
with LANGUAGES_FILE.open(encoding='utf-8') as f:
|
||||
TRANSLATION_LANGUAGES = json.load(f)
|
||||
|
||||
|
||||
@pytest.mark.skip("TODO: update for raylib")
|
||||
@parameterized_class(("name", "file"), translation_files.items())
|
||||
class TestTranslations:
|
||||
name: str
|
||||
file: str
|
||||
def extract_placeholders(text: str) -> list[str]:
|
||||
placeholders = PERCENT_PLACEHOLDER_RE.findall(text)
|
||||
|
||||
@staticmethod
|
||||
def _read_translation_file(path, file):
|
||||
tr_file = os.path.join(path, f"{file}.ts")
|
||||
with open(tr_file) as f:
|
||||
return f.read()
|
||||
try:
|
||||
parsed = list(FORMATTER.parse(text))
|
||||
except ValueError as e:
|
||||
raise AssertionError(f"invalid brace formatting in {text!r}: {e}") from e
|
||||
|
||||
def test_missing_translation_files(self):
|
||||
assert os.path.exists(os.path.join(str(TRANSLATIONS_DIR), f"{self.file}.ts")), \
|
||||
f"{self.name} has no XML translation file, run selfdrive/ui/update_translations.py"
|
||||
for _, field_name, format_spec, conversion in parsed:
|
||||
if field_name is None:
|
||||
continue
|
||||
|
||||
@pytest.mark.skip("Only test unfinished translations before going to release")
|
||||
def test_unfinished_translations(self):
|
||||
cur_translations = self._read_translation_file(TRANSLATIONS_DIR, self.file)
|
||||
assert UNFINISHED_TRANSLATION_TAG not in cur_translations, \
|
||||
f"{self.file} ({self.name}) translation file has unfinished translations. Finish translations or mark them as completed in Qt Linguist"
|
||||
token = "{"
|
||||
token += field_name
|
||||
if conversion:
|
||||
token += f"!{conversion}"
|
||||
if format_spec:
|
||||
token += f":{format_spec}"
|
||||
token += "}"
|
||||
placeholders.append(token)
|
||||
|
||||
def test_vanished_translations(self):
|
||||
cur_translations = self._read_translation_file(TRANSLATIONS_DIR, self.file)
|
||||
assert "<translation type=\"vanished\">" not in cur_translations, \
|
||||
f"{self.file} ({self.name}) translation file has obsolete translations. Run selfdrive/ui/update_translations.py --vanish to remove them"
|
||||
return sorted(placeholders)
|
||||
|
||||
def test_finished_translations(self):
|
||||
"""
|
||||
Tests ran on each translation marked "finished"
|
||||
Plural:
|
||||
- that any numerus (plural) translations have all plural forms non-empty
|
||||
- that the correct format specifier is used (%n)
|
||||
Non-plural:
|
||||
- that translation is not empty
|
||||
- that translation format arguments are consistent
|
||||
"""
|
||||
tr_xml = ET.parse(os.path.join(TRANSLATIONS_DIR, f"{self.file}.ts"))
|
||||
|
||||
for context in tr_xml.getroot():
|
||||
for message in context.iterfind("message"):
|
||||
translation = message.find("translation")
|
||||
source_text = message.find("source").text
|
||||
def load_po_text(po_path: Path) -> str:
|
||||
return po_path.read_text(encoding='utf-8')
|
||||
|
||||
# Do not test unfinished translations
|
||||
if translation.get("type") == "unfinished":
|
||||
continue
|
||||
|
||||
if message.get("numerus") == "yes":
|
||||
numerusform = [t.text for t in translation.findall("numerusform")]
|
||||
@pytest.mark.parametrize("language_code", sorted(TRANSLATION_LANGUAGES.values()))
|
||||
def test_translation_file_exists(language_code: str):
|
||||
po_path = PO_DIR / f"app_{language_code}.po"
|
||||
assert po_path.exists(), f"missing translation file: {po_path}"
|
||||
|
||||
for nf in numerusform:
|
||||
assert nf is not None, f"Ensure all plural translation forms are completed: {source_text}"
|
||||
assert "%n" in nf, "Ensure numerus argument (%n) exists in translation."
|
||||
assert FORMAT_ARG.search(nf) is None, f"Plural translations must use %n, not %1, %2, etc.: {numerusform}"
|
||||
|
||||
else:
|
||||
assert translation.text is not None, f"Ensure translation is completed: {source_text}"
|
||||
@pytest.mark.parametrize("po_path", sorted(PO_DIR.glob("app_*.po")), ids=lambda p: p.name)
|
||||
def test_translation_placeholders_are_preserved(po_path: Path):
|
||||
_, entries = parse_po(po_path)
|
||||
language = po_path.stem.removeprefix("app_")
|
||||
|
||||
source_args = FORMAT_ARG.findall(source_text)
|
||||
translation_args = FORMAT_ARG.findall(translation.text)
|
||||
assert sorted(source_args) == sorted(translation_args), \
|
||||
f"Ensure format arguments are consistent: `{source_text}` vs. `{translation.text}`"
|
||||
for entry in entries:
|
||||
source_placeholders = extract_placeholders(entry.msgid)
|
||||
|
||||
def test_no_locations(self):
|
||||
for line in self._read_translation_file(TRANSLATIONS_DIR, self.file).splitlines():
|
||||
assert not line.strip().startswith(LOCATION_TAG), \
|
||||
f"Line contains location tag: {line.strip()}, remove all line numbers."
|
||||
|
||||
def test_entities_error(self):
|
||||
cur_translations = self._read_translation_file(TRANSLATIONS_DIR, self.file)
|
||||
matches = re.findall(r'@(\w+);', cur_translations)
|
||||
assert len(matches) == 0, f"The string(s) {matches} were found with '@' instead of '&'"
|
||||
|
||||
def test_bad_language(self):
|
||||
IGNORED_WORDS = {'pédale'}
|
||||
|
||||
match = re.search(r'([a-zA-Z]{2,3})', self.file)
|
||||
assert match, f"{self.name} - could not parse language"
|
||||
|
||||
try:
|
||||
response = requests.get(
|
||||
f"https://raw.githubusercontent.com/LDNOOBW/List-of-Dirty-Naughty-Obscene-and-Otherwise-Bad-Words/master/{match.group(1)}"
|
||||
if entry.is_plural:
|
||||
plural_placeholders = extract_placeholders(entry.msgid_plural)
|
||||
message = (
|
||||
f"{language}: source plural placeholders do not match singular for "
|
||||
+ f"{entry.msgid!r}: {source_placeholders} vs {plural_placeholders}"
|
||||
)
|
||||
response.raise_for_status()
|
||||
except requests.exceptions.HTTPError as e:
|
||||
if e.response is not None and e.response.status_code == 429:
|
||||
pytest.skip("word list rate limited")
|
||||
raise
|
||||
assert plural_placeholders == source_placeholders, message
|
||||
|
||||
banned_words = {line.strip() for line in response.text.splitlines()}
|
||||
|
||||
for context in ET.parse(os.path.join(TRANSLATIONS_DIR, f"{self.file}.ts")).getroot():
|
||||
for message in context.iterfind("message"):
|
||||
translation = message.find("translation")
|
||||
if translation.get("type") == "unfinished":
|
||||
for idx, msgstr in sorted(entry.msgstr_plural.items()):
|
||||
if not msgstr:
|
||||
continue
|
||||
|
||||
translation_text = " ".join([t.text for t in translation.findall("numerusform")]) if message.get("numerus") == "yes" else translation.text
|
||||
translated_placeholders = extract_placeholders(msgstr)
|
||||
message = (
|
||||
f"{language}: plural form {idx} changes placeholders for {entry.msgid!r}: "
|
||||
+ f"expected {source_placeholders}, got {translated_placeholders}"
|
||||
)
|
||||
assert translated_placeholders == source_placeholders, message
|
||||
else:
|
||||
if not entry.msgstr:
|
||||
continue
|
||||
|
||||
if not translation_text:
|
||||
continue
|
||||
translated_placeholders = extract_placeholders(entry.msgstr)
|
||||
message = (
|
||||
f"{language}: translation changes placeholders for {entry.msgid!r}: "
|
||||
+ f"expected {source_placeholders}, got {translated_placeholders}"
|
||||
)
|
||||
assert translated_placeholders == source_placeholders, message
|
||||
|
||||
words = set(translation_text.translate(str.maketrans('', '', string.punctuation + '%n')).lower().split())
|
||||
bad_words_found = words & (banned_words - IGNORED_WORDS)
|
||||
assert not bad_words_found, f"Bad language found in {self.name}: '{translation_text}'. Bad word(s): {', '.join(bad_words_found)}"
|
||||
|
||||
@pytest.mark.parametrize("po_path", sorted(PO_DIR.glob("app_*.po")), ids=lambda p: p.name)
|
||||
def test_translation_refs_do_not_include_line_numbers(po_path: Path):
|
||||
for line in load_po_text(po_path).splitlines():
|
||||
assert not LINE_NUMBER_REF_RE.match(line), (
|
||||
f"{po_path.name}: line-number source reference found: {line}"
|
||||
)
|
||||
|
||||
|
||||
@pytest.mark.parametrize("po_path", sorted(PO_DIR.glob("app_*.po")), ids=lambda p: p.name)
|
||||
def test_translation_entities_are_valid(po_path: Path):
|
||||
matches = BAD_ENTITY_RE.findall(load_po_text(po_path))
|
||||
assert not matches, (
|
||||
f"{po_path.name}: found '@...;' entity typo(s): {', '.join(sorted(set(matches)))}"
|
||||
)
|
||||
|
||||
@@ -1,3 +0,0 @@
|
||||
# Multilanguage
|
||||
|
||||
[](#)
|
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -1,138 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
import argparse
|
||||
import json
|
||||
import os
|
||||
import pathlib
|
||||
import xml.etree.ElementTree as ET
|
||||
from typing import cast
|
||||
|
||||
import requests
|
||||
|
||||
TRANSLATIONS_DIR = pathlib.Path(__file__).resolve().parent
|
||||
TRANSLATIONS_LANGUAGES = TRANSLATIONS_DIR / "languages.json"
|
||||
|
||||
OPENAI_MODEL = "gpt-4"
|
||||
OPENAI_API_KEY = os.environ.get("OPENAI_API_KEY")
|
||||
OPENAI_PROMPT = "You are a professional translator from English to {language} (ISO 639 language code). " + \
|
||||
"The following sentence or word is in the GUI of a software called openpilot, translate it accordingly."
|
||||
|
||||
|
||||
def get_language_files(languages: list[str] | None = None) -> dict[str, pathlib.Path]:
|
||||
files = {}
|
||||
|
||||
with open(TRANSLATIONS_LANGUAGES) as fp:
|
||||
language_dict = json.load(fp)
|
||||
|
||||
for filename in language_dict.values():
|
||||
path = TRANSLATIONS_DIR / f"{filename}.ts"
|
||||
language = path.stem
|
||||
|
||||
if languages is None or language in languages:
|
||||
files[language] = path
|
||||
|
||||
return files
|
||||
|
||||
|
||||
def translate_phrase(text: str, language: str) -> str:
|
||||
response = requests.post(
|
||||
"https://api.openai.com/v1/chat/completions",
|
||||
json={
|
||||
"model": OPENAI_MODEL,
|
||||
"messages": [
|
||||
{
|
||||
"role": "system",
|
||||
"content": OPENAI_PROMPT.format(language=language),
|
||||
},
|
||||
{
|
||||
"role": "user",
|
||||
"content": text,
|
||||
},
|
||||
],
|
||||
"temperature": 0.8,
|
||||
"max_tokens": 1024,
|
||||
"top_p": 1,
|
||||
},
|
||||
headers={
|
||||
"Authorization": f"Bearer {OPENAI_API_KEY}",
|
||||
"Content-Type": "application/json",
|
||||
},
|
||||
)
|
||||
|
||||
if 400 <= response.status_code < 600:
|
||||
raise requests.HTTPError(f'Error {response.status_code}: {response.json()}', response=response)
|
||||
|
||||
data = response.json()
|
||||
|
||||
return cast(str, data["choices"][0]["message"]["content"])
|
||||
|
||||
|
||||
def translate_file(path: pathlib.Path, language: str, all_: bool) -> None:
|
||||
tree = ET.parse(path)
|
||||
|
||||
root = tree.getroot()
|
||||
|
||||
for context in root.findall("./context"):
|
||||
name = context.find("name")
|
||||
if name is None:
|
||||
raise ValueError("name not found")
|
||||
|
||||
print(f"Context: {name.text}")
|
||||
|
||||
for message in context.findall("./message"):
|
||||
source = message.find("source")
|
||||
translation = message.find("translation")
|
||||
|
||||
if source is None or translation is None:
|
||||
raise ValueError("source or translation not found")
|
||||
|
||||
if not all_ and translation.attrib.get("type") != "unfinished":
|
||||
continue
|
||||
|
||||
llm_translation = translate_phrase(cast(str, source.text), language)
|
||||
|
||||
print(f"Source: {source.text}\n" +
|
||||
f"Current translation: {translation.text}\n" +
|
||||
f"LLM translation: {llm_translation}")
|
||||
|
||||
translation.text = llm_translation
|
||||
|
||||
with path.open("w", encoding="utf-8") as fp:
|
||||
fp.write('<?xml version="1.0" encoding="utf-8"?>\n' +
|
||||
'<!DOCTYPE TS>\n' +
|
||||
ET.tostring(root, encoding="utf-8").decode())
|
||||
|
||||
|
||||
def main():
|
||||
arg_parser = argparse.ArgumentParser("Auto translate")
|
||||
|
||||
group = arg_parser.add_mutually_exclusive_group(required=True)
|
||||
group.add_argument("-a", "--all-files", action="store_true", help="Translate all files")
|
||||
group.add_argument("-f", "--file", nargs="+", help="Translate the selected files. (Example: -f fr de)")
|
||||
|
||||
arg_parser.add_argument("-t", "--all-translations", action="store_true", default=False, help="Translate all sections. (Default: only unfinished)")
|
||||
|
||||
args = arg_parser.parse_args()
|
||||
|
||||
if OPENAI_API_KEY is None:
|
||||
print("OpenAI API key is missing. (Hint: use `export OPENAI_API_KEY=YOUR-KEY` before you run the script).\n" +
|
||||
"If you don't have one go to: https://beta.openai.com/account/api-keys.")
|
||||
exit(1)
|
||||
|
||||
files = get_language_files(None if args.all_files else args.file)
|
||||
|
||||
if args.file:
|
||||
missing_files = set(args.file) - set(files)
|
||||
if len(missing_files):
|
||||
print(f"No language files found: {missing_files}")
|
||||
exit(1)
|
||||
|
||||
print(f"Translation mode: {'all' if args.all_translations else 'only unfinished'}. Files: {list(files)}")
|
||||
|
||||
for lang, path in files.items():
|
||||
print(f"Translate {lang} ({path})")
|
||||
translate_file(path, lang, args.all_translations)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
26
selfdrive/ui/translations/auto_translate.sh
Executable file
26
selfdrive/ui/translations/auto_translate.sh
Executable file
@@ -0,0 +1,26 @@
|
||||
#!/usr/bin/env bash
|
||||
set -euo pipefail
|
||||
|
||||
DIR="$(cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd)"
|
||||
ROOT="$DIR/../../../"
|
||||
|
||||
cd $DIR
|
||||
./update_translations.py
|
||||
|
||||
command -v codex >/dev/null || {
|
||||
echo "Install codex CLI to continue:"
|
||||
echo "-> https://developers.openai.com/codex/cli"
|
||||
echo
|
||||
exit 1
|
||||
}
|
||||
|
||||
codex exec --cd "$ROOT" -c 'model_reasoning_effort="low"' --dangerously-bypass-approvals-and-sandbox "$(cat <<EOF
|
||||
Update openpilot UI translations in selfdrive/ui/translations.
|
||||
- Translate English UI text naturally.
|
||||
- Preserve placeholders (%n, %1, {}, {:.1f}), HTML/tags, and plural forms.
|
||||
- Edit .po files in place.
|
||||
- Print a short summary of changes.
|
||||
- All strings should be translated. Don't stop until it's 100%.
|
||||
- Be mindful of the layout/style of the UI and length of the original English string.
|
||||
EOF
|
||||
)"
|
||||
@@ -1,108 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
import json
|
||||
import os
|
||||
import requests
|
||||
import xml.etree.ElementTree as ET
|
||||
|
||||
from openpilot.common.basedir import BASEDIR
|
||||
from openpilot.selfdrive.ui.update_translations import LANGUAGES_FILE, TRANSLATIONS_DIR
|
||||
|
||||
BADGE_HEIGHT = 20 + 8
|
||||
SHIELDS_URL = "https://img.shields.io/badge"
|
||||
|
||||
def parse_po_file(file_path):
|
||||
"""
|
||||
Parse a .po file and count total and unfinished translations.
|
||||
Returns: (total_translations, unfinished_translations)
|
||||
"""
|
||||
with open(file_path) as f:
|
||||
content = f.read()
|
||||
|
||||
total_translations = 0
|
||||
unfinished_translations = 0
|
||||
|
||||
# Split into entries (separated by blank lines)
|
||||
entries = content.split('\n\n')
|
||||
|
||||
for entry in entries:
|
||||
# Skip header entry (contains Project-Id-Version)
|
||||
if 'Project-Id-Version' in entry:
|
||||
continue
|
||||
|
||||
# Check if this entry has a msgid (translation entry)
|
||||
# After skipping header, any entry with msgid " is a translation
|
||||
# (both msgid "content" and msgid "" for multiline contain msgid ")
|
||||
if 'msgid "' not in entry:
|
||||
continue
|
||||
|
||||
total_translations += 1
|
||||
|
||||
# Check if msgstr is empty (unfinished translation)
|
||||
if 'msgstr ""' in entry:
|
||||
# Check if there are continuation lines with content after msgstr ""
|
||||
lines = entry.split('\n')
|
||||
msgstr_idx = None
|
||||
for i, line in enumerate(lines):
|
||||
if line.strip().startswith('msgstr ""'):
|
||||
msgstr_idx = i
|
||||
break
|
||||
|
||||
if msgstr_idx is not None:
|
||||
# Check if any continuation lines have content
|
||||
has_content = False
|
||||
for line in lines[msgstr_idx + 1:]:
|
||||
stripped = line.strip()
|
||||
# Continuation line with content
|
||||
if stripped.startswith('"') and len(stripped) > 2:
|
||||
has_content = True
|
||||
break
|
||||
# End of entry
|
||||
if stripped.startswith(('msgid', '#')) or not stripped:
|
||||
break
|
||||
|
||||
if not has_content:
|
||||
unfinished_translations += 1
|
||||
|
||||
return (total_translations, unfinished_translations)
|
||||
|
||||
if __name__ == "__main__":
|
||||
with open(LANGUAGES_FILE) as f:
|
||||
translation_files = json.load(f)
|
||||
|
||||
badge_svg = []
|
||||
max_badge_width = 0 # keep track of max width to set parent element
|
||||
for idx, (name, file) in enumerate(translation_files.items()):
|
||||
po_file_path = os.path.join(str(TRANSLATIONS_DIR), f"app_{file}.po")
|
||||
|
||||
total_translations, unfinished_translations = parse_po_file(po_file_path)
|
||||
|
||||
percent_finished = int(100 - (unfinished_translations / total_translations * 100.)) if total_translations > 0 else 0
|
||||
color = f"rgb{(94, 188, 0) if percent_finished == 100 else (248, 255, 50) if percent_finished > 90 else (204, 55, 27)}"
|
||||
|
||||
# Download badge
|
||||
badge_label = f"LANGUAGE {name}"
|
||||
badge_message = f"{percent_finished}% complete"
|
||||
if unfinished_translations != 0:
|
||||
badge_message += f" ({unfinished_translations} unfinished)"
|
||||
|
||||
r = requests.get(f"{SHIELDS_URL}/{badge_label}-{badge_message}-{color}", timeout=10)
|
||||
assert r.status_code == 200, "Error downloading badge"
|
||||
content_svg = r.content.decode("utf-8")
|
||||
|
||||
xml = ET.fromstring(content_svg)
|
||||
assert "width" in xml.attrib
|
||||
max_badge_width = max(max_badge_width, int(xml.attrib["width"]))
|
||||
|
||||
# Make tag ids in each badge unique to combine them into one svg
|
||||
for tag in ("r", "s"):
|
||||
content_svg = content_svg.replace(f'id="{tag}"', f'id="{tag}{idx}"')
|
||||
content_svg = content_svg.replace(f'"url(#{tag})"', f'"url(#{tag}{idx})"')
|
||||
|
||||
badge_svg.extend([f'<g transform="translate(0, {idx * BADGE_HEIGHT})">', content_svg, "</g>"])
|
||||
|
||||
badge_svg.insert(0, '<svg xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" ' +
|
||||
f'height="{len(translation_files) * BADGE_HEIGHT}" width="{max_badge_width}">')
|
||||
badge_svg.append("</svg>")
|
||||
|
||||
with open(os.path.join(BASEDIR, "translation_badge.svg"), "w") as badge_f:
|
||||
badge_f.write("\n".join(badge_svg))
|
||||
@@ -8,7 +8,6 @@ import ast
|
||||
import os
|
||||
import re
|
||||
from dataclasses import dataclass, field
|
||||
from datetime import UTC, datetime
|
||||
from pathlib import Path
|
||||
|
||||
|
||||
@@ -165,18 +164,18 @@ def write_po(path: str | Path, header: POEntry | None, entries: list[POEntry]) -
|
||||
if header:
|
||||
for c in header.comments:
|
||||
f.write(c + '\n')
|
||||
if header.flags:
|
||||
f.write('#, ' + ', '.join(header.flags) + '\n')
|
||||
f.write(f'msgid {_quote("")}\n')
|
||||
f.write(f'msgstr {_quote(header.msgstr)}\n\n')
|
||||
|
||||
for entry in entries:
|
||||
for c in entry.comments:
|
||||
f.write(c + '\n')
|
||||
for ref in entry.source_refs:
|
||||
# Keep file-level context for translators, but drop line numbers to
|
||||
# avoid churning PO diffs on unrelated code edits.
|
||||
source_files = sorted({ref.rsplit(':', 1)[0] for ref in entry.source_refs})
|
||||
for ref in source_files:
|
||||
f.write(f'#: {ref}\n')
|
||||
if entry.flags:
|
||||
f.write('#, ' + ', '.join(entry.flags) + '\n')
|
||||
# Runtime loading ignores gettext flags; omit them to reduce noise.
|
||||
f.write(f'msgid {_quote(entry.msgid)}\n')
|
||||
if entry.is_plural:
|
||||
f.write(f'msgid_plural {_quote(entry.msgid_plural)}\n')
|
||||
@@ -256,31 +255,24 @@ def extract_strings(files: list[str], basedir: str) -> list[POEntry]:
|
||||
|
||||
# ──── POT generation ────
|
||||
|
||||
def _build_pot_header() -> POEntry:
|
||||
return POEntry(
|
||||
msgstr='Content-Type: text/plain; charset=UTF-8\n',
|
||||
)
|
||||
|
||||
|
||||
def _build_po_header(language: str) -> POEntry:
|
||||
plural_forms = PLURAL_FORMS.get(language, 'nplurals=2; plural=(n != 1);')
|
||||
return POEntry(
|
||||
msgstr='Content-Type: text/plain; charset=UTF-8\n' +
|
||||
f'Language: {language}\n' +
|
||||
f'Plural-Forms: {plural_forms}\n',
|
||||
)
|
||||
|
||||
|
||||
def generate_pot(entries: list[POEntry], pot_path: str | Path) -> None:
|
||||
"""Generate a .pot template file from extracted entries."""
|
||||
now = datetime.now(UTC).strftime('%Y-%m-%d %H:%M%z')
|
||||
header = POEntry(
|
||||
comments=[
|
||||
'# SOME DESCRIPTIVE TITLE.',
|
||||
"# Copyright (C) YEAR THE PACKAGE'S COPYRIGHT HOLDER",
|
||||
'# This file is distributed under the same license as the PACKAGE package.',
|
||||
'# FIRST AUTHOR <EMAIL@ADDRESS>, YEAR.',
|
||||
'#',
|
||||
],
|
||||
flags=['fuzzy'],
|
||||
msgstr='Project-Id-Version: PACKAGE VERSION\n' +
|
||||
'Report-Msgid-Bugs-To: \n' +
|
||||
f'POT-Creation-Date: {now}\n' +
|
||||
'PO-Revision-Date: YEAR-MO-DA HO:MI+ZONE\n' +
|
||||
'Last-Translator: FULL NAME <EMAIL@ADDRESS>\n' +
|
||||
'Language-Team: LANGUAGE <LL@li.org>\n' +
|
||||
'Language: \n' +
|
||||
'MIME-Version: 1.0\n' +
|
||||
'Content-Type: text/plain; charset=UTF-8\n' +
|
||||
'Content-Transfer-Encoding: 8bit\n' +
|
||||
'Plural-Forms: nplurals=INTEGER; plural=EXPRESSION;\n',
|
||||
)
|
||||
write_po(pot_path, header, entries)
|
||||
write_po(pot_path, _build_pot_header(), entries)
|
||||
|
||||
|
||||
# ──── PO init (replaces msginit) ────
|
||||
@@ -305,43 +297,22 @@ def init_po(pot_path: str | Path, po_path: str | Path, language: str) -> None:
|
||||
"""Create a new .po file from a .pot template (replaces msginit)."""
|
||||
_, entries = parse_po(pot_path)
|
||||
plural_forms = PLURAL_FORMS.get(language, 'nplurals=2; plural=(n != 1);')
|
||||
now = datetime.now(UTC).strftime('%Y-%m-%d %H:%M%z')
|
||||
|
||||
header = POEntry(
|
||||
comments=[
|
||||
f'# {language} translations for PACKAGE package.',
|
||||
"# Copyright (C) YEAR THE PACKAGE'S COPYRIGHT HOLDER",
|
||||
'# This file is distributed under the same license as the PACKAGE package.',
|
||||
'# Automatically generated.',
|
||||
'#',
|
||||
],
|
||||
msgstr='Project-Id-Version: PACKAGE VERSION\n' +
|
||||
'Report-Msgid-Bugs-To: \n' +
|
||||
f'POT-Creation-Date: {now}\n' +
|
||||
f'PO-Revision-Date: {now}\n' +
|
||||
'Last-Translator: Automatically generated\n' +
|
||||
'Language-Team: none\n' +
|
||||
f'Language: {language}\n' +
|
||||
'MIME-Version: 1.0\n' +
|
||||
'Content-Type: text/plain; charset=UTF-8\n' +
|
||||
'Content-Transfer-Encoding: 8bit\n' +
|
||||
f'Plural-Forms: {plural_forms}\n',
|
||||
)
|
||||
|
||||
nplurals = int(re.search(r'nplurals=(\d+)', plural_forms).group(1))
|
||||
for e in entries:
|
||||
if e.is_plural:
|
||||
e.msgstr_plural = dict.fromkeys(range(nplurals), '')
|
||||
|
||||
write_po(po_path, header, entries)
|
||||
write_po(po_path, _build_po_header(language), entries)
|
||||
|
||||
|
||||
# ──── PO merge (replaces msgmerge) ────
|
||||
|
||||
def merge_po(po_path: str | Path, pot_path: str | Path) -> None:
|
||||
"""Update a .po file with entries from a .pot template (replaces msgmerge --update)."""
|
||||
po_header, po_entries = parse_po(po_path)
|
||||
_, po_entries = parse_po(po_path)
|
||||
_, pot_entries = parse_po(pot_path)
|
||||
language = Path(po_path).stem.removeprefix("app_")
|
||||
|
||||
existing = {e.msgid: e for e in po_entries}
|
||||
merged = []
|
||||
@@ -359,4 +330,4 @@ def merge_po(po_path: str | Path, pot_path: str | Path) -> None:
|
||||
merged.append(pot_e)
|
||||
|
||||
merged.sort(key=lambda e: e.msgid)
|
||||
write_po(po_path, po_header, merged)
|
||||
write_po(po_path, _build_po_header(language), merged)
|
||||
|
||||
@@ -105,7 +105,7 @@ class TestSpeedLimitAssist:
|
||||
assert not self.sla.is_active
|
||||
assert V_CRUISE_UNSET == self.sla.get_v_target_from_control()
|
||||
|
||||
@pytest.mark.parametrize("car_name", [RIVIAN.RIVIAN_R1_GEN1, TESLA.TESLA_MODEL_Y], indirect=True)
|
||||
@pytest.mark.parametrize("car_name", [RIVIAN.RIVIAN_R1, TESLA.TESLA_MODEL_Y], indirect=True)
|
||||
def test_disallowed_brands(self, car_name):
|
||||
"""
|
||||
Speed Limit Assist is disabled for the following brands and conditions:
|
||||
|
||||
@@ -588,6 +588,10 @@
|
||||
"title": "Last Update Uptime Onroad",
|
||||
"description": ""
|
||||
},
|
||||
"LateralManeuverMode": {
|
||||
"title": "Lateral Maneuver Mode",
|
||||
"description": ""
|
||||
},
|
||||
"LeadDepartAlert": {
|
||||
"title": "Lead Departure Alert (Beta)",
|
||||
"description": "A chime and on-screen alert (TIZI/TICI only) will play when you are stopped, and the vehicle in front of you start moving. <br>Note: This chime is only designed as a notification. It is the driver's responsibility to observe their environment and make decisions accordingly."
|
||||
|
||||
@@ -3,11 +3,16 @@ Import('env', 'arch', 'messaging', 'common', 'visionipc')
|
||||
libs = [common, messaging, visionipc,
|
||||
'avformat', 'avcodec', 'swresample', 'avutil', 'x264',
|
||||
'pthread', 'z', 'm', 'zstd']
|
||||
frameworks = []
|
||||
|
||||
src = ['logger.cc', 'zstd_writer.cc', 'video_writer.cc', 'encoder/encoder.cc', 'encoder/v4l_encoder.cc', 'encoder/jpeg_encoder.cc']
|
||||
if arch != "larch64":
|
||||
src += ['encoder/ffmpeg_encoder.cc']
|
||||
libs += ['yuv']
|
||||
if arch == "Darwin":
|
||||
frameworks += ['VideoToolbox', 'CoreMedia', 'CoreFoundation', 'CoreVideo']
|
||||
else:
|
||||
libs += ['va', 'va-drm', 'drm']
|
||||
|
||||
if arch == "Darwin":
|
||||
# exclude v4l
|
||||
@@ -16,9 +21,9 @@ if arch == "Darwin":
|
||||
logger_lib = env.Library('logger', src)
|
||||
libs.insert(0, logger_lib)
|
||||
|
||||
env.Program('loggerd', ['loggerd.cc'], LIBS=libs)
|
||||
env.Program('encoderd', ['encoderd.cc'], LIBS=libs + ["jpeg"])
|
||||
env.Program('bootlog.cc', LIBS=libs)
|
||||
env.Program('loggerd', ['loggerd.cc'], LIBS=libs, FRAMEWORKS=frameworks)
|
||||
env.Program('encoderd', ['encoderd.cc'], LIBS=libs + ["jpeg"], FRAMEWORKS=frameworks)
|
||||
env.Program('bootlog.cc', LIBS=libs, FRAMEWORKS=frameworks)
|
||||
|
||||
if GetOption('extras'):
|
||||
env.Program('tests/test_logger', ['tests/test_runner.cc', 'tests/test_logger.cc', 'tests/test_zstd_writer.cc'], LIBS=libs)
|
||||
|
||||
@@ -46,6 +46,9 @@ def not_joystick(started: bool, params: Params, CP: car.CarParams) -> bool:
|
||||
def long_maneuver(started: bool, params: Params, CP: car.CarParams) -> bool:
|
||||
return started and params.get_bool("LongitudinalManeuverMode")
|
||||
|
||||
def lat_maneuver(started: bool, params: Params, CP: car.CarParams) -> bool:
|
||||
return started and params.get_bool("LateralManeuverMode")
|
||||
|
||||
def not_long_maneuver(started: bool, params: Params, CP: car.CarParams) -> bool:
|
||||
return started and not params.get_bool("LongitudinalManeuverMode")
|
||||
|
||||
@@ -142,6 +145,7 @@ procs = [
|
||||
PythonProcess("pigeond", "system.ubloxd.pigeond", ublox, enabled=TICI),
|
||||
PythonProcess("plannerd", "selfdrive.controls.plannerd", not_long_maneuver),
|
||||
PythonProcess("maneuversd", "tools.longitudinal_maneuvers.maneuversd", long_maneuver),
|
||||
PythonProcess("lateral_maneuversd", "tools.lateral_maneuvers.lateral_maneuversd", lat_maneuver),
|
||||
PythonProcess("radard", "selfdrive.controls.radard", only_onroad),
|
||||
PythonProcess("hardwared", "system.hardware.hardwared", always_run),
|
||||
PythonProcess("tombstoned", "system.tombstoned", always_run, enabled=not PC),
|
||||
|
||||
@@ -457,6 +457,11 @@ class GuiApplication(GuiApplicationExt):
|
||||
|
||||
def texture(self, asset_path: str, width: int | None = None, height: int | None = None,
|
||||
alpha_premultiply=False, keep_aspect_ratio=True, flip_x: bool = False) -> rl.Texture:
|
||||
if width is not None:
|
||||
width = round(width)
|
||||
if height is not None:
|
||||
height = round(height)
|
||||
|
||||
cache_key = f"{asset_path}_{width}_{height}_{alpha_premultiply}_{keep_aspect_ratio}_{flip_x}"
|
||||
if cache_key in self._textures:
|
||||
return self._textures[cache_key]
|
||||
|
||||
BIN
third_party/bootstrap/bootstrap-icons.ttf
LFS
vendored
Normal file
BIN
third_party/bootstrap/bootstrap-icons.ttf
LFS
vendored
Normal file
Binary file not shown.
10
third_party/bootstrap/pull.sh
vendored
10
third_party/bootstrap/pull.sh
vendored
@@ -12,3 +12,13 @@ cd icons
|
||||
git fetch --all
|
||||
git checkout d5aa187483a1b0b186f87adcfa8576350d970d98
|
||||
cp bootstrap-icons.svg ../
|
||||
|
||||
# Convert WOFF → TTF for imgui (imgui only reads TTF/OTF)
|
||||
python3 -c "
|
||||
from fontTools.ttLib import TTFont
|
||||
import io
|
||||
f = TTFont('font/fonts/bootstrap-icons.woff')
|
||||
f.flavor = None
|
||||
f.save('../bootstrap-icons.ttf')
|
||||
print('bootstrap-icons.ttf written')
|
||||
"
|
||||
|
||||
@@ -4,7 +4,7 @@ import shutil
|
||||
|
||||
import libusb
|
||||
|
||||
Import('env', 'arch', 'common', 'messaging', 'visionipc', 'cereal')
|
||||
Import('env', 'arch', 'common', 'messaging', 'visionipc', 'cereal', 'replay_lib')
|
||||
|
||||
# Detect Qt - skip build if not available
|
||||
if arch == "Darwin":
|
||||
@@ -18,9 +18,6 @@ else:
|
||||
if not has_qt:
|
||||
Return()
|
||||
|
||||
SConscript(['#tools/replay/SConscript'])
|
||||
Import('replay_lib')
|
||||
|
||||
qt_env = env.Clone()
|
||||
qt_modules = ["Widgets", "Gui", "Core"]
|
||||
|
||||
@@ -69,7 +66,7 @@ base_frameworks = qt_env['FRAMEWORKS']
|
||||
base_libs = [common, messaging, cereal, visionipc, 'm', 'pthread'] + qt_env["LIBS"]
|
||||
|
||||
if arch == "Darwin":
|
||||
base_frameworks.append('QtCharts')
|
||||
base_frameworks += ['QtCharts', 'CoreFoundation', 'CoreVideo', 'CoreMedia', 'IOKit', 'Security', 'VideoToolbox']
|
||||
else:
|
||||
base_libs.append('Qt5Charts')
|
||||
|
||||
@@ -78,6 +75,8 @@ cabana_env['CPPPATH'] += [libusb.INCLUDE_DIR]
|
||||
cabana_env['LIBPATH'] += [libusb.LIB_DIR]
|
||||
|
||||
cabana_libs = [cereal, messaging, visionipc, replay_lib, 'avformat', 'avcodec', 'swresample', 'avutil', 'x264', 'z', 'bz2', 'zstd', 'yuv', 'usb-1.0'] + base_libs
|
||||
if arch != "Darwin":
|
||||
cabana_libs += ['va', 'va-drm', 'drm']
|
||||
opendbc_path = '-DOPENDBC_FILE_PATH=\'"%s"\'' % (cabana_env.Dir("../../opendbc/dbc").abspath)
|
||||
cabana_env['CXXFLAGS'] += [opendbc_path]
|
||||
|
||||
|
||||
@@ -33,6 +33,6 @@ fi
|
||||
|
||||
# Build _cabana
|
||||
cd "$ROOT"
|
||||
scons -j"$(nproc)" tools/cabana/_cabana
|
||||
scons -j4 tools/cabana/_cabana
|
||||
|
||||
exec "$DIR/_cabana" "$@"
|
||||
|
||||
9
tools/jotpluggler/.gitignore
vendored
Normal file
9
tools/jotpluggler/.gitignore
vendored
Normal file
@@ -0,0 +1,9 @@
|
||||
__pycache__/
|
||||
jot_*.o
|
||||
*.o
|
||||
jotpluggler
|
||||
car_fingerprint_to_dbc.h
|
||||
generated_dbcs/.stamp
|
||||
generated_dbcs/*.dbc
|
||||
layouts/.jotpluggler_autosave/
|
||||
reports/
|
||||
92
tools/jotpluggler/SConscript
Normal file
92
tools/jotpluggler/SConscript
Normal file
@@ -0,0 +1,92 @@
|
||||
import os
|
||||
import imgui
|
||||
import libusb
|
||||
from opendbc import get_generated_dbcs
|
||||
from opendbc.car import Bus
|
||||
from opendbc.car.fingerprints import MIGRATION
|
||||
from opendbc.car.values import PLATFORMS
|
||||
from openpilot.common.basedir import BASEDIR
|
||||
|
||||
Import('env', 'arch', 'common', 'messaging', 'visionipc', 'cereal', 'replay_lib')
|
||||
|
||||
jot_env = env.Clone()
|
||||
jot_env["LIBPATH"] += [imgui.MESA_DIR, libusb.LIB_DIR]
|
||||
jot_env["CPPPATH"] += [imgui.INCLUDE_DIR, libusb.INCLUDE_DIR]
|
||||
jot_env["CXXFLAGS"] += [
|
||||
"-DGLFW_INCLUDE_NONE",
|
||||
'-DJOTP_REPO_ROOT=\'"%s"\'' % os.path.realpath(BASEDIR),
|
||||
]
|
||||
|
||||
def materialize_generated_dbcs(target, source, env):
|
||||
out_dir = os.path.dirname(str(target[0]))
|
||||
os.makedirs(out_dir, exist_ok=True)
|
||||
|
||||
for name in os.listdir(out_dir):
|
||||
if name.endswith('.dbc'):
|
||||
os.unlink(os.path.join(out_dir, name))
|
||||
|
||||
for name, content in sorted(get_generated_dbcs().items()):
|
||||
with open(os.path.join(out_dir, f"{name}.dbc"), "w") as f:
|
||||
f.write(content)
|
||||
|
||||
with open(str(target[0]), "w") as f:
|
||||
f.write("ok\n")
|
||||
|
||||
return None
|
||||
|
||||
def write_car_fingerprint_to_dbc_header(target, source, env):
|
||||
pairs = {}
|
||||
|
||||
for name, platform in sorted(PLATFORMS.items()):
|
||||
dbc = platform.config.dbc_dict.get(Bus.pt, "")
|
||||
if not dbc and name.startswith("TESLA_"):
|
||||
dbc = platform.config.dbc_dict.get(Bus.party, "")
|
||||
if not dbc and name == "COMMA_BODY":
|
||||
dbc = "comma_body"
|
||||
if dbc and name != "MOCK":
|
||||
pairs[name] = dbc
|
||||
|
||||
for fingerprint, car in sorted(MIGRATION.items()):
|
||||
dbc = pairs.get(str(car), "")
|
||||
if dbc:
|
||||
pairs[fingerprint] = dbc
|
||||
|
||||
lines = [
|
||||
"#pragma once",
|
||||
"",
|
||||
"#include <string_view>",
|
||||
"#include <utility>",
|
||||
"",
|
||||
"inline constexpr std::pair<std::string_view, std::string_view> kCarFingerprintToDbc[] = {",
|
||||
]
|
||||
lines.extend(f' {{"{fingerprint}", "{dbc}"}},' for fingerprint, dbc in sorted(pairs.items()))
|
||||
lines.extend([
|
||||
"};",
|
||||
"",
|
||||
"inline std::string_view dbc_for_car_fingerprint(std::string_view fingerprint) {",
|
||||
" for (const auto &[car_fingerprint, dbc] : kCarFingerprintToDbc) {",
|
||||
" if (car_fingerprint == fingerprint) return dbc;",
|
||||
" }",
|
||||
" return {};",
|
||||
"}",
|
||||
"",
|
||||
])
|
||||
|
||||
with open(str(target[0]), "w") as f:
|
||||
f.write("\n".join(lines))
|
||||
|
||||
return None
|
||||
|
||||
generated_dbc_stamp = jot_env.Command(f"generated_dbcs/.stamp", [], materialize_generated_dbcs)
|
||||
car_fingerprint_to_dbc = jot_env.Command("car_fingerprint_to_dbc.h", [], write_car_fingerprint_to_dbc_header)
|
||||
|
||||
libs = [replay_lib, common, messaging, visionipc, cereal, File(f"{imgui.LIB_DIR}/libimgui.a"), File(f"{imgui.LIB_DIR}/libglfw3.a"),
|
||||
"avformat", "avcodec", "avutil", "x264", "yuv", "z", "bz2", "zstd", "m", "pthread", "usb-1.0"]
|
||||
if arch == "Darwin":
|
||||
jot_env["FRAMEWORKS"] = ["OpenGL", "Cocoa", "IOKit", "CoreFoundation", "CoreVideo", "CoreMedia", "VideoToolbox"]
|
||||
else:
|
||||
libs += ["GL", "dl", "va", "va-drm", "drm"]
|
||||
|
||||
program = jot_env.Program("jotpluggler", jot_env.Glob("*.cc"), LIBS=libs)
|
||||
jot_env.Depends(program, generated_dbc_stamp)
|
||||
jot_env.Depends(program, car_fingerprint_to_dbc)
|
||||
1914
tools/jotpluggler/app.cc
Normal file
1914
tools/jotpluggler/app.cc
Normal file
File diff suppressed because it is too large
Load Diff
884
tools/jotpluggler/app.h
Normal file
884
tools/jotpluggler/app.h
Normal file
@@ -0,0 +1,884 @@
|
||||
#pragma once
|
||||
|
||||
#include "cereal/gen/cpp/log.capnp.h"
|
||||
#include "imgui.h"
|
||||
#include "tools/jotpluggler/dbc.h"
|
||||
#include "tools/jotpluggler/util.h"
|
||||
|
||||
#include <algorithm>
|
||||
#include <array>
|
||||
#include <atomic>
|
||||
#include <cstdint>
|
||||
#include <filesystem>
|
||||
#include <future>
|
||||
#include <functional>
|
||||
#include <memory>
|
||||
#include <optional>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
#include <unordered_map>
|
||||
#include <vector>
|
||||
|
||||
// *****
|
||||
// app options & entry point
|
||||
// *****
|
||||
|
||||
struct Options {
|
||||
std::string layout;
|
||||
std::string route_name;
|
||||
std::string data_dir;
|
||||
std::string output_path;
|
||||
std::string stream_address = "127.0.0.1";
|
||||
int width = 1600;
|
||||
int height = 900;
|
||||
bool show = false;
|
||||
bool sync_load = false;
|
||||
bool stream = false;
|
||||
double stream_buffer_seconds = 30.0;
|
||||
};
|
||||
|
||||
int run(const Options &options);
|
||||
|
||||
// *****
|
||||
// sketch layout & route data
|
||||
// *****
|
||||
|
||||
struct PlotRange {
|
||||
bool valid = false;
|
||||
double left = 0.0;
|
||||
double right = 0.0;
|
||||
double bottom = 0.0;
|
||||
double top = 1.0;
|
||||
bool has_y_limit_min = false;
|
||||
bool has_y_limit_max = false;
|
||||
double y_limit_min = 0.0;
|
||||
double y_limit_max = 1.0;
|
||||
};
|
||||
|
||||
struct CustomPythonSeries {
|
||||
std::string linked_source;
|
||||
std::vector<std::string> additional_sources;
|
||||
std::string globals_code;
|
||||
std::string function_code;
|
||||
};
|
||||
|
||||
struct Curve {
|
||||
std::string name;
|
||||
std::string label;
|
||||
std::array<uint8_t, 3> color = {160, 170, 180};
|
||||
bool visible = true;
|
||||
bool derivative = false;
|
||||
double derivative_dt = 0.0;
|
||||
double value_scale = 1.0;
|
||||
double value_offset = 0.0;
|
||||
bool runtime_only = false;
|
||||
std::optional<CustomPythonSeries> custom_python;
|
||||
std::string runtime_error_message;
|
||||
std::vector<double> xs;
|
||||
std::vector<double> ys;
|
||||
};
|
||||
|
||||
enum class PaneKind : uint8_t {
|
||||
Plot,
|
||||
Map,
|
||||
Camera,
|
||||
};
|
||||
|
||||
enum class CameraViewKind : uint8_t {
|
||||
Road,
|
||||
Driver,
|
||||
WideRoad,
|
||||
QRoad,
|
||||
};
|
||||
|
||||
struct Pane {
|
||||
PaneKind kind = PaneKind::Plot;
|
||||
CameraViewKind camera_view = CameraViewKind::Road;
|
||||
std::string title;
|
||||
PlotRange range;
|
||||
std::vector<Curve> curves;
|
||||
};
|
||||
|
||||
enum class SplitOrientation {
|
||||
Horizontal,
|
||||
Vertical,
|
||||
};
|
||||
|
||||
struct WorkspaceNode {
|
||||
bool is_pane = false;
|
||||
int pane_index = -1;
|
||||
SplitOrientation orientation = SplitOrientation::Horizontal;
|
||||
std::vector<float> sizes;
|
||||
std::vector<WorkspaceNode> children;
|
||||
};
|
||||
|
||||
struct WorkspaceTab {
|
||||
std::string tab_name;
|
||||
WorkspaceNode root;
|
||||
std::vector<Pane> panes;
|
||||
};
|
||||
|
||||
struct RouteSeries {
|
||||
std::string path;
|
||||
std::vector<double> times;
|
||||
std::vector<double> values;
|
||||
};
|
||||
|
||||
struct CameraSegmentFile {
|
||||
int segment = -1;
|
||||
std::string path;
|
||||
};
|
||||
|
||||
struct CameraFrameIndexEntry {
|
||||
double timestamp = 0.0;
|
||||
int segment = -1;
|
||||
int decode_index = -1;
|
||||
uint32_t frame_id = 0;
|
||||
};
|
||||
|
||||
struct CameraFeedIndex {
|
||||
std::vector<CameraSegmentFile> segment_files;
|
||||
std::vector<CameraFrameIndexEntry> entries;
|
||||
};
|
||||
|
||||
enum class LogOrigin : uint8_t {
|
||||
Log,
|
||||
Android,
|
||||
Alert,
|
||||
};
|
||||
|
||||
struct LogEntry {
|
||||
double mono_time = 0.0;
|
||||
double boot_time = 0.0;
|
||||
double wall_time = 0.0;
|
||||
uint8_t level = 20;
|
||||
std::string source;
|
||||
std::string func;
|
||||
std::string message;
|
||||
std::string context;
|
||||
LogOrigin origin = LogOrigin::Log;
|
||||
};
|
||||
|
||||
struct EnumInfo {
|
||||
std::vector<std::string> names;
|
||||
};
|
||||
|
||||
struct SeriesFormat {
|
||||
int decimals = 3;
|
||||
bool integer_like = false;
|
||||
bool has_negative = false;
|
||||
int digits_before = 1;
|
||||
int total_width = 0;
|
||||
char fmt[16] = "%7.3f";
|
||||
};
|
||||
|
||||
enum class CanServiceKind : uint8_t {
|
||||
Can,
|
||||
Sendcan,
|
||||
};
|
||||
|
||||
struct CanMessageId {
|
||||
CanServiceKind service = CanServiceKind::Can;
|
||||
uint8_t bus = 0;
|
||||
uint32_t address = 0;
|
||||
|
||||
bool operator==(const CanMessageId &other) const {
|
||||
return service == other.service && bus == other.bus && address == other.address;
|
||||
}
|
||||
};
|
||||
|
||||
struct CanMessageIdHash {
|
||||
size_t operator()(const CanMessageId &id) const {
|
||||
return (static_cast<size_t>(id.service) << 40)
|
||||
^ (static_cast<size_t>(id.bus) << 32)
|
||||
^ static_cast<size_t>(id.address);
|
||||
}
|
||||
};
|
||||
|
||||
struct CanFrameSample {
|
||||
double mono_time = 0.0;
|
||||
uint16_t bus_time = 0;
|
||||
std::string data;
|
||||
};
|
||||
|
||||
struct LiveCanFrame {
|
||||
double mono_time = 0.0;
|
||||
uint8_t bus = 0;
|
||||
uint32_t address = 0;
|
||||
uint16_t bus_time = 0;
|
||||
std::string data;
|
||||
};
|
||||
|
||||
struct CanMessageData {
|
||||
CanMessageId id;
|
||||
std::vector<CanFrameSample> samples;
|
||||
};
|
||||
|
||||
struct TimelineEntry {
|
||||
enum class Type : uint8_t {
|
||||
None,
|
||||
Engaged,
|
||||
AlertInfo,
|
||||
AlertWarning,
|
||||
AlertCritical,
|
||||
};
|
||||
|
||||
double start_time = 0.0;
|
||||
double end_time = 0.0;
|
||||
Type type = Type::None;
|
||||
};
|
||||
|
||||
struct GpsPoint {
|
||||
double time = 0.0;
|
||||
double lat = 0.0;
|
||||
double lon = 0.0;
|
||||
float bearing = 0.0f;
|
||||
TimelineEntry::Type type = TimelineEntry::Type::None;
|
||||
};
|
||||
|
||||
struct GpsTrace {
|
||||
std::vector<GpsPoint> points;
|
||||
double min_lat = 0.0;
|
||||
double max_lat = 0.0;
|
||||
double min_lon = 0.0;
|
||||
double max_lon = 0.0;
|
||||
};
|
||||
|
||||
enum class LogSelector : uint8_t {
|
||||
Auto,
|
||||
RLog,
|
||||
QLog,
|
||||
};
|
||||
|
||||
struct RouteIdentifier {
|
||||
std::string dongle_id;
|
||||
std::string log_id;
|
||||
int slice_begin = 0;
|
||||
int slice_end = -1;
|
||||
bool slice_explicit = false;
|
||||
LogSelector selector = LogSelector::Auto;
|
||||
bool selector_explicit = false;
|
||||
int available_begin = 0;
|
||||
int available_end = 0;
|
||||
|
||||
bool empty() const {
|
||||
return dongle_id.empty() || log_id.empty();
|
||||
}
|
||||
|
||||
std::string canonical() const {
|
||||
return empty() ? std::string() : dongle_id + "/" + log_id;
|
||||
}
|
||||
|
||||
std::string onebox() const {
|
||||
return empty() ? std::string() : dongle_id + "|" + log_id;
|
||||
}
|
||||
|
||||
std::string display_slice() const {
|
||||
const int begin = slice_explicit ? slice_begin : available_begin;
|
||||
const int end = slice_explicit ? slice_end : available_end;
|
||||
if (end < 0 || end == begin) {
|
||||
return std::to_string(begin);
|
||||
}
|
||||
return std::to_string(begin) + ":" + std::to_string(end);
|
||||
}
|
||||
|
||||
char selector_char() const {
|
||||
switch (selector) {
|
||||
case LogSelector::RLog: return 'r';
|
||||
case LogSelector::QLog: return 'q';
|
||||
case LogSelector::Auto:
|
||||
default: return 'a';
|
||||
}
|
||||
}
|
||||
|
||||
std::string full_spec() const {
|
||||
if (empty()) return {};
|
||||
std::string spec = dongle_id + "/" + log_id;
|
||||
if (slice_explicit) {
|
||||
spec += "/";
|
||||
spec += display_slice();
|
||||
}
|
||||
if (selector_explicit) {
|
||||
spec += "/";
|
||||
spec.push_back(selector_char());
|
||||
}
|
||||
return spec;
|
||||
}
|
||||
};
|
||||
|
||||
struct RouteData {
|
||||
std::vector<RouteSeries> series;
|
||||
std::vector<std::string> paths;
|
||||
std::vector<std::string> roots;
|
||||
std::vector<CanMessageData> can_messages;
|
||||
CameraFeedIndex road_camera;
|
||||
CameraFeedIndex driver_camera;
|
||||
CameraFeedIndex wide_road_camera;
|
||||
CameraFeedIndex qroad_camera;
|
||||
GpsTrace gps_trace;
|
||||
std::vector<LogEntry> logs;
|
||||
std::vector<TimelineEntry> timeline;
|
||||
std::unordered_map<std::string, EnumInfo> enum_info;
|
||||
std::unordered_map<std::string, SeriesFormat> series_formats;
|
||||
std::string car_fingerprint;
|
||||
std::string dbc_name;
|
||||
RouteIdentifier route_id;
|
||||
bool has_time_range = false;
|
||||
double x_min = 0.0;
|
||||
double x_max = 1.0;
|
||||
};
|
||||
|
||||
struct StreamExtractBatch {
|
||||
std::vector<RouteSeries> series;
|
||||
std::vector<CanMessageData> can_messages;
|
||||
std::vector<LogEntry> logs;
|
||||
std::vector<TimelineEntry> timeline;
|
||||
std::unordered_map<std::string, EnumInfo> enum_info;
|
||||
std::string car_fingerprint;
|
||||
std::string dbc_name;
|
||||
bool has_time_offset = false;
|
||||
double time_offset = 0.0;
|
||||
};
|
||||
|
||||
struct SketchLayout {
|
||||
std::vector<WorkspaceTab> tabs;
|
||||
std::vector<std::string> roots;
|
||||
int current_tab_index = 0;
|
||||
};
|
||||
|
||||
enum class RouteLoadStage {
|
||||
Resolving,
|
||||
DownloadingSegment,
|
||||
ParsingSegment,
|
||||
Finished,
|
||||
};
|
||||
|
||||
struct RouteLoadProgress {
|
||||
RouteLoadStage stage = RouteLoadStage::Resolving;
|
||||
size_t segment_index = 0;
|
||||
size_t segment_count = 0;
|
||||
uint64_t current = 0;
|
||||
uint64_t total = 0;
|
||||
size_t segments_downloaded = 0;
|
||||
size_t segments_parsed = 0;
|
||||
size_t total_segments = 0;
|
||||
uint64_t bytes_downloaded = 0;
|
||||
int num_workers = 1;
|
||||
std::string segment_name;
|
||||
};
|
||||
|
||||
using RouteLoadProgressCallback = std::function<void(const RouteLoadProgress &)>;
|
||||
|
||||
class StreamAccumulator {
|
||||
public:
|
||||
explicit StreamAccumulator(const std::string &dbc_name = {}, std::optional<double> time_offset = std::nullopt);
|
||||
~StreamAccumulator();
|
||||
|
||||
StreamAccumulator(const StreamAccumulator &) = delete;
|
||||
StreamAccumulator &operator=(const StreamAccumulator &) = delete;
|
||||
|
||||
void setDbcName(const std::string &dbc_name);
|
||||
void appendEvent(cereal::Event::Which which, kj::ArrayPtr<const capnp::word> data);
|
||||
void appendCanFrames(CanServiceKind service, const std::vector<LiveCanFrame> &frames);
|
||||
StreamExtractBatch takeBatch();
|
||||
const std::string &carFingerprint() const;
|
||||
const std::string &dbc_name() const;
|
||||
std::optional<double> timeOffset() const;
|
||||
|
||||
private:
|
||||
struct Impl;
|
||||
std::unique_ptr<Impl> impl_;
|
||||
};
|
||||
|
||||
SketchLayout load_sketch_layout(const std::filesystem::path &layout_path);
|
||||
std::vector<std::string> available_dbc_names();
|
||||
std::vector<std::string> collect_route_roots_for_paths(const std::vector<std::string> &paths);
|
||||
std::optional<dbc::Database> load_dbc_by_name(const std::string &dbc_name);
|
||||
std::vector<RouteSeries> decode_can_messages(const std::vector<CanMessageData> &can_messages,
|
||||
const std::string &dbc_name,
|
||||
std::unordered_map<std::string, EnumInfo> *enum_info = nullptr);
|
||||
RouteData load_route_data(const std::string &route_name,
|
||||
const std::string &data_dir = {},
|
||||
const std::string &dbc_name = {},
|
||||
const RouteLoadProgressCallback &progress = {});
|
||||
RouteIdentifier parse_route_identifier(std::string_view route_name);
|
||||
void rebuild_gps_trace(RouteData *route_data);
|
||||
|
||||
// *****
|
||||
// icons
|
||||
// *****
|
||||
|
||||
namespace icon {
|
||||
constexpr const char ARROW_DOWN_UP[] = "\xef\x84\xa7";
|
||||
constexpr const char ARROW_LEFT_RIGHT[] = "\xef\x84\xab";
|
||||
constexpr const char BAR_CHART[] = "\xef\x85\xbe";
|
||||
constexpr const char BOX_ARROW_UP_RIGHT[] = "\xef\x87\x85";
|
||||
constexpr const char CLIPBOARD[] = "\xef\x8a\x90";
|
||||
constexpr const char CLIPBOARD2[] = "\xef\x9c\xb3";
|
||||
constexpr const char DISTRIBUTE_HORIZONTAL[] = "\xef\x8c\x83";
|
||||
constexpr const char DISTRIBUTE_VERTICAL[] = "\xef\x8c\x84";
|
||||
constexpr const char FILE_EARMARK_IMAGE[] = "\xef\x8d\xad";
|
||||
constexpr const char FILES[] = "\xef\x8f\x82";
|
||||
constexpr const char INFO_CIRCLE[] = "\xef\x90\xb1";
|
||||
constexpr const char PALETTE[] = "\xef\x92\xb1";
|
||||
constexpr const char PLUS_SLASH_MINUS[] = "\xef\x9a\xaa";
|
||||
constexpr const char SAVE[] = "\xef\x94\xa5";
|
||||
constexpr const char SLIDERS[] = "\xef\x95\xab";
|
||||
constexpr const char TRASH[] = "\xef\x97\x9e";
|
||||
constexpr const char X_SQUARE[] = "\xef\x98\xa9";
|
||||
constexpr const char ZOOM_OUT[] = "\xef\x98\xad";
|
||||
} // namespace icon
|
||||
|
||||
void icon_add_font(float size, bool merge = false, const ImFont *base_font = nullptr);
|
||||
bool icon_menu_item(const char *glyph,
|
||||
const char *label,
|
||||
const char *shortcut = nullptr,
|
||||
bool selected = false,
|
||||
bool enabled = true);
|
||||
|
||||
// *****
|
||||
// app session, UI state, & internal API
|
||||
// *****
|
||||
|
||||
class AsyncRouteLoader;
|
||||
class CameraFeedView;
|
||||
class StreamPoller;
|
||||
class MapDataManager;
|
||||
|
||||
enum class SessionDataMode : uint8_t {
|
||||
Route,
|
||||
Stream,
|
||||
};
|
||||
|
||||
enum class StreamSourceKind : uint8_t {
|
||||
CerealLocal,
|
||||
CerealRemote,
|
||||
};
|
||||
|
||||
struct StreamSourceConfig {
|
||||
StreamSourceKind kind = StreamSourceKind::CerealLocal;
|
||||
std::string address = "127.0.0.1";
|
||||
};
|
||||
|
||||
struct BrowserNode {
|
||||
std::string label;
|
||||
std::string full_path;
|
||||
std::vector<BrowserNode> children;
|
||||
};
|
||||
|
||||
struct AppSession {
|
||||
std::filesystem::path layout_path;
|
||||
std::filesystem::path autosave_path;
|
||||
std::string route_name;
|
||||
std::string data_dir;
|
||||
std::string dbc_override;
|
||||
StreamSourceConfig stream_source;
|
||||
double stream_buffer_seconds = 30.0;
|
||||
SessionDataMode data_mode = SessionDataMode::Route;
|
||||
RouteIdentifier route_id;
|
||||
SketchLayout layout;
|
||||
RouteData route_data;
|
||||
std::unordered_map<std::string, RouteSeries *> series_by_path;
|
||||
std::vector<BrowserNode> browser_nodes;
|
||||
std::unique_ptr<AsyncRouteLoader> route_loader;
|
||||
std::unique_ptr<StreamPoller> stream_poller;
|
||||
std::array<std::unique_ptr<CameraFeedView>, 4> pane_camera_feeds;
|
||||
std::unique_ptr<MapDataManager> map_data;
|
||||
bool async_route_loading = false;
|
||||
double next_stream_custom_refresh_time = 0.0;
|
||||
bool stream_paused = false;
|
||||
std::optional<double> stream_time_offset;
|
||||
};
|
||||
|
||||
struct TabUiState {
|
||||
struct MapPaneState {
|
||||
bool initialized = false;
|
||||
bool follow = false;
|
||||
float zoom = 1.0f;
|
||||
double center_lat = 0.0;
|
||||
double center_lon = 0.0;
|
||||
};
|
||||
|
||||
struct CameraPaneState {
|
||||
bool fit_to_pane = true;
|
||||
};
|
||||
|
||||
bool dock_needs_build = true;
|
||||
int active_pane_index = 0;
|
||||
int runtime_id = 0;
|
||||
ImVec2 last_dockspace_size = ImVec2(0.0f, 0.0f);
|
||||
std::vector<MapPaneState> map_panes;
|
||||
std::vector<CameraPaneState> camera_panes;
|
||||
};
|
||||
|
||||
struct CustomSeriesEditorState {
|
||||
bool open = false;
|
||||
bool open_help = false;
|
||||
bool request_select = false;
|
||||
bool selected = false;
|
||||
bool focus_name = false;
|
||||
int selected_template = 0;
|
||||
int selected_additional_source = -1;
|
||||
std::string name;
|
||||
std::string linked_source;
|
||||
std::vector<std::string> additional_sources;
|
||||
std::string globals_code;
|
||||
std::string function_code = "return value";
|
||||
std::string preview_label;
|
||||
std::vector<double> preview_xs;
|
||||
std::vector<double> preview_ys;
|
||||
bool preview_is_result = false;
|
||||
};
|
||||
|
||||
enum class LogTimeMode : uint8_t {
|
||||
Route,
|
||||
Boot,
|
||||
WallClock,
|
||||
};
|
||||
|
||||
struct LogsUiState {
|
||||
bool selected = false;
|
||||
bool request_select = false;
|
||||
bool all_sources = true;
|
||||
uint32_t enabled_levels_mask = 0b11110;
|
||||
int expanded_index = -1;
|
||||
std::string search;
|
||||
std::vector<std::string> selected_sources;
|
||||
double last_auto_scroll_time = -1.0;
|
||||
LogTimeMode time_mode = LogTimeMode::Route;
|
||||
};
|
||||
|
||||
struct AxisLimitsEditorState {
|
||||
bool open = false;
|
||||
int pane_index = -1;
|
||||
double x_min = 0.0;
|
||||
double x_max = 1.0;
|
||||
bool y_min_enabled = false;
|
||||
bool y_max_enabled = false;
|
||||
double y_min = 0.0;
|
||||
double y_max = 1.0;
|
||||
};
|
||||
|
||||
struct DbcEditorState {
|
||||
bool open = false;
|
||||
bool loaded = false;
|
||||
std::string source_name;
|
||||
std::filesystem::path source_path;
|
||||
enum class SourceKind : uint8_t {
|
||||
None,
|
||||
Generated,
|
||||
Opendbc,
|
||||
};
|
||||
SourceKind source_kind = SourceKind::None;
|
||||
std::string save_name;
|
||||
std::string text;
|
||||
};
|
||||
|
||||
enum class TimelineDragMode : uint8_t {
|
||||
None,
|
||||
ScrubCursor,
|
||||
PanViewport,
|
||||
ResizeLeft,
|
||||
ResizeRight,
|
||||
};
|
||||
|
||||
struct UndoStack {
|
||||
static constexpr size_t kMaxHistory = 50;
|
||||
|
||||
std::vector<SketchLayout> history;
|
||||
int position = -1;
|
||||
|
||||
void reset(const SketchLayout &layout) {
|
||||
history.clear();
|
||||
history.push_back(layout);
|
||||
position = 0;
|
||||
}
|
||||
|
||||
void push(const SketchLayout &layout) {
|
||||
if (position < 0) {
|
||||
reset(layout);
|
||||
return;
|
||||
}
|
||||
if (position + 1 < static_cast<int>(history.size())) {
|
||||
history.resize(static_cast<size_t>(position + 1));
|
||||
}
|
||||
history.push_back(layout);
|
||||
if (history.size() > kMaxHistory) {
|
||||
history.erase(history.begin());
|
||||
}
|
||||
position = static_cast<int>(history.size()) - 1;
|
||||
}
|
||||
|
||||
bool can_undo() const {
|
||||
return position > 0;
|
||||
}
|
||||
|
||||
bool can_redo() const {
|
||||
return position >= 0 && position + 1 < static_cast<int>(history.size());
|
||||
}
|
||||
|
||||
const SketchLayout &undo() {
|
||||
return history[static_cast<size_t>(--position)];
|
||||
}
|
||||
|
||||
const SketchLayout &redo() {
|
||||
return history[static_cast<size_t>(++position)];
|
||||
}
|
||||
};
|
||||
|
||||
struct UiState {
|
||||
bool open_open_route = false;
|
||||
bool open_stream = false;
|
||||
bool open_load_layout = false;
|
||||
bool open_save_layout = false;
|
||||
bool open_preferences = false;
|
||||
bool open_find_signal = false;
|
||||
bool request_close = false;
|
||||
bool request_reset_layout = false;
|
||||
bool request_save_layout = false;
|
||||
bool request_new_tab = false;
|
||||
bool request_duplicate_tab = false;
|
||||
bool request_close_tab = false;
|
||||
bool follow_latest = false;
|
||||
bool has_shared_range = false;
|
||||
bool has_tracker_time = false;
|
||||
bool layout_dirty = false;
|
||||
bool playback_loop = false;
|
||||
bool playback_playing = false;
|
||||
bool show_deprecated_fields = false;
|
||||
bool show_fps_overlay = false;
|
||||
bool fps_overlay_initialized = false;
|
||||
bool suppress_range_side_effects = false;
|
||||
bool browser_nodes_dirty = false;
|
||||
int active_tab_index = 0;
|
||||
int next_tab_runtime_id = 1;
|
||||
int requested_tab_index = -1;
|
||||
int rename_tab_index = -1;
|
||||
bool focus_rename_tab_input = false;
|
||||
std::vector<TabUiState> tabs;
|
||||
std::string route_buffer;
|
||||
std::string stream_address_buffer;
|
||||
std::string rename_tab_buffer;
|
||||
std::string browser_filter;
|
||||
std::string data_dir_buffer;
|
||||
std::string load_layout_buffer;
|
||||
std::string save_layout_buffer;
|
||||
std::string find_signal_buffer;
|
||||
std::string selected_browser_path;
|
||||
std::vector<std::string> selected_browser_paths;
|
||||
std::string browser_selection_anchor;
|
||||
std::string route_slice_buffer;
|
||||
std::string error_text;
|
||||
bool open_error_popup = false;
|
||||
std::string status_text = "Ready";
|
||||
std::string route_copy_feedback_text;
|
||||
double route_copy_feedback_until = 0.0;
|
||||
bool editing_route_slice = false;
|
||||
bool focus_route_slice_input = false;
|
||||
StreamSourceKind stream_source_kind = StreamSourceKind::CerealLocal;
|
||||
float sidebar_width = 320.0f;
|
||||
double route_x_min = 0.0;
|
||||
double route_x_max = 1.0;
|
||||
double x_view_min = 0.0;
|
||||
double x_view_max = 1.0;
|
||||
double tracker_time = 0.0;
|
||||
double playback_rate = 1.0;
|
||||
double playback_step = 0.1;
|
||||
double stream_buffer_seconds = 30.0;
|
||||
TimelineDragMode timeline_drag_mode = TimelineDragMode::None;
|
||||
double timeline_drag_anchor_time = 0.0;
|
||||
double timeline_drag_anchor_x_min = 0.0;
|
||||
double timeline_drag_anchor_x_max = 0.0;
|
||||
AxisLimitsEditorState axis_limits;
|
||||
DbcEditorState dbc_editor;
|
||||
CustomSeriesEditorState custom_series;
|
||||
LogsUiState logs;
|
||||
UndoStack undo;
|
||||
};
|
||||
|
||||
// app.cc public API
|
||||
|
||||
const WorkspaceTab *app_active_tab(const SketchLayout &layout, const UiState &state);
|
||||
WorkspaceTab *app_active_tab(SketchLayout *layout, const UiState &state);
|
||||
TabUiState *app_active_tab_state(UiState *state);
|
||||
|
||||
void app_push_mono_font();
|
||||
void app_pop_mono_font();
|
||||
bool app_add_curve_to_active_pane(AppSession *session, UiState *state, const std::string &path);
|
||||
|
||||
std::string app_curve_display_name(const Curve &curve);
|
||||
std::array<uint8_t, 3> app_next_curve_color(const Pane &pane);
|
||||
const RouteSeries *app_find_route_series(const AppSession &session, const std::string &path);
|
||||
void app_decimate_samples(const std::vector<double> &xs_in,
|
||||
const std::vector<double> &ys_in,
|
||||
int max_points,
|
||||
std::vector<double> *xs_out,
|
||||
std::vector<double> *ys_out);
|
||||
std::optional<double> app_sample_xy_value_at_time(const std::vector<double> &xs,
|
||||
const std::vector<double> &ys,
|
||||
bool stairs,
|
||||
double tm);
|
||||
void save_layout_json(const SketchLayout &layout, const std::filesystem::path &path);
|
||||
|
||||
// *****
|
||||
// browser
|
||||
// *****
|
||||
|
||||
void rebuild_route_index(AppSession *session);
|
||||
void rebuild_browser_nodes(AppSession *session, UiState *state);
|
||||
SeriesFormat compute_series_format(const std::vector<double> &values, bool enum_like = false);
|
||||
std::string format_display_value(double display_value,
|
||||
const SeriesFormat &format,
|
||||
const EnumInfo *enum_info);
|
||||
std::vector<std::string> decode_browser_drag_payload(std::string_view payload);
|
||||
void collect_visible_leaf_paths(const BrowserNode &node,
|
||||
const std::string &filter,
|
||||
std::vector<std::string> *out);
|
||||
void draw_browser_node(AppSession *session,
|
||||
const BrowserNode &node,
|
||||
UiState *state,
|
||||
const std::string &filter,
|
||||
const std::vector<std::string> &visible_paths);
|
||||
|
||||
// *****
|
||||
// custom series
|
||||
// *****
|
||||
|
||||
void open_custom_series_editor(UiState *state, const std::string &preferred_source = {});
|
||||
std::string preferred_custom_series_source(const Pane &pane);
|
||||
void refresh_all_custom_curves(AppSession *session, UiState *state);
|
||||
void draw_custom_series_editor(AppSession *session, UiState *state);
|
||||
|
||||
// *****
|
||||
// logs
|
||||
// *****
|
||||
|
||||
void draw_logs_tab(AppSession *session, UiState *state);
|
||||
|
||||
// *****
|
||||
// map
|
||||
// *****
|
||||
|
||||
void draw_map_pane(AppSession *session, UiState *state, Pane *pane, int pane_index);
|
||||
|
||||
// *****
|
||||
// runtime (GLFW, async loaders, streaming, camera)
|
||||
// *****
|
||||
|
||||
struct GLFWwindow;
|
||||
|
||||
struct RouteLoadSnapshot {
|
||||
bool active = false;
|
||||
size_t total_segments = 0;
|
||||
size_t segments_downloaded = 0;
|
||||
size_t segments_parsed = 0;
|
||||
};
|
||||
|
||||
struct StreamPollSnapshot {
|
||||
bool active = false;
|
||||
bool connected = false;
|
||||
bool paused = false;
|
||||
StreamSourceKind source_kind = StreamSourceKind::CerealLocal;
|
||||
std::string source_label;
|
||||
std::string dbc_name;
|
||||
std::string car_fingerprint;
|
||||
double buffer_seconds = 30.0;
|
||||
uint64_t received_messages = 0;
|
||||
};
|
||||
|
||||
class GlfwRuntime {
|
||||
public:
|
||||
explicit GlfwRuntime(const Options &options);
|
||||
~GlfwRuntime();
|
||||
|
||||
GlfwRuntime(const GlfwRuntime &) = delete;
|
||||
GlfwRuntime &operator=(const GlfwRuntime &) = delete;
|
||||
|
||||
GLFWwindow *window() const;
|
||||
|
||||
private:
|
||||
GLFWwindow *window_ = nullptr;
|
||||
};
|
||||
|
||||
class ImGuiRuntime {
|
||||
public:
|
||||
explicit ImGuiRuntime(GLFWwindow *window);
|
||||
~ImGuiRuntime();
|
||||
|
||||
ImGuiRuntime(const ImGuiRuntime &) = delete;
|
||||
ImGuiRuntime &operator=(const ImGuiRuntime &) = delete;
|
||||
};
|
||||
|
||||
class TerminalRouteProgress {
|
||||
public:
|
||||
explicit TerminalRouteProgress(bool enabled);
|
||||
~TerminalRouteProgress();
|
||||
|
||||
TerminalRouteProgress(const TerminalRouteProgress &) = delete;
|
||||
TerminalRouteProgress &operator=(const TerminalRouteProgress &) = delete;
|
||||
|
||||
void update(const RouteLoadProgress &progress);
|
||||
void finish();
|
||||
|
||||
private:
|
||||
struct Impl;
|
||||
std::unique_ptr<Impl> impl_;
|
||||
};
|
||||
|
||||
class AsyncRouteLoader {
|
||||
public:
|
||||
explicit AsyncRouteLoader(bool enable_terminal_progress);
|
||||
~AsyncRouteLoader();
|
||||
|
||||
AsyncRouteLoader(const AsyncRouteLoader &) = delete;
|
||||
AsyncRouteLoader &operator=(const AsyncRouteLoader &) = delete;
|
||||
|
||||
void start(const std::string &route_name, const std::string &data_dir, const std::string &dbc_name);
|
||||
RouteLoadSnapshot snapshot() const;
|
||||
bool consume(RouteData *route_data, std::string *error_text);
|
||||
|
||||
private:
|
||||
struct Impl;
|
||||
std::unique_ptr<Impl> impl_;
|
||||
};
|
||||
|
||||
class StreamPoller {
|
||||
public:
|
||||
StreamPoller();
|
||||
~StreamPoller();
|
||||
|
||||
StreamPoller(const StreamPoller &) = delete;
|
||||
StreamPoller &operator=(const StreamPoller &) = delete;
|
||||
|
||||
void start(const StreamSourceConfig &source,
|
||||
double buffer_seconds,
|
||||
const std::string &dbc_name,
|
||||
std::optional<double> time_offset = std::nullopt);
|
||||
void setPaused(bool paused);
|
||||
void stop();
|
||||
StreamPollSnapshot snapshot() const;
|
||||
bool consume(StreamExtractBatch *batch, std::string *error_text);
|
||||
|
||||
private:
|
||||
struct Impl;
|
||||
std::unique_ptr<Impl> impl_;
|
||||
};
|
||||
|
||||
class CameraFeedView {
|
||||
public:
|
||||
CameraFeedView();
|
||||
~CameraFeedView();
|
||||
|
||||
CameraFeedView(const CameraFeedView &) = delete;
|
||||
CameraFeedView &operator=(const CameraFeedView &) = delete;
|
||||
|
||||
void setRouteData(const RouteData &route_data);
|
||||
void setCameraIndex(const CameraFeedIndex &camera_index, CameraViewKind view);
|
||||
void update(double tracker_time);
|
||||
void draw(float width, bool loading);
|
||||
void drawSized(ImVec2 size, bool loading, bool fit_to_pane = false);
|
||||
|
||||
private:
|
||||
struct Impl;
|
||||
std::unique_ptr<Impl> impl_;
|
||||
};
|
||||
465
tools/jotpluggler/browser.cc
Normal file
465
tools/jotpluggler/browser.cc
Normal file
@@ -0,0 +1,465 @@
|
||||
#include "tools/jotpluggler/app.h"
|
||||
|
||||
#include "imgui_internal.h"
|
||||
|
||||
#include <cmath>
|
||||
#include <cstdio>
|
||||
#include <unordered_set>
|
||||
|
||||
namespace {
|
||||
|
||||
constexpr float BROWSER_VALUE_WIDTH = 88.0f;
|
||||
|
||||
bool path_matches_filter(const std::string &path, const std::string &lower_filter) {
|
||||
if (lower_filter.empty()) return true;
|
||||
return lowercase_copy(path).find(lower_filter) != std::string::npos;
|
||||
}
|
||||
|
||||
void insert_browser_path(std::vector<BrowserNode> *nodes, const std::string &path) {
|
||||
size_t start = 0;
|
||||
while (start < path.size() && path[start] == '/') {
|
||||
++start;
|
||||
}
|
||||
std::vector<std::string> parts;
|
||||
while (start < path.size()) {
|
||||
const size_t end = path.find('/', start);
|
||||
parts.push_back(path.substr(start, end == std::string::npos ? std::string::npos : end - start));
|
||||
if (end == std::string::npos) break;
|
||||
start = end + 1;
|
||||
}
|
||||
if (parts.empty()) {
|
||||
return;
|
||||
}
|
||||
|
||||
std::vector<BrowserNode> *current_nodes = nodes;
|
||||
std::string current_path;
|
||||
for (size_t i = 0; i < parts.size(); ++i) {
|
||||
if (!current_path.empty()) {
|
||||
current_path += "/";
|
||||
}
|
||||
current_path += parts[i];
|
||||
auto it = std::find_if(current_nodes->begin(), current_nodes->end(),
|
||||
[&](const BrowserNode &node) { return node.label == parts[i]; });
|
||||
if (it == current_nodes->end()) {
|
||||
current_nodes->push_back(BrowserNode{.label = parts[i]});
|
||||
it = std::prev(current_nodes->end());
|
||||
}
|
||||
if (i + 1 == parts.size()) {
|
||||
it->full_path = "/" + current_path;
|
||||
}
|
||||
current_nodes = &it->children;
|
||||
}
|
||||
}
|
||||
|
||||
void sort_browser_nodes(std::vector<BrowserNode> *nodes) {
|
||||
std::sort(nodes->begin(), nodes->end(), [](const BrowserNode &a, const BrowserNode &b) {
|
||||
if (a.children.empty() != b.children.empty()) {
|
||||
return !a.children.empty();
|
||||
}
|
||||
return a.label < b.label;
|
||||
});
|
||||
for (BrowserNode &node : *nodes) {
|
||||
sort_browser_nodes(&node.children);
|
||||
}
|
||||
}
|
||||
|
||||
std::vector<BrowserNode> build_browser_tree(const std::vector<std::string> &paths) {
|
||||
std::vector<BrowserNode> nodes;
|
||||
for (const std::string &path : paths) {
|
||||
insert_browser_path(&nodes, path);
|
||||
}
|
||||
sort_browser_nodes(&nodes);
|
||||
return nodes;
|
||||
}
|
||||
|
||||
bool is_deprecated_browser_path(const std::string &path) {
|
||||
return path.find("DEPRECATED") != std::string::npos;
|
||||
}
|
||||
|
||||
std::vector<std::string> visible_browser_paths(const RouteData &route_data, bool show_deprecated_fields) {
|
||||
if (show_deprecated_fields) return route_data.paths;
|
||||
std::vector<std::string> filtered;
|
||||
filtered.reserve(route_data.paths.size());
|
||||
for (const std::string &path : route_data.paths) {
|
||||
if (!is_deprecated_browser_path(path)) {
|
||||
filtered.push_back(path);
|
||||
}
|
||||
}
|
||||
return filtered;
|
||||
}
|
||||
|
||||
bool browser_selection_contains(const UiState &state, std::string_view path) {
|
||||
return std::find(state.selected_browser_paths.begin(), state.selected_browser_paths.end(), path)
|
||||
!= state.selected_browser_paths.end();
|
||||
}
|
||||
|
||||
std::vector<std::string> browser_drag_paths(const UiState &state, const std::string &dragged_path) {
|
||||
if (browser_selection_contains(state, dragged_path) && !state.selected_browser_paths.empty()) {
|
||||
return state.selected_browser_paths;
|
||||
}
|
||||
return {dragged_path};
|
||||
}
|
||||
|
||||
std::string encode_browser_drag_payload(const std::vector<std::string> &paths) {
|
||||
std::string payload;
|
||||
for (size_t i = 0; i < paths.size(); ++i) {
|
||||
if (i != 0) {
|
||||
payload.push_back('\n');
|
||||
}
|
||||
payload += paths[i];
|
||||
}
|
||||
return payload;
|
||||
}
|
||||
|
||||
void set_browser_selection_single(UiState *state, const std::string &path) {
|
||||
state->selected_browser_paths = {path};
|
||||
state->selected_browser_path = path;
|
||||
state->browser_selection_anchor = path;
|
||||
}
|
||||
|
||||
void toggle_browser_selection(UiState *state, const std::string &path) {
|
||||
auto it = std::find(state->selected_browser_paths.begin(), state->selected_browser_paths.end(), path);
|
||||
if (it == state->selected_browser_paths.end()) {
|
||||
state->selected_browser_paths.push_back(path);
|
||||
} else {
|
||||
state->selected_browser_paths.erase(it);
|
||||
}
|
||||
state->selected_browser_path = path;
|
||||
state->browser_selection_anchor = path;
|
||||
if (state->selected_browser_paths.empty()) {
|
||||
state->selected_browser_path.clear();
|
||||
}
|
||||
}
|
||||
|
||||
void select_browser_range(UiState *state, const std::vector<std::string> &visible_paths, const std::string &clicked_path) {
|
||||
if (visible_paths.empty()) {
|
||||
set_browser_selection_single(state, clicked_path);
|
||||
return;
|
||||
}
|
||||
|
||||
const std::string anchor = state->browser_selection_anchor.empty() ? clicked_path : state->browser_selection_anchor;
|
||||
const auto anchor_it = std::find(visible_paths.begin(), visible_paths.end(), anchor);
|
||||
const auto clicked_it = std::find(visible_paths.begin(), visible_paths.end(), clicked_path);
|
||||
if (clicked_it == visible_paths.end()) {
|
||||
return;
|
||||
}
|
||||
if (anchor_it == visible_paths.end()) {
|
||||
set_browser_selection_single(state, clicked_path);
|
||||
return;
|
||||
}
|
||||
|
||||
const auto [begin_it, end_it] = std::minmax(anchor_it, clicked_it);
|
||||
std::vector<std::string> selected;
|
||||
selected.reserve(static_cast<size_t>(std::distance(begin_it, end_it)) + 1);
|
||||
for (auto it = begin_it; it != end_it + 1; ++it) {
|
||||
selected.push_back(*it);
|
||||
}
|
||||
state->selected_browser_paths = std::move(selected);
|
||||
state->selected_browser_path = clicked_path;
|
||||
}
|
||||
|
||||
void prune_browser_selection(UiState *state, const std::vector<std::string> &visible_paths) {
|
||||
const std::unordered_set<std::string> visible_set(visible_paths.begin(), visible_paths.end());
|
||||
auto is_visible = [&](const std::string &path) {
|
||||
return visible_set.count(path) > 0;
|
||||
};
|
||||
|
||||
state->selected_browser_paths.erase(
|
||||
std::remove_if(state->selected_browser_paths.begin(), state->selected_browser_paths.end(),
|
||||
[&](const std::string &path) { return !is_visible(path); }),
|
||||
state->selected_browser_paths.end());
|
||||
|
||||
if (!state->selected_browser_path.empty() && !is_visible(state->selected_browser_path)) {
|
||||
state->selected_browser_path.clear();
|
||||
}
|
||||
if (!state->browser_selection_anchor.empty() && !is_visible(state->browser_selection_anchor)) {
|
||||
state->browser_selection_anchor.clear();
|
||||
}
|
||||
if (state->selected_browser_paths.empty()) {
|
||||
state->selected_browser_path.clear();
|
||||
} else if (state->selected_browser_path.empty()) {
|
||||
state->selected_browser_path = state->selected_browser_paths.back();
|
||||
}
|
||||
}
|
||||
|
||||
std::optional<double> sample_route_series_value(const RouteSeries &series, double tm, bool stairs) {
|
||||
return app_sample_xy_value_at_time(series.times, series.values, stairs, tm);
|
||||
}
|
||||
|
||||
std::string browser_series_value_text(const AppSession &session, const UiState &state, std::string_view path) {
|
||||
auto it = session.series_by_path.find(std::string(path));
|
||||
if (it == session.series_by_path.end() || it->second == nullptr) return {};
|
||||
|
||||
const RouteSeries &series = *it->second;
|
||||
if (series.values.empty()) return {};
|
||||
|
||||
const auto enum_it = session.route_data.enum_info.find(series.path);
|
||||
const EnumInfo *enum_info = enum_it == session.route_data.enum_info.end() ? nullptr : &enum_it->second;
|
||||
const bool stairs = enum_info != nullptr;
|
||||
|
||||
std::optional<double> value;
|
||||
if (state.has_tracker_time) {
|
||||
value = sample_route_series_value(series, state.tracker_time, stairs);
|
||||
} else {
|
||||
value = series.values.back();
|
||||
}
|
||||
if (!value.has_value()) return {};
|
||||
|
||||
const auto display_it = session.route_data.series_formats.find(series.path);
|
||||
const SeriesFormat display_info = display_it == session.route_data.series_formats.end()
|
||||
? compute_series_format(series.values, enum_info != nullptr)
|
||||
: display_it->second;
|
||||
|
||||
return format_display_value(*value, display_info, enum_info);
|
||||
}
|
||||
|
||||
bool browser_node_matches(const BrowserNode &node, const std::string &filter) {
|
||||
if (filter.empty()) return true;
|
||||
if (!node.full_path.empty() && path_matches_filter(node.full_path, filter)) {
|
||||
return true;
|
||||
}
|
||||
for (const BrowserNode &child : node.children) {
|
||||
if (browser_node_matches(child, filter)) return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
namespace {
|
||||
|
||||
int decimals_needed(double value) {
|
||||
const double abs_value = std::abs(value);
|
||||
if (abs_value < 1.0e-12) return 0;
|
||||
for (int decimals = 0; decimals <= 6; ++decimals) {
|
||||
const double scale = std::pow(10.0, decimals);
|
||||
if (std::abs(abs_value * scale - std::round(abs_value * scale)) < 1.0e-6) {
|
||||
return decimals;
|
||||
}
|
||||
}
|
||||
return 6;
|
||||
}
|
||||
|
||||
void finalize_series_format(SeriesFormat *format) {
|
||||
format->digits_before = std::max(format->digits_before, 1);
|
||||
format->decimals = std::clamp(format->decimals, 0, 6);
|
||||
format->integer_like = format->decimals == 0;
|
||||
const int sign_width = format->has_negative ? 1 : 0;
|
||||
const int dot_width = format->decimals > 0 ? 1 : 0;
|
||||
format->total_width = sign_width + format->digits_before + dot_width + format->decimals;
|
||||
std::snprintf(format->fmt, sizeof(format->fmt), "%%%d.%df", format->total_width, format->decimals);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
SeriesFormat compute_series_format(const std::vector<double> &values, bool enum_like) {
|
||||
SeriesFormat format;
|
||||
if (values.empty()) return format;
|
||||
|
||||
const size_t step = std::max<size_t>(1, values.size() / 256);
|
||||
bool saw_finite = false;
|
||||
bool all_integer = enum_like;
|
||||
double min_value = 0.0;
|
||||
double max_value = 0.0;
|
||||
int max_needed_decimals = 0;
|
||||
|
||||
for (size_t i = 0; i < values.size(); i += step) {
|
||||
const double value = values[i];
|
||||
if (!std::isfinite(value)) continue;
|
||||
if (!saw_finite) {
|
||||
min_value = value;
|
||||
max_value = value;
|
||||
saw_finite = true;
|
||||
} else {
|
||||
min_value = std::min(min_value, value);
|
||||
max_value = std::max(max_value, value);
|
||||
}
|
||||
if (std::abs(value - std::round(value)) > 1.0e-9) {
|
||||
all_integer = false;
|
||||
}
|
||||
if (!all_integer) {
|
||||
max_needed_decimals = std::max(max_needed_decimals, decimals_needed(value));
|
||||
}
|
||||
}
|
||||
|
||||
if (!saw_finite) return format;
|
||||
|
||||
format.has_negative = min_value < 0.0;
|
||||
const double peak = std::max(std::abs(min_value), std::abs(max_value));
|
||||
format.digits_before = peak < 1.0 ? 1 : static_cast<int>(std::floor(std::log10(peak))) + 1;
|
||||
|
||||
if (enum_like || all_integer) {
|
||||
format.decimals = 0;
|
||||
} else if (peak >= 1000.0) {
|
||||
format.decimals = std::min(max_needed_decimals, 1);
|
||||
} else if (peak >= 100.0) {
|
||||
format.decimals = std::min(max_needed_decimals, 2);
|
||||
} else {
|
||||
format.decimals = std::min(max_needed_decimals, 4);
|
||||
}
|
||||
|
||||
finalize_series_format(&format);
|
||||
return format;
|
||||
}
|
||||
|
||||
std::string format_display_value(double display_value,
|
||||
const SeriesFormat &display_info,
|
||||
const EnumInfo *enum_info) {
|
||||
if (!std::isfinite(display_value)) return "---";
|
||||
if (enum_info != nullptr) {
|
||||
const int idx = static_cast<int>(std::llround(display_value));
|
||||
if (idx >= 0 && std::abs(display_value - static_cast<double>(idx)) < 0.01
|
||||
&& static_cast<size_t>(idx) < enum_info->names.size()
|
||||
&& !enum_info->names[static_cast<size_t>(idx)].empty()) {
|
||||
return enum_info->names[static_cast<size_t>(idx)];
|
||||
}
|
||||
}
|
||||
char buf[64] = {};
|
||||
std::snprintf(buf, sizeof(buf), display_info.fmt, display_value);
|
||||
return buf;
|
||||
}
|
||||
|
||||
std::vector<std::string> decode_browser_drag_payload(std::string_view payload) {
|
||||
std::vector<std::string> out;
|
||||
size_t begin = 0;
|
||||
while (begin <= payload.size()) {
|
||||
const size_t end = payload.find('\n', begin);
|
||||
const size_t length = (end == std::string_view::npos ? payload.size() : end) - begin;
|
||||
if (length > 0) {
|
||||
out.emplace_back(payload.substr(begin, length));
|
||||
}
|
||||
if (end == std::string_view::npos) break;
|
||||
begin = end + 1;
|
||||
}
|
||||
return out;
|
||||
}
|
||||
|
||||
void collect_visible_leaf_paths(const BrowserNode &node,
|
||||
const std::string &filter,
|
||||
std::vector<std::string> *out) {
|
||||
if (!browser_node_matches(node, filter)) {
|
||||
return;
|
||||
}
|
||||
if (node.children.empty()) {
|
||||
if (!node.full_path.empty()) {
|
||||
out->push_back(node.full_path);
|
||||
}
|
||||
return;
|
||||
}
|
||||
for (const BrowserNode &child : node.children) {
|
||||
collect_visible_leaf_paths(child, filter, out);
|
||||
}
|
||||
}
|
||||
|
||||
void rebuild_browser_nodes(AppSession *session, UiState *state) {
|
||||
const std::vector<std::string> paths = visible_browser_paths(session->route_data, state->show_deprecated_fields);
|
||||
session->browser_nodes = build_browser_tree(paths);
|
||||
prune_browser_selection(state, paths);
|
||||
}
|
||||
|
||||
void rebuild_route_index(AppSession *session) {
|
||||
session->series_by_path.clear();
|
||||
session->route_data.series_formats.clear();
|
||||
for (RouteSeries &series : session->route_data.series) {
|
||||
session->series_by_path.emplace(series.path, &series);
|
||||
const bool enum_like = session->route_data.enum_info.find(series.path) != session->route_data.enum_info.end();
|
||||
session->route_data.series_formats.emplace(series.path, compute_series_format(series.values, enum_like));
|
||||
}
|
||||
}
|
||||
|
||||
void draw_browser_node(AppSession *session,
|
||||
const BrowserNode &node,
|
||||
UiState *state,
|
||||
const std::string &filter,
|
||||
const std::vector<std::string> &visible_paths) {
|
||||
if (!browser_node_matches(node, filter)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (node.children.empty()) {
|
||||
const bool selected = browser_selection_contains(*state, node.full_path);
|
||||
const std::string value_text = browser_series_value_text(*session, *state, node.full_path);
|
||||
const ImGuiStyle &style = ImGui::GetStyle();
|
||||
const ImVec2 row_size(std::max(1.0f, ImGui::GetContentRegionAvail().x), ImGui::GetFrameHeight());
|
||||
ImGui::PushID(node.full_path.c_str());
|
||||
const bool clicked = ImGui::InvisibleButton("##browser_leaf", row_size);
|
||||
const bool hovered = ImGui::IsItemHovered();
|
||||
const bool held = ImGui::IsItemActive();
|
||||
const ImRect rect(ImGui::GetItemRectMin(), ImGui::GetItemRectMax());
|
||||
ImDrawList *draw_list = ImGui::GetWindowDrawList();
|
||||
if (selected || hovered) {
|
||||
const ImU32 bg = ImGui::GetColorU32(selected
|
||||
? (held ? ImGuiCol_HeaderActive : ImGuiCol_Header)
|
||||
: ImGuiCol_HeaderHovered);
|
||||
draw_list->AddRectFilled(rect.Min, rect.Max, bg, 0.0f);
|
||||
}
|
||||
|
||||
const float value_right = rect.Max.x - style.FramePadding.x;
|
||||
const float value_left = value_right - (value_text.empty() ? 0.0f : BROWSER_VALUE_WIDTH);
|
||||
const float label_left = rect.Min.x + style.FramePadding.x;
|
||||
const float label_right = value_text.empty()
|
||||
? rect.Max.x - style.FramePadding.x
|
||||
: std::max(label_left + 40.0f, value_left - 10.0f);
|
||||
ImGui::RenderTextEllipsis(draw_list,
|
||||
ImVec2(label_left, rect.Min.y + style.FramePadding.y),
|
||||
ImVec2(label_right, rect.Max.y),
|
||||
label_right,
|
||||
node.label.c_str(),
|
||||
nullptr,
|
||||
nullptr);
|
||||
if (!value_text.empty()) {
|
||||
app_push_mono_font();
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, selected ? color_rgb(70, 77, 86) : color_rgb(116, 124, 133));
|
||||
ImGui::RenderTextClipped(ImVec2(value_left, rect.Min.y + style.FramePadding.y),
|
||||
ImVec2(value_right, rect.Max.y),
|
||||
value_text.c_str(),
|
||||
nullptr,
|
||||
nullptr,
|
||||
ImVec2(1.0f, 0.0f));
|
||||
ImGui::PopStyleColor();
|
||||
app_pop_mono_font();
|
||||
}
|
||||
|
||||
if (clicked) {
|
||||
const bool shift_down = ImGui::GetIO().KeyShift;
|
||||
const bool ctrl_down = ImGui::GetIO().KeyCtrl || ImGui::GetIO().KeySuper;
|
||||
if (shift_down) {
|
||||
select_browser_range(state, visible_paths, node.full_path);
|
||||
} else if (ctrl_down) {
|
||||
toggle_browser_selection(state, node.full_path);
|
||||
} else {
|
||||
set_browser_selection_single(state, node.full_path);
|
||||
}
|
||||
}
|
||||
if (hovered && ImGui::IsMouseDoubleClicked(0)) {
|
||||
set_browser_selection_single(state, node.full_path);
|
||||
app_add_curve_to_active_pane(session, state, node.full_path);
|
||||
}
|
||||
if (ImGui::BeginDragDropSource(ImGuiDragDropFlags_SourceAllowNullID)) {
|
||||
const std::vector<std::string> drag_paths = browser_drag_paths(*state, node.full_path);
|
||||
const std::string payload = encode_browser_drag_payload(drag_paths);
|
||||
ImGui::SetDragDropPayload("JOTP_BROWSER_PATHS", payload.c_str(), payload.size() + 1);
|
||||
if (drag_paths.size() == 1) {
|
||||
ImGui::TextUnformatted(drag_paths.front().c_str());
|
||||
} else {
|
||||
ImGui::Text("%zu timeseries", drag_paths.size());
|
||||
ImGui::TextUnformatted(drag_paths.front().c_str());
|
||||
}
|
||||
ImGui::EndDragDropSource();
|
||||
}
|
||||
ImGui::PopID();
|
||||
return;
|
||||
}
|
||||
|
||||
ImGuiTreeNodeFlags flags = ImGuiTreeNodeFlags_SpanAvailWidth;
|
||||
if (!filter.empty()) {
|
||||
flags |= ImGuiTreeNodeFlags_DefaultOpen;
|
||||
}
|
||||
const bool open = ImGui::TreeNodeEx(node.label.c_str(), flags);
|
||||
if (open) {
|
||||
for (const BrowserNode &child : node.children) {
|
||||
draw_browser_node(session, child, state, filter, visible_paths);
|
||||
}
|
||||
ImGui::TreePop();
|
||||
}
|
||||
}
|
||||
54
tools/jotpluggler/camera.cc
Normal file
54
tools/jotpluggler/camera.cc
Normal file
@@ -0,0 +1,54 @@
|
||||
#include "tools/jotpluggler/camera.h"
|
||||
|
||||
#include "imgui.h"
|
||||
#include "imgui_internal.h"
|
||||
|
||||
namespace {
|
||||
|
||||
bool draw_camera_fit_toggle_overlay(bool fit_to_pane) {
|
||||
const ImVec2 window_pos = ImGui::GetWindowPos();
|
||||
const ImVec2 content_min = ImGui::GetWindowContentRegionMin();
|
||||
const ImRect rect(ImVec2(window_pos.x + content_min.x + 8.0f, window_pos.y + content_min.y + 8.0f),
|
||||
ImVec2(window_pos.x + content_min.x + 58.0f, window_pos.y + content_min.y + 28.0f));
|
||||
const bool hovered = ImGui::IsMouseHoveringRect(rect.Min, rect.Max, false);
|
||||
const bool held = hovered && ImGui::IsMouseDown(ImGuiMouseButton_Left);
|
||||
if (hovered) ImGui::SetMouseCursor(ImGuiMouseCursor_Hand);
|
||||
|
||||
ImDrawList *draw_list = ImGui::GetWindowDrawList();
|
||||
draw_list->AddRectFilled(rect.Min, rect.Max, hovered ? IM_COL32(255, 255, 255, 234) : IM_COL32(255, 255, 255, 214), 4.0f);
|
||||
draw_list->AddRect(rect.Min, rect.Max, IM_COL32(184, 189, 196, 255), 4.0f, 0, 1.0f);
|
||||
const ImRect box(ImVec2(rect.Min.x + 6.0f, rect.Min.y + 4.0f), ImVec2(rect.Min.x + 18.0f, rect.Min.y + 16.0f));
|
||||
draw_list->AddRect(box.Min, box.Max, IM_COL32(112, 120, 129, 255), 2.0f, 0, 1.0f);
|
||||
if (fit_to_pane) {
|
||||
draw_list->AddLine(ImVec2(box.Min.x + 2.5f, box.Min.y + 6.5f), ImVec2(box.Min.x + 5.5f, box.Max.y - 2.5f), IM_COL32(60, 111, 202, 255), 1.8f);
|
||||
draw_list->AddLine(ImVec2(box.Min.x + 5.5f, box.Max.y - 2.5f), ImVec2(box.Max.x - 2.5f, box.Min.y + 2.5f), IM_COL32(60, 111, 202, 255), 1.8f);
|
||||
}
|
||||
draw_list->AddText(ImVec2(box.Max.x + 6.0f, rect.Min.y + 3.0f), IM_COL32(72, 79, 88, 255), "Fit");
|
||||
return hovered && !held && ImGui::IsMouseReleased(ImGuiMouseButton_Left);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
void draw_camera_pane(AppSession *session, UiState *state, TabUiState *tab_state, int pane_index, const Pane &pane) {
|
||||
CameraFeedView *feed = session->pane_camera_feeds[static_cast<size_t>(pane.camera_view)].get();
|
||||
if (feed == nullptr) {
|
||||
ImGui::TextDisabled("Camera unavailable");
|
||||
return;
|
||||
}
|
||||
|
||||
const bool fit_to_pane = tab_state != nullptr
|
||||
&& pane_index >= 0
|
||||
&& pane_index < static_cast<int>(tab_state->camera_panes.size())
|
||||
? tab_state->camera_panes[static_cast<size_t>(pane_index)].fit_to_pane
|
||||
: true;
|
||||
if (state->has_tracker_time) {
|
||||
feed->update(state->tracker_time);
|
||||
}
|
||||
feed->drawSized(ImGui::GetContentRegionAvail(), session->async_route_loading, fit_to_pane);
|
||||
if (tab_state != nullptr
|
||||
&& pane_index >= 0
|
||||
&& pane_index < static_cast<int>(tab_state->camera_panes.size())
|
||||
&& draw_camera_fit_toggle_overlay(fit_to_pane)) {
|
||||
tab_state->camera_panes[static_cast<size_t>(pane_index)].fit_to_pane = !fit_to_pane;
|
||||
}
|
||||
}
|
||||
5
tools/jotpluggler/camera.h
Normal file
5
tools/jotpluggler/camera.h
Normal file
@@ -0,0 +1,5 @@
|
||||
#pragma once
|
||||
|
||||
#include "tools/jotpluggler/app.h"
|
||||
|
||||
void draw_camera_pane(AppSession *session, UiState *state, TabUiState *tab_state, int pane_index, const Pane &pane);
|
||||
179
tools/jotpluggler/common.cc
Normal file
179
tools/jotpluggler/common.cc
Normal file
@@ -0,0 +1,179 @@
|
||||
#include "tools/jotpluggler/common.h"
|
||||
|
||||
#include <algorithm>
|
||||
#include <array>
|
||||
#include <cstdlib>
|
||||
|
||||
namespace {
|
||||
|
||||
std::string format_coord(const GpsPoint &point) {
|
||||
return util::string_format("%.5f,%.5f", point.lat, point.lon);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
const CameraViewSpec &camera_view_spec(CameraViewKind view) {
|
||||
auto it = std::find_if(kCameraViewSpecs.begin(), kCameraViewSpecs.end(), [&](const CameraViewSpec &spec) {
|
||||
return spec.view == view;
|
||||
});
|
||||
return it != kCameraViewSpecs.end() ? *it : kCameraViewSpecs.front();
|
||||
}
|
||||
|
||||
const CameraViewSpec *camera_view_spec_from_special_item(std::string_view item_id) {
|
||||
auto it = std::find_if(kCameraViewSpecs.begin(), kCameraViewSpecs.end(), [&](const CameraViewSpec &spec) {
|
||||
return item_id == spec.special_item_id;
|
||||
});
|
||||
return it != kCameraViewSpecs.end() ? &*it : nullptr;
|
||||
}
|
||||
|
||||
const CameraViewSpec *camera_view_spec_from_layout_name(std::string_view layout_name) {
|
||||
auto it = std::find_if(kCameraViewSpecs.begin(), kCameraViewSpecs.end(), [&](const CameraViewSpec &spec) {
|
||||
return layout_name == spec.layout_name;
|
||||
});
|
||||
return it != kCameraViewSpecs.end() ? &*it : nullptr;
|
||||
}
|
||||
|
||||
const SpecialItemSpec *special_item_spec(std::string_view item_id) {
|
||||
auto it = std::find_if(kSpecialItemSpecs.begin(), kSpecialItemSpecs.end(), [&](const SpecialItemSpec &spec) {
|
||||
return item_id == spec.id;
|
||||
});
|
||||
return it != kSpecialItemSpecs.end() ? &*it : nullptr;
|
||||
}
|
||||
|
||||
const char *special_item_label(std::string_view item_id) {
|
||||
const SpecialItemSpec *spec = special_item_spec(item_id);
|
||||
return spec != nullptr ? spec->label : "Item";
|
||||
}
|
||||
|
||||
bool pane_kind_is_special(PaneKind kind) {
|
||||
return kind == PaneKind::Map || kind == PaneKind::Camera;
|
||||
}
|
||||
|
||||
bool is_default_special_title(std::string_view title) {
|
||||
if (title == "Map") return true;
|
||||
return std::any_of(kCameraViewSpecs.begin(), kCameraViewSpecs.end(), [&](const CameraViewSpec &spec) {
|
||||
return title == spec.label;
|
||||
});
|
||||
}
|
||||
|
||||
CameraViewKind sidebar_preview_camera_view(const AppSession &session) {
|
||||
return session.route_data.road_camera.entries.empty() && !session.route_data.qroad_camera.entries.empty()
|
||||
? CameraViewKind::QRoad
|
||||
: CameraViewKind::Road;
|
||||
}
|
||||
|
||||
const std::filesystem::path &repo_root() {
|
||||
static const std::filesystem::path root(JOTP_REPO_ROOT);
|
||||
return root;
|
||||
}
|
||||
|
||||
ImU32 timeline_entry_color(TimelineEntry::Type type, float alpha) {
|
||||
return timeline_entry_color(type, alpha, {111, 143, 175});
|
||||
}
|
||||
|
||||
ImU32 timeline_entry_color(TimelineEntry::Type type, float alpha, std::array<uint8_t, 3> none_color) {
|
||||
switch (type) {
|
||||
case TimelineEntry::Type::Engaged:
|
||||
return ImGui::GetColorU32(color_rgb(0, 163, 108, alpha));
|
||||
case TimelineEntry::Type::AlertInfo:
|
||||
return ImGui::GetColorU32(color_rgb(255, 195, 0, alpha));
|
||||
case TimelineEntry::Type::AlertWarning:
|
||||
case TimelineEntry::Type::AlertCritical:
|
||||
return ImGui::GetColorU32(color_rgb(199, 0, 57, alpha));
|
||||
case TimelineEntry::Type::None:
|
||||
default:
|
||||
return ImGui::GetColorU32(color_rgb(none_color, alpha));
|
||||
}
|
||||
}
|
||||
|
||||
const char *timeline_entry_label(TimelineEntry::Type type) {
|
||||
static constexpr const char *kLabels[] = {
|
||||
"disengaged",
|
||||
"engaged",
|
||||
"alert info",
|
||||
"alert warning",
|
||||
"alert critical",
|
||||
};
|
||||
const size_t index = static_cast<size_t>(type);
|
||||
return index < std::size(kLabels) ? kLabels[index] : kLabels[0];
|
||||
}
|
||||
|
||||
TimelineEntry::Type timeline_type_at_time(const std::vector<TimelineEntry> &timeline, double time_value) {
|
||||
for (const TimelineEntry &entry : timeline) {
|
||||
if (time_value >= entry.start_time && time_value <= entry.end_time) {
|
||||
return entry.type;
|
||||
}
|
||||
}
|
||||
return TimelineEntry::Type::None;
|
||||
}
|
||||
|
||||
std::string normalize_stream_address(std::string address) {
|
||||
return is_local_stream_address(address) ? "127.0.0.1" : address;
|
||||
}
|
||||
|
||||
const char *stream_source_kind_label(StreamSourceKind kind) {
|
||||
static constexpr const char *kLabels[] = {
|
||||
"Local (MSGQ)",
|
||||
"Remote (ZMQ)",
|
||||
};
|
||||
const size_t index = static_cast<size_t>(kind);
|
||||
return index < std::size(kLabels) ? kLabels[index] : kLabels[0];
|
||||
}
|
||||
|
||||
std::string stream_source_target_label(const StreamSourceConfig &source) {
|
||||
switch (source.kind) {
|
||||
case StreamSourceKind::CerealRemote:
|
||||
return normalize_stream_address(source.address);
|
||||
case StreamSourceKind::CerealLocal:
|
||||
default:
|
||||
return "127.0.0.1";
|
||||
}
|
||||
}
|
||||
|
||||
bool env_flag_enabled(const char *name, bool default_value) {
|
||||
const char *raw = std::getenv(name);
|
||||
if (raw == nullptr || raw[0] == '\0') {
|
||||
return default_value;
|
||||
}
|
||||
const std::string value = lowercase_copy(util::strip(raw));
|
||||
return !(value == "0" || value == "false" || value == "no" || value == "off");
|
||||
}
|
||||
|
||||
void open_external_url(std::string_view url) {
|
||||
#ifdef __APPLE__
|
||||
const std::string command = "open " + shell_quote(url) + " &";
|
||||
#else
|
||||
const std::string command = "xdg-open " + shell_quote(url) + " >/dev/null 2>&1 &";
|
||||
#endif
|
||||
util::check_system(command);
|
||||
}
|
||||
|
||||
std::string route_useradmin_url(const RouteIdentifier &route_id) {
|
||||
return route_id.empty() ? std::string()
|
||||
: "https://useradmin.comma.ai/?onebox=" + route_id.dongle_id + "%7C" + route_id.log_id;
|
||||
}
|
||||
|
||||
std::string route_connect_url(const RouteIdentifier &route_id) {
|
||||
return route_id.empty() ? std::string()
|
||||
: "https://connect.comma.ai/" + route_id.canonical();
|
||||
}
|
||||
|
||||
std::string route_google_maps_url(const GpsTrace &trace) {
|
||||
if (trace.points.size() < 2) {
|
||||
return {};
|
||||
}
|
||||
|
||||
const std::string prefix = "https://www.google.com/maps/dir/?api=1&travelmode=driving&origin="
|
||||
+ format_coord(trace.points.front()) + "&destination=" + format_coord(trace.points.back());
|
||||
for (size_t n = std::min<size_t>(9, trace.points.size() > 2 ? trace.points.size() - 2 : 0); ; --n) {
|
||||
std::string url = prefix;
|
||||
if (n > 0) {
|
||||
url += "&waypoints=";
|
||||
for (size_t i = 0; i < n; ++i) {
|
||||
if (i) url += "%7C";
|
||||
url += format_coord(trace.points[1 + ((trace.points.size() - 2) * (i + 1)) / (n + 1)]);
|
||||
}
|
||||
}
|
||||
if (url.size() <= 1900 || n == 0) return url;
|
||||
}
|
||||
}
|
||||
63
tools/jotpluggler/common.h
Normal file
63
tools/jotpluggler/common.h
Normal file
@@ -0,0 +1,63 @@
|
||||
#pragma once
|
||||
|
||||
#include "tools/jotpluggler/app.h"
|
||||
|
||||
#include <array>
|
||||
#include <string_view>
|
||||
|
||||
struct CameraViewSpec {
|
||||
CameraViewKind view = CameraViewKind::Road;
|
||||
const char *label = "";
|
||||
const char *runtime_name = "";
|
||||
const char *layout_name = "";
|
||||
const char *special_item_id = "";
|
||||
CameraFeedIndex RouteData::*route_member = nullptr;
|
||||
};
|
||||
|
||||
struct SpecialItemSpec {
|
||||
const char *id = "";
|
||||
const char *label = "";
|
||||
PaneKind kind = PaneKind::Plot;
|
||||
CameraViewKind camera_view = CameraViewKind::Road;
|
||||
};
|
||||
|
||||
inline constexpr std::array<CameraViewSpec, 4> kCameraViewSpecs = {{
|
||||
{CameraViewKind::Road, "Road Camera", "road", "road", "camera_road", &RouteData::road_camera},
|
||||
{CameraViewKind::Driver, "Driver Camera", "driver", "driver", "camera_driver", &RouteData::driver_camera},
|
||||
{CameraViewKind::WideRoad, "Wide Road Camera", "wide", "wide_road", "camera_wide_road", &RouteData::wide_road_camera},
|
||||
{CameraViewKind::QRoad, "qRoad Camera", "qroad", "qroad", "camera_qroad", &RouteData::qroad_camera},
|
||||
}};
|
||||
|
||||
inline constexpr std::array<SpecialItemSpec, 5> kSpecialItemSpecs = {{
|
||||
{"map", "Map", PaneKind::Map, CameraViewKind::Road},
|
||||
{kCameraViewSpecs[0].special_item_id, kCameraViewSpecs[0].label, PaneKind::Camera, kCameraViewSpecs[0].view},
|
||||
{kCameraViewSpecs[1].special_item_id, kCameraViewSpecs[1].label, PaneKind::Camera, kCameraViewSpecs[1].view},
|
||||
{kCameraViewSpecs[2].special_item_id, kCameraViewSpecs[2].label, PaneKind::Camera, kCameraViewSpecs[2].view},
|
||||
{kCameraViewSpecs[3].special_item_id, kCameraViewSpecs[3].label, PaneKind::Camera, kCameraViewSpecs[3].view},
|
||||
}};
|
||||
|
||||
const CameraViewSpec &camera_view_spec(CameraViewKind view);
|
||||
const CameraViewSpec *camera_view_spec_from_special_item(std::string_view item_id);
|
||||
const CameraViewSpec *camera_view_spec_from_layout_name(std::string_view layout_name);
|
||||
|
||||
const SpecialItemSpec *special_item_spec(std::string_view item_id);
|
||||
const char *special_item_label(std::string_view item_id);
|
||||
|
||||
bool pane_kind_is_special(PaneKind kind);
|
||||
bool is_default_special_title(std::string_view title);
|
||||
CameraViewKind sidebar_preview_camera_view(const AppSession &session);
|
||||
const std::filesystem::path &repo_root();
|
||||
|
||||
ImU32 timeline_entry_color(TimelineEntry::Type type, float alpha = 1.0f);
|
||||
ImU32 timeline_entry_color(TimelineEntry::Type type, float alpha, std::array<uint8_t, 3> none_color);
|
||||
const char *timeline_entry_label(TimelineEntry::Type type);
|
||||
TimelineEntry::Type timeline_type_at_time(const std::vector<TimelineEntry> &timeline, double time_value);
|
||||
std::string normalize_stream_address(std::string address);
|
||||
const char *stream_source_kind_label(StreamSourceKind kind);
|
||||
std::string stream_source_target_label(const StreamSourceConfig &source);
|
||||
|
||||
bool env_flag_enabled(const char *name, bool default_value = false);
|
||||
void open_external_url(std::string_view url);
|
||||
std::string route_useradmin_url(const RouteIdentifier &route_id);
|
||||
std::string route_connect_url(const RouteIdentifier &route_id);
|
||||
std::string route_google_maps_url(const GpsTrace &trace);
|
||||
750
tools/jotpluggler/custom_series.cc
Normal file
750
tools/jotpluggler/custom_series.cc
Normal file
@@ -0,0 +1,750 @@
|
||||
#include "tools/jotpluggler/app.h"
|
||||
#include "tools/jotpluggler/common.h"
|
||||
|
||||
#include "implot.h"
|
||||
|
||||
#include <cfloat>
|
||||
#include <chrono>
|
||||
#include <cstring>
|
||||
#include <regex>
|
||||
#include <set>
|
||||
#include <stdexcept>
|
||||
#include <unistd.h>
|
||||
|
||||
#include "third_party/json11/json11.hpp"
|
||||
|
||||
namespace fs = std::filesystem;
|
||||
|
||||
namespace {
|
||||
|
||||
struct PythonEvalResult {
|
||||
std::vector<double> xs;
|
||||
std::vector<double> ys;
|
||||
};
|
||||
|
||||
struct CustomSeriesTemplate {
|
||||
const char *name;
|
||||
const char *globals_code;
|
||||
const char *function_code;
|
||||
const char *preview_text;
|
||||
int required_additional_sources;
|
||||
const char *requirement_text;
|
||||
};
|
||||
|
||||
void write_binary_vector(const fs::path &path, const std::vector<double> &values) {
|
||||
write_file_or_throw(path, values.data(), values.size() * sizeof(double));
|
||||
}
|
||||
|
||||
std::vector<double> read_binary_vector(const fs::path &path) {
|
||||
const std::string raw = read_file_or_throw(path);
|
||||
if (raw.size() % sizeof(double) != 0) {
|
||||
throw std::runtime_error("Invalid binary series file: " + path.string());
|
||||
}
|
||||
std::vector<double> values(raw.size() / sizeof(double));
|
||||
if (!values.empty()) {
|
||||
std::memcpy(values.data(), raw.data(), raw.size());
|
||||
}
|
||||
return values;
|
||||
}
|
||||
|
||||
void write_text_file(const fs::path &path, std::string_view text) {
|
||||
write_file_or_throw(path, text);
|
||||
}
|
||||
|
||||
fs::path create_custom_series_temp_dir() {
|
||||
const auto stamp = std::chrono::steady_clock::now().time_since_epoch().count();
|
||||
const fs::path dir = fs::temp_directory_path() / ("jotpluggler_math_" + std::to_string(::getpid()) + "_" + std::to_string(stamp));
|
||||
fs::create_directories(dir);
|
||||
return dir;
|
||||
}
|
||||
|
||||
void reset_custom_series_editor(CustomSeriesEditorState *editor) {
|
||||
*editor = CustomSeriesEditorState{};
|
||||
}
|
||||
|
||||
bool add_additional_source(CustomSeriesEditorState *editor, const std::string &path) {
|
||||
if (path.empty() || path == editor->linked_source) return false;
|
||||
if (std::find(editor->additional_sources.begin(), editor->additional_sources.end(), path) != editor->additional_sources.end()) {
|
||||
return false;
|
||||
}
|
||||
editor->additional_sources.push_back(path);
|
||||
return true;
|
||||
}
|
||||
|
||||
std::string next_custom_curve_name(const Pane &pane) {
|
||||
std::set<std::string> used;
|
||||
for (const Curve &curve : pane.curves) {
|
||||
if (!curve.label.empty()) {
|
||||
used.insert(curve.label);
|
||||
}
|
||||
if (!curve.name.empty()) {
|
||||
used.insert(curve.name);
|
||||
}
|
||||
}
|
||||
for (int i = 1; i < 1000; ++i) {
|
||||
const std::string candidate = "series" + std::to_string(i);
|
||||
if (used.find(candidate) == used.end()) {
|
||||
return candidate;
|
||||
}
|
||||
}
|
||||
return "series";
|
||||
}
|
||||
|
||||
Curve make_custom_curve(const Pane &pane,
|
||||
const std::string &name,
|
||||
const CustomPythonSeries &spec,
|
||||
PythonEvalResult result) {
|
||||
Curve curve;
|
||||
curve.name = name;
|
||||
curve.label = name;
|
||||
curve.color = app_next_curve_color(pane);
|
||||
curve.runtime_only = true;
|
||||
curve.custom_python = spec;
|
||||
curve.xs = std::move(result.xs);
|
||||
curve.ys = std::move(result.ys);
|
||||
return curve;
|
||||
}
|
||||
|
||||
bool upsert_custom_curve_in_pane(WorkspaceTab *tab, int pane_index, Curve curve) {
|
||||
if (pane_index < 0 || pane_index >= static_cast<int>(tab->panes.size())) {
|
||||
return false;
|
||||
}
|
||||
Pane &pane = tab->panes[static_cast<size_t>(pane_index)];
|
||||
for (Curve &existing : pane.curves) {
|
||||
if (existing.runtime_only && existing.name == curve.name) {
|
||||
existing.visible = true;
|
||||
existing.label = curve.label;
|
||||
existing.custom_python = curve.custom_python;
|
||||
existing.xs = std::move(curve.xs);
|
||||
existing.ys = std::move(curve.ys);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
pane.curves.push_back(std::move(curve));
|
||||
return true;
|
||||
}
|
||||
|
||||
std::set<std::string> collect_custom_series_paths(const CustomPythonSeries &spec,
|
||||
std::string_view globals_code,
|
||||
std::string_view function_code) {
|
||||
std::set<std::string> paths;
|
||||
if (!spec.linked_source.empty()) {
|
||||
paths.insert(spec.linked_source);
|
||||
}
|
||||
paths.insert(spec.additional_sources.begin(), spec.additional_sources.end());
|
||||
|
||||
static const std::regex kPathRegex(R"([tv]\(\s*["']([^"']+)["']\s*\))");
|
||||
const auto collect_from = [&](std::string_view code) {
|
||||
std::string owned(code);
|
||||
for (std::sregex_iterator it(owned.begin(), owned.end(), kPathRegex), end; it != end; ++it) {
|
||||
paths.insert((*it)[1].str());
|
||||
}
|
||||
};
|
||||
collect_from(globals_code);
|
||||
collect_from(function_code);
|
||||
return paths;
|
||||
}
|
||||
|
||||
PythonEvalResult evaluate_custom_python_series(const AppSession &session,
|
||||
const CustomPythonSeries &spec) {
|
||||
const std::set<std::string> referenced_paths =
|
||||
collect_custom_series_paths(spec, spec.globals_code, spec.function_code);
|
||||
if (referenced_paths.empty()) throw std::runtime_error("No input series referenced. Set an input timeseries or reference route paths in code.");
|
||||
|
||||
const fs::path temp_dir = create_custom_series_temp_dir();
|
||||
try {
|
||||
const fs::path globals_path = temp_dir / "globals.py";
|
||||
const fs::path code_path = temp_dir / "code.py";
|
||||
const fs::path manifest_path = temp_dir / "manifest.json";
|
||||
const fs::path out_t_path = temp_dir / "result.t.bin";
|
||||
const fs::path out_v_path = temp_dir / "result.v.bin";
|
||||
|
||||
write_text_file(globals_path, spec.globals_code);
|
||||
write_text_file(code_path, spec.function_code);
|
||||
|
||||
json11::Json::array paths_json(session.route_data.paths.begin(), session.route_data.paths.end());
|
||||
json11::Json::array additional_json(spec.additional_sources.begin(), spec.additional_sources.end());
|
||||
json11::Json::array series_json;
|
||||
size_t series_index = 0;
|
||||
for (const std::string &path : referenced_paths) {
|
||||
const RouteSeries *series = app_find_route_series(session, path);
|
||||
if (series == nullptr || series->times.size() < 2 || series->times.size() != series->values.size()) {
|
||||
throw std::runtime_error("Missing route series " + path);
|
||||
}
|
||||
const std::string prefix = "series_" + std::to_string(series_index++);
|
||||
const fs::path time_path = temp_dir / (prefix + ".t.bin");
|
||||
const fs::path value_path = temp_dir / (prefix + ".v.bin");
|
||||
write_binary_vector(time_path, series->times);
|
||||
write_binary_vector(value_path, series->values);
|
||||
series_json.push_back(json11::Json::object{
|
||||
{"path", path}, {"t", time_path.string()}, {"v", value_path.string()}});
|
||||
}
|
||||
const json11::Json manifest_json = json11::Json::object{
|
||||
{"paths", std::move(paths_json)},
|
||||
{"linked_source", spec.linked_source},
|
||||
{"additional_sources", std::move(additional_json)},
|
||||
{"series", std::move(series_json)},
|
||||
};
|
||||
write_text_file(manifest_path, manifest_json.dump());
|
||||
|
||||
const CommandResult process = run_process_capture_output({
|
||||
"python3",
|
||||
(repo_root() / "tools" / "jotpluggler" / "math_eval.py").string(),
|
||||
manifest_path.string(),
|
||||
globals_path.string(),
|
||||
code_path.string(),
|
||||
out_t_path.string(),
|
||||
out_v_path.string(),
|
||||
});
|
||||
if (process.exit_code != 0) {
|
||||
const std::string error_text = util::strip(process.output);
|
||||
throw std::runtime_error(error_text.empty() ? "Python evaluation failed" : error_text);
|
||||
}
|
||||
|
||||
PythonEvalResult result;
|
||||
result.xs = read_binary_vector(out_t_path);
|
||||
result.ys = read_binary_vector(out_v_path);
|
||||
if (result.xs.size() < 2 || result.xs.size() != result.ys.size()) {
|
||||
throw std::runtime_error("Custom series returned invalid output");
|
||||
}
|
||||
fs::remove_all(temp_dir);
|
||||
return result;
|
||||
} catch (...) {
|
||||
std::error_code ignore_error;
|
||||
fs::remove_all(temp_dir, ignore_error);
|
||||
throw;
|
||||
}
|
||||
}
|
||||
|
||||
void refresh_custom_curve_samples(AppSession *session, UiState *state, Curve *curve) {
|
||||
if (!curve->custom_python.has_value()) {
|
||||
return;
|
||||
}
|
||||
if (!session->route_data.has_time_range || session->route_data.series.empty()) {
|
||||
curve->runtime_error_message.clear();
|
||||
curve->xs.clear();
|
||||
curve->ys.clear();
|
||||
return;
|
||||
}
|
||||
try {
|
||||
PythonEvalResult result = evaluate_custom_python_series(*session, *curve->custom_python);
|
||||
curve->runtime_error_message.clear();
|
||||
curve->xs = std::move(result.xs);
|
||||
curve->ys = std::move(result.ys);
|
||||
} catch (const std::exception &err) {
|
||||
curve->xs.clear();
|
||||
curve->ys.clear();
|
||||
const std::string err_text = err.what();
|
||||
if (session->data_mode == SessionDataMode::Stream && util::starts_with(err_text, "Missing route series ")) {
|
||||
curve->runtime_error_message = err_text;
|
||||
return;
|
||||
}
|
||||
const std::string error_message = std::string("Failed to evaluate custom series \"")
|
||||
+ app_curve_display_name(*curve) + "\":\n\n" + err_text;
|
||||
if (curve->runtime_error_message != error_message) {
|
||||
curve->runtime_error_message = error_message;
|
||||
state->error_text = error_message;
|
||||
state->open_error_popup = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
const std::array<CustomSeriesTemplate, 4> &custom_series_templates() {
|
||||
static constexpr std::array<CustomSeriesTemplate, 4> kTemplates = {{
|
||||
{
|
||||
.name = "Derivative",
|
||||
.globals_code = "",
|
||||
.function_code = "return np.gradient(value, time)",
|
||||
.preview_text = "return np.gradient(value, time)",
|
||||
.required_additional_sources = 0,
|
||||
.requirement_text = "",
|
||||
},
|
||||
{
|
||||
.name = "Difference",
|
||||
.globals_code = "",
|
||||
.function_code = "return value - v1",
|
||||
.preview_text = "Requires one additional source timeseries.\n\nreturn value - v1",
|
||||
.required_additional_sources = 1,
|
||||
.requirement_text = "Difference requires one additional source timeseries for v1.",
|
||||
},
|
||||
{
|
||||
.name = "Smoothing",
|
||||
.globals_code = "window = 20\nweights = np.ones(window) / window",
|
||||
.function_code = "return np.convolve(value, weights, mode='same')",
|
||||
.preview_text = "window = 20\nweights = np.ones(window) / window\n\nreturn np.convolve(value, weights, mode='same')",
|
||||
.required_additional_sources = 0,
|
||||
.requirement_text = "",
|
||||
},
|
||||
{
|
||||
.name = "Integral",
|
||||
.globals_code = "",
|
||||
.function_code = "dt = np.mean(np.diff(time))\nreturn np.cumsum(value) * dt",
|
||||
.preview_text = "dt = np.mean(np.diff(time))\nreturn np.cumsum(value) * dt",
|
||||
.required_additional_sources = 0,
|
||||
.requirement_text = "",
|
||||
},
|
||||
}};
|
||||
return kTemplates;
|
||||
}
|
||||
|
||||
void draw_custom_series_help_popup(CustomSeriesEditorState *editor) {
|
||||
if (editor->open_help) {
|
||||
ImGui::OpenPopup("Custom Series Help");
|
||||
editor->open_help = false;
|
||||
}
|
||||
if (!ImGui::BeginPopupModal("Custom Series Help", nullptr, ImGuiWindowFlags_AlwaysAutoResize)) {
|
||||
return;
|
||||
}
|
||||
ImGui::TextUnformatted("Available variables");
|
||||
ImGui::Separator();
|
||||
ImGui::BulletText("np: numpy");
|
||||
ImGui::BulletText("t(path), v(path): timestamps and values for a route series");
|
||||
ImGui::BulletText("paths: all available route series paths");
|
||||
ImGui::BulletText("time, value: linked input timeseries");
|
||||
ImGui::BulletText("t1, v1, t2, v2, ...: additional source timeseries");
|
||||
ImGui::Spacing();
|
||||
ImGui::TextWrapped("Write either a single expression like \"return np.gradient(value, time)\" "
|
||||
"or a multi-line Python body that returns an array or a (times, values) tuple.");
|
||||
ImGui::Spacing();
|
||||
if (ImGui::Button("Close", ImVec2(120.0f, 0.0f))) {
|
||||
ImGui::CloseCurrentPopup();
|
||||
}
|
||||
ImGui::EndPopup();
|
||||
}
|
||||
|
||||
void draw_custom_series_preview(const AppSession &session, CustomSeriesEditorState *editor) {
|
||||
std::vector<double> preview_xs;
|
||||
std::vector<double> preview_ys;
|
||||
std::string preview_label = editor->preview_label;
|
||||
if (editor->preview_is_result && editor->preview_xs.size() > 1 && editor->preview_xs.size() == editor->preview_ys.size()) {
|
||||
preview_xs = editor->preview_xs;
|
||||
preview_ys = editor->preview_ys;
|
||||
if (preview_label.empty()) {
|
||||
preview_label = "Result preview";
|
||||
}
|
||||
} else if (!editor->linked_source.empty()) {
|
||||
if (const RouteSeries *series = app_find_route_series(session, editor->linked_source); series != nullptr
|
||||
&& series->times.size() > 1 && series->times.size() == series->values.size()) {
|
||||
preview_xs = series->times;
|
||||
preview_ys = series->values;
|
||||
preview_label = "Input preview (not result)";
|
||||
}
|
||||
}
|
||||
|
||||
if (!preview_xs.empty() && preview_xs.size() == preview_ys.size()) {
|
||||
std::vector<double> plot_xs;
|
||||
std::vector<double> plot_ys;
|
||||
app_decimate_samples(preview_xs, preview_ys, 1200, &plot_xs, &plot_ys);
|
||||
const double preview_x_min = preview_xs.front();
|
||||
const double preview_x_max = preview_xs.back() > preview_xs.front()
|
||||
? preview_xs.back()
|
||||
: preview_xs.front() + 1e-6;
|
||||
std::string plot_id = "##custom_series_preview";
|
||||
if (editor->preview_is_result) {
|
||||
plot_id += "_result_";
|
||||
plot_id += editor->name.empty() ? preview_label : editor->name;
|
||||
} else if (!editor->linked_source.empty()) {
|
||||
plot_id += "_input_";
|
||||
plot_id += editor->linked_source;
|
||||
}
|
||||
ImGui::TextUnformatted(preview_label.c_str());
|
||||
if (!editor->linked_source.empty() && !editor->preview_is_result) {
|
||||
ImGui::SameLine();
|
||||
ImGui::TextDisabled("%s", editor->linked_source.c_str());
|
||||
}
|
||||
if (ImPlot::BeginPlot(plot_id.c_str(),
|
||||
ImVec2(-1.0f, std::max(180.0f, ImGui::GetContentRegionAvail().y - 6.0f)),
|
||||
ImPlotFlags_NoTitle | ImPlotFlags_NoMenus | ImPlotFlags_NoLegend)) {
|
||||
ImPlot::SetupAxes(nullptr, nullptr, ImPlotAxisFlags_NoMenus | ImPlotAxisFlags_NoHighlight,
|
||||
ImPlotAxisFlags_NoMenus | ImPlotAxisFlags_NoHighlight | ImPlotAxisFlags_AutoFit | ImPlotAxisFlags_RangeFit);
|
||||
ImPlot::SetupAxisLimitsConstraints(ImAxis_X1, preview_x_min, preview_x_max);
|
||||
ImPlot::SetupAxisLimits(ImAxis_X1, preview_x_min, preview_x_max, ImPlotCond_Once);
|
||||
ImPlot::SetupAxisFormat(ImAxis_X1, "%.1f");
|
||||
ImPlot::SetupAxisFormat(ImAxis_Y1, "%.6g");
|
||||
ImPlotSpec spec;
|
||||
spec.LineColor = color_rgb(35, 107, 180);
|
||||
spec.LineWeight = 2.0f;
|
||||
ImPlot::PlotLine("##custom_preview_line", plot_xs.data(), plot_ys.data(), static_cast<int>(plot_xs.size()), spec);
|
||||
ImPlot::EndPlot();
|
||||
}
|
||||
} else {
|
||||
ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 72.0f);
|
||||
ImGui::PushStyleColor(ImGuiCol_Text, color_rgb(116, 124, 133));
|
||||
ImGui::TextWrapped("Choose an input timeseries or click Preview to evaluate the custom result.");
|
||||
ImGui::PopStyleColor();
|
||||
}
|
||||
}
|
||||
|
||||
std::string custom_series_name_status(const Pane &pane, std::string_view name) {
|
||||
const std::string trimmed = util::strip(std::string(name));
|
||||
if (trimmed.empty()) return "name required";
|
||||
if (!trimmed.empty() && trimmed.front() == '/') {
|
||||
return "cannot start with /";
|
||||
}
|
||||
for (const Curve &curve : pane.curves) {
|
||||
if (curve.runtime_only && curve.name == trimmed) return "updates existing curve";
|
||||
}
|
||||
return "new curve";
|
||||
}
|
||||
|
||||
const CustomSeriesTemplate &selected_custom_series_template(const CustomSeriesEditorState &editor) {
|
||||
const auto &templates = custom_series_templates();
|
||||
return templates[static_cast<size_t>(std::clamp(editor.selected_template, 0, static_cast<int>(templates.size()) - 1))];
|
||||
}
|
||||
|
||||
bool custom_series_template_ready(const CustomSeriesEditorState &editor) {
|
||||
const CustomSeriesTemplate &templ = selected_custom_series_template(editor);
|
||||
return !editor.linked_source.empty()
|
||||
&& static_cast<int>(editor.additional_sources.size()) >= templ.required_additional_sources;
|
||||
}
|
||||
|
||||
bool prepare_custom_series_spec(CustomSeriesEditorState *editor,
|
||||
UiState *state,
|
||||
bool require_name,
|
||||
CustomPythonSeries *out_spec) {
|
||||
editor->name = util::strip(editor->name);
|
||||
editor->linked_source = util::strip(editor->linked_source);
|
||||
for (std::string &path : editor->additional_sources) {
|
||||
path = util::strip(path);
|
||||
}
|
||||
editor->additional_sources.erase(
|
||||
std::remove_if(editor->additional_sources.begin(), editor->additional_sources.end(),
|
||||
[&](const std::string &path) { return path.empty() || path == editor->linked_source; }),
|
||||
editor->additional_sources.end());
|
||||
|
||||
if (require_name && editor->name.empty()) {
|
||||
state->error_text = "Custom series name is required.";
|
||||
state->open_error_popup = true;
|
||||
return false;
|
||||
}
|
||||
if (require_name && !editor->name.empty() && editor->name.front() == '/') {
|
||||
state->error_text = "Custom series names may not start with '/'.";
|
||||
state->open_error_popup = true;
|
||||
return false;
|
||||
}
|
||||
|
||||
*out_spec = CustomPythonSeries{
|
||||
.linked_source = editor->linked_source,
|
||||
.additional_sources = editor->additional_sources,
|
||||
.globals_code = editor->globals_code,
|
||||
.function_code = editor->function_code,
|
||||
};
|
||||
return true;
|
||||
}
|
||||
|
||||
bool preview_custom_series_editor(AppSession *session, UiState *state) {
|
||||
CustomSeriesEditorState &editor = state->custom_series;
|
||||
const CustomSeriesTemplate &templ = selected_custom_series_template(editor);
|
||||
if (editor.linked_source.empty()) {
|
||||
state->error_text = "Choose an input timeseries before previewing.";
|
||||
state->open_error_popup = true;
|
||||
state->status_text = "Custom series preview failed";
|
||||
return false;
|
||||
}
|
||||
if (static_cast<int>(editor.additional_sources.size()) < templ.required_additional_sources) {
|
||||
state->error_text = templ.requirement_text;
|
||||
state->open_error_popup = true;
|
||||
state->status_text = "Custom series preview failed";
|
||||
return false;
|
||||
}
|
||||
CustomPythonSeries spec;
|
||||
if (!prepare_custom_series_spec(&editor, state, false, &spec)) return false;
|
||||
|
||||
try {
|
||||
PythonEvalResult result = evaluate_custom_python_series(*session, spec);
|
||||
editor.preview_label = editor.name.empty() ? "Result preview" : editor.name;
|
||||
editor.preview_xs = std::move(result.xs);
|
||||
editor.preview_ys = std::move(result.ys);
|
||||
editor.preview_is_result = true;
|
||||
state->status_text = "Previewed custom series";
|
||||
return true;
|
||||
} catch (const std::exception &err) {
|
||||
state->error_text = err.what();
|
||||
state->open_error_popup = true;
|
||||
state->status_text = "Custom series preview failed";
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool apply_custom_series_editor(AppSession *session, UiState *state) {
|
||||
WorkspaceTab *tab = app_active_tab(&session->layout, *state);
|
||||
TabUiState *tab_state = app_active_tab_state(state);
|
||||
if (tab == nullptr || tab_state == nullptr) {
|
||||
state->status_text = "No active pane";
|
||||
return false;
|
||||
}
|
||||
if (tab_state->active_pane_index < 0 || tab_state->active_pane_index >= static_cast<int>(tab->panes.size())) {
|
||||
state->status_text = "No active pane";
|
||||
return false;
|
||||
}
|
||||
|
||||
CustomSeriesEditorState &editor = state->custom_series;
|
||||
CustomPythonSeries spec;
|
||||
if (!prepare_custom_series_spec(&editor, state, true, &spec)) return false;
|
||||
|
||||
try {
|
||||
PythonEvalResult result = evaluate_custom_python_series(*session, spec);
|
||||
const SketchLayout before_layout = session->layout;
|
||||
Pane &pane = tab->panes[static_cast<size_t>(tab_state->active_pane_index)];
|
||||
editor.preview_label = editor.name;
|
||||
editor.preview_xs = result.xs;
|
||||
editor.preview_ys = result.ys;
|
||||
editor.preview_is_result = true;
|
||||
const bool inserted = upsert_custom_curve_in_pane(tab,
|
||||
tab_state->active_pane_index,
|
||||
make_custom_curve(pane, editor.name, spec, std::move(result)));
|
||||
state->undo.push(before_layout);
|
||||
state->status_text = inserted ? "Created custom series " + editor.name
|
||||
: "Updated custom series " + editor.name;
|
||||
return true;
|
||||
} catch (const std::exception &err) {
|
||||
state->error_text = err.what();
|
||||
state->open_error_popup = true;
|
||||
state->status_text = "Custom series failed";
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
void open_custom_series_editor(UiState *state, const std::string &preferred_source) {
|
||||
CustomSeriesEditorState &editor = state->custom_series;
|
||||
if (!editor.open && editor.name.empty() && editor.linked_source.empty() && editor.function_code == "return value") {
|
||||
editor.focus_name = true;
|
||||
}
|
||||
if (editor.linked_source.empty() && !preferred_source.empty()) {
|
||||
editor.linked_source = preferred_source;
|
||||
}
|
||||
editor.open = true;
|
||||
editor.request_select = true;
|
||||
}
|
||||
|
||||
std::string preferred_custom_series_source(const Pane &pane) {
|
||||
for (const Curve &curve : pane.curves) {
|
||||
if (!curve.name.empty() && curve.name.front() == '/') {
|
||||
return curve.name;
|
||||
}
|
||||
if (curve.custom_python.has_value() && !curve.custom_python->linked_source.empty()) {
|
||||
return curve.custom_python->linked_source;
|
||||
}
|
||||
}
|
||||
return {};
|
||||
}
|
||||
|
||||
void refresh_all_custom_curves(AppSession *session, UiState *state) {
|
||||
for (WorkspaceTab &tab : session->layout.tabs) {
|
||||
for (Pane &pane : tab.panes) {
|
||||
for (Curve &curve : pane.curves) {
|
||||
refresh_custom_curve_samples(session, state, &curve);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void draw_editor_source_panel(UiState *state, CustomSeriesEditorState &editor) {
|
||||
ImGui::TextWrapped("Input timeseries. Provides arguments time and value:");
|
||||
ImGui::SetNextItemWidth(-FLT_MIN);
|
||||
input_text_string("##custom_linked_source", &editor.linked_source, ImGuiInputTextFlags_ReadOnly);
|
||||
if (ImGui::BeginDragDropTarget()) {
|
||||
if (const ImGuiPayload *payload = ImGui::AcceptDragDropPayload("JOTP_BROWSER_PATH")) {
|
||||
editor.linked_source = static_cast<const char *>(payload->Data);
|
||||
editor.additional_sources.erase(
|
||||
std::remove(editor.additional_sources.begin(), editor.additional_sources.end(), editor.linked_source),
|
||||
editor.additional_sources.end());
|
||||
editor.preview_is_result = false;
|
||||
}
|
||||
ImGui::EndDragDropTarget();
|
||||
}
|
||||
if (ImGui::Button("Use Selected", ImVec2(120.0f, 0.0f)) && !state->selected_browser_path.empty()) {
|
||||
editor.linked_source = state->selected_browser_path;
|
||||
editor.additional_sources.erase(
|
||||
std::remove(editor.additional_sources.begin(), editor.additional_sources.end(), editor.linked_source),
|
||||
editor.additional_sources.end());
|
||||
editor.preview_is_result = false;
|
||||
}
|
||||
ImGui::SameLine();
|
||||
if (ImGui::Button("Clear", ImVec2(120.0f, 0.0f))) {
|
||||
editor.linked_source.clear();
|
||||
editor.preview_is_result = false;
|
||||
}
|
||||
|
||||
ImGui::Spacing();
|
||||
ImGui::TextUnformatted("Additional source timeseries:");
|
||||
ImGui::SameLine();
|
||||
const CustomSeriesTemplate &tmpl = selected_custom_series_template(editor);
|
||||
if (tmpl.required_additional_sources > 0) {
|
||||
const bool ready = static_cast<int>(editor.additional_sources.size()) >= tmpl.required_additional_sources;
|
||||
ImGui::TextColored(ready ? color_rgb(58, 126, 73) : color_rgb(180, 122, 44), "%s", tmpl.requirement_text);
|
||||
}
|
||||
ImGui::SameLine();
|
||||
ImGui::BeginDisabled(editor.selected_additional_source < 0
|
||||
|| editor.selected_additional_source >= static_cast<int>(editor.additional_sources.size()));
|
||||
if (ImGui::Button("Remove Selected", ImVec2(140.0f, 0.0f))
|
||||
&& editor.selected_additional_source >= 0
|
||||
&& editor.selected_additional_source < static_cast<int>(editor.additional_sources.size())) {
|
||||
editor.additional_sources.erase(editor.additional_sources.begin()
|
||||
+ static_cast<std::ptrdiff_t>(editor.selected_additional_source));
|
||||
editor.selected_additional_source = editor.additional_sources.empty()
|
||||
? -1 : std::clamp(editor.selected_additional_source, 0, static_cast<int>(editor.additional_sources.size()) - 1);
|
||||
editor.preview_is_result = false;
|
||||
}
|
||||
ImGui::EndDisabled();
|
||||
|
||||
if (ImGui::BeginChild("##custom_additional_sources", ImVec2(0.0f, 156.0f), true)) {
|
||||
if (ImGui::BeginTable("##custom_additional_table", 2,
|
||||
ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingStretchProp)) {
|
||||
ImGui::TableSetupColumn("id", ImGuiTableColumnFlags_WidthFixed, 42.0f);
|
||||
ImGui::TableSetupColumn("path", ImGuiTableColumnFlags_WidthStretch);
|
||||
for (size_t i = 0; i < editor.additional_sources.size(); ++i) {
|
||||
ImGui::TableNextRow();
|
||||
ImGui::TableNextColumn();
|
||||
ImGui::Text("v%zu", i + 1);
|
||||
ImGui::TableNextColumn();
|
||||
if (ImGui::Selectable(editor.additional_sources[i].c_str(),
|
||||
editor.selected_additional_source == static_cast<int>(i),
|
||||
ImGuiSelectableFlags_SpanAllColumns)) {
|
||||
editor.selected_additional_source = static_cast<int>(i);
|
||||
}
|
||||
}
|
||||
ImGui::EndTable();
|
||||
}
|
||||
if (ImGui::BeginDragDropTarget()) {
|
||||
if (const ImGuiPayload *payload = ImGui::AcceptDragDropPayload("JOTP_BROWSER_PATH")) {
|
||||
if (add_additional_source(&editor, static_cast<const char *>(payload->Data)))
|
||||
editor.preview_is_result = false;
|
||||
}
|
||||
ImGui::EndDragDropTarget();
|
||||
}
|
||||
}
|
||||
ImGui::EndChild();
|
||||
if (ImGui::Button("Add Selected", ImVec2(120.0f, 0.0f))) {
|
||||
for (const std::string &path : state->selected_browser_paths) {
|
||||
if (add_additional_source(&editor, path)) editor.preview_is_result = false;
|
||||
}
|
||||
}
|
||||
|
||||
ImGui::Spacing();
|
||||
ImGui::SeparatorText("Function library");
|
||||
const auto &templates = custom_series_templates();
|
||||
if (ImGui::BeginChild("##custom_series_template_list", ImVec2(0.0f, 132.0f), true)) {
|
||||
for (size_t i = 0; i < templates.size(); ++i) {
|
||||
if (ImGui::Selectable(templates[i].name, editor.selected_template == static_cast<int>(i),
|
||||
ImGuiSelectableFlags_AllowDoubleClick)) {
|
||||
editor.selected_template = static_cast<int>(i);
|
||||
if (ImGui::IsMouseDoubleClicked(ImGuiMouseButton_Left)) {
|
||||
editor.globals_code = templates[i].globals_code;
|
||||
editor.function_code = templates[i].function_code;
|
||||
editor.preview_is_result = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
ImGui::EndChild();
|
||||
if (ImGui::Button("Use Selected Example")) {
|
||||
const auto &sel = selected_custom_series_template(editor);
|
||||
editor.globals_code = sel.globals_code;
|
||||
editor.function_code = sel.function_code;
|
||||
editor.preview_is_result = false;
|
||||
}
|
||||
ImGui::Spacing();
|
||||
ImGui::TextDisabled("Preview");
|
||||
ImGui::BeginChild("##custom_series_template_preview", ImVec2(0.0f, 0.0f), true);
|
||||
ImGui::TextUnformatted(selected_custom_series_template(editor).preview_text);
|
||||
ImGui::EndChild();
|
||||
}
|
||||
|
||||
void draw_editor_code_panel(CustomSeriesEditorState &editor, const Pane *active_pane) {
|
||||
const std::string name_status = active_pane != nullptr ? custom_series_name_status(*active_pane, editor.name) : "no active pane";
|
||||
ImGui::TextUnformatted("New name:");
|
||||
ImGui::SameLine();
|
||||
const bool name_error = name_status == "name required" || name_status == "cannot start with /";
|
||||
ImGui::TextColored(name_error ? color_rgb(200, 72, 64) : color_rgb(58, 126, 73), "%s", name_status.c_str());
|
||||
if (editor.focus_name) { ImGui::SetKeyboardFocusHere(); editor.focus_name = false; }
|
||||
ImGui::SetNextItemWidth(-FLT_MIN);
|
||||
input_text_string("##custom_series_name", &editor.name, ImGuiInputTextFlags_AutoSelectAll);
|
||||
|
||||
ImGui::Spacing();
|
||||
ImGui::SeparatorText("Global variables");
|
||||
ImGui::SameLine();
|
||||
if (ImGui::SmallButton("Help")) editor.open_help = true;
|
||||
const float globals_h = std::max(96.0f, ImGui::GetContentRegionAvail().y * 0.28f);
|
||||
if (input_text_multiline_string("##custom_series_globals", &editor.globals_code,
|
||||
ImVec2(-FLT_MIN, globals_h), ImGuiInputTextFlags_AllowTabInput))
|
||||
editor.preview_is_result = false;
|
||||
|
||||
ImGui::Spacing();
|
||||
ImGui::TextUnformatted("def calc(time, value):");
|
||||
const float func_h = std::max(180.0f, ImGui::GetContentRegionAvail().y - 16.0f);
|
||||
if (input_text_multiline_string("##custom_series_function", &editor.function_code,
|
||||
ImVec2(-FLT_MIN, func_h), ImGuiInputTextFlags_AllowTabInput))
|
||||
editor.preview_is_result = false;
|
||||
}
|
||||
|
||||
void draw_custom_series_editor(AppSession *session, UiState *state) {
|
||||
CustomSeriesEditorState &editor = state->custom_series;
|
||||
if (!editor.open) return;
|
||||
|
||||
WorkspaceTab *tab = app_active_tab(&session->layout, *state);
|
||||
TabUiState *tab_state = app_active_tab_state(state);
|
||||
Pane *active_pane = (tab && tab_state && tab_state->active_pane_index >= 0
|
||||
&& tab_state->active_pane_index < static_cast<int>(tab->panes.size()))
|
||||
? &tab->panes[static_cast<size_t>(tab_state->active_pane_index)] : nullptr;
|
||||
if (editor.focus_name && active_pane && editor.name.empty())
|
||||
editor.name = next_custom_curve_name(*active_pane);
|
||||
|
||||
draw_custom_series_help_popup(&editor);
|
||||
|
||||
if (ImGui::BeginTabBar("##custom_series_tabs")) {
|
||||
if (ImGui::BeginTabItem("Single Function")) {
|
||||
const float footer_height = ImGui::GetFrameHeightWithSpacing() * 2.0f + 10.0f;
|
||||
if (ImGui::BeginChild("##custom_series_body",
|
||||
ImVec2(0.0f, std::max(1.0f, ImGui::GetContentRegionAvail().y - footer_height)), false)) {
|
||||
if (ImGui::BeginChild("##custom_series_preview_child",
|
||||
ImVec2(0.0f, std::max(200.0f, ImGui::GetContentRegionAvail().y * 0.28f)), true))
|
||||
draw_custom_series_preview(*session, &editor);
|
||||
ImGui::EndChild();
|
||||
ImGui::Spacing();
|
||||
|
||||
if (ImGui::BeginTable("##custom_series_editor_table", 2,
|
||||
ImGuiTableFlags_Resizable | ImGuiTableFlags_BordersInnerV | ImGuiTableFlags_SizingStretchProp,
|
||||
ImVec2(0.0f, std::max(1.0f, ImGui::GetContentRegionAvail().y)))) {
|
||||
ImGui::TableSetupColumn("left", ImGuiTableColumnFlags_WidthFixed, 320.0f);
|
||||
ImGui::TableSetupColumn("right", ImGuiTableColumnFlags_WidthStretch);
|
||||
ImGui::TableNextColumn();
|
||||
if (ImGui::BeginChild("##custom_series_left", ImVec2(0.0f, 0.0f), false))
|
||||
draw_editor_source_panel(state, editor);
|
||||
ImGui::EndChild();
|
||||
ImGui::TableNextColumn();
|
||||
if (ImGui::BeginChild("##custom_series_right", ImVec2(0.0f, 0.0f), false))
|
||||
draw_editor_code_panel(editor, active_pane);
|
||||
ImGui::EndChild();
|
||||
ImGui::EndTable();
|
||||
}
|
||||
}
|
||||
ImGui::EndChild();
|
||||
|
||||
ImGui::Spacing();
|
||||
if (ImGui::Button("New", ImVec2(120.0f, 0.0f))) {
|
||||
reset_custom_series_editor(&editor);
|
||||
if (!state->selected_browser_path.empty()) editor.linked_source = state->selected_browser_path;
|
||||
editor.open = true;
|
||||
editor.focus_name = true;
|
||||
}
|
||||
ImGui::SameLine();
|
||||
ImGui::BeginDisabled(!custom_series_template_ready(editor));
|
||||
if (ImGui::Button("Preview Result", ImVec2(120.0f, 0.0f)))
|
||||
preview_custom_series_editor(session, state);
|
||||
ImGui::EndDisabled();
|
||||
if (ImGui::IsItemHovered(ImGuiHoveredFlags_AllowWhenDisabled) && !custom_series_template_ready(editor)) {
|
||||
if (editor.linked_source.empty()) ImGui::SetTooltip("Choose an input timeseries first.");
|
||||
else ImGui::SetTooltip("%s", selected_custom_series_template(editor).requirement_text);
|
||||
}
|
||||
ImGui::SameLine();
|
||||
if (ImGui::Button("Apply", ImVec2(120.0f, 0.0f))) apply_custom_series_editor(session, state);
|
||||
ImGui::SameLine();
|
||||
if (ImGui::Button("Close", ImVec2(120.0f, 0.0f))) { editor.open = false; editor.request_select = false; }
|
||||
ImGui::EndTabItem();
|
||||
}
|
||||
ImGui::EndTabBar();
|
||||
}
|
||||
}
|
||||
400
tools/jotpluggler/dbc.h
Normal file
400
tools/jotpluggler/dbc.h
Normal file
@@ -0,0 +1,400 @@
|
||||
#pragma once
|
||||
|
||||
#include "common/util.h"
|
||||
|
||||
#include <algorithm>
|
||||
#include <cmath>
|
||||
#include <cstddef>
|
||||
#include <cstdint>
|
||||
#include <filesystem>
|
||||
#include <fstream>
|
||||
#include <optional>
|
||||
#include <regex>
|
||||
#include <sstream>
|
||||
#include <stdexcept>
|
||||
#include <string>
|
||||
#include <tuple>
|
||||
#include <unordered_map>
|
||||
#include <vector>
|
||||
|
||||
namespace dbc {
|
||||
|
||||
|
||||
struct ValueDescriptionEntry {
|
||||
double value = 0.0;
|
||||
std::string text;
|
||||
};
|
||||
|
||||
struct Signal {
|
||||
enum class Type {
|
||||
Normal = 0,
|
||||
Multiplexed,
|
||||
Multiplexor,
|
||||
};
|
||||
|
||||
Type type = Type::Normal;
|
||||
std::string name;
|
||||
int start_bit = 0;
|
||||
int msb = 0;
|
||||
int lsb = 0;
|
||||
int size = 0;
|
||||
double factor = 1.0;
|
||||
double offset = 0.0;
|
||||
double min = 0.0;
|
||||
double max = 0.0;
|
||||
bool is_signed = false;
|
||||
bool is_little_endian = false;
|
||||
std::string unit;
|
||||
std::string comment;
|
||||
std::string receiver_name;
|
||||
int multiplex_value = 0;
|
||||
int multiplexor_index = -1;
|
||||
std::vector<ValueDescriptionEntry> value_descriptions;
|
||||
};
|
||||
|
||||
struct Message {
|
||||
uint32_t address = 0;
|
||||
std::string name;
|
||||
uint32_t size = 0;
|
||||
std::string comment;
|
||||
std::string transmitter;
|
||||
std::vector<Signal> signals;
|
||||
int multiplexor_index = -1;
|
||||
|
||||
const std::vector<Signal> &getSignals() const { return signals; }
|
||||
};
|
||||
|
||||
class Database {
|
||||
public:
|
||||
Database() = default;
|
||||
explicit Database(const std::filesystem::path &path);
|
||||
static Database fromContent(const std::string &content, const std::string &filename = "<dbc>");
|
||||
|
||||
const Message *message(uint32_t address) const;
|
||||
const std::unordered_map<uint32_t, Message> &messages() const { return messages_; }
|
||||
std::vector<std::string> enumNames(const Signal &signal) const;
|
||||
|
||||
private:
|
||||
void parse(const std::string &content, const std::string &filename);
|
||||
void parseBo(const std::string &line, int line_number, Message **current_message);
|
||||
void parseSg(const std::string &line, int line_number, Message *current_message);
|
||||
void parseVal(const std::string &line, int line_number);
|
||||
void parseCmBo(const std::string &line, int line_number);
|
||||
void parseCmSg(const std::string &line, int line_number);
|
||||
void finalize();
|
||||
|
||||
std::string filename_;
|
||||
std::unordered_map<uint32_t, Message> messages_;
|
||||
};
|
||||
|
||||
void updateMsbLsb(Signal *signal);
|
||||
double rawSignalValue(const Signal &signal, const uint8_t *data, size_t data_size);
|
||||
std::optional<double> signalValue(const Signal &signal, const Message &message, const uint8_t *data, size_t data_size);
|
||||
|
||||
namespace {
|
||||
|
||||
std::string unescape_dbc_string(std::string text) {
|
||||
size_t pos = 0;
|
||||
while ((pos = text.find("\\\"", pos)) != std::string::npos) {
|
||||
text.replace(pos, 2, "\"");
|
||||
++pos;
|
||||
}
|
||||
return text;
|
||||
}
|
||||
|
||||
int flip_bit_pos(int start_bit) {
|
||||
return 8 * (start_bit / 8) + 7 - start_bit % 8;
|
||||
}
|
||||
|
||||
std::string read_multiline_statement(std::istream &stream, std::string statement, int *line_number) {
|
||||
static const std::regex statement_end(R"(\"\s*;\s*$)");
|
||||
while (true) {
|
||||
const std::string trimmed = util::strip(statement);
|
||||
if (std::regex_search(trimmed, statement_end)) {
|
||||
return trimmed;
|
||||
}
|
||||
|
||||
std::string next_line;
|
||||
if (!std::getline(stream, next_line)) {
|
||||
return trimmed;
|
||||
}
|
||||
statement += "\n";
|
||||
statement += next_line;
|
||||
++(*line_number);
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
inline void updateMsbLsb(Signal *signal) {
|
||||
if (signal->is_little_endian) {
|
||||
signal->lsb = signal->start_bit;
|
||||
signal->msb = signal->start_bit + signal->size - 1;
|
||||
} else {
|
||||
signal->lsb = flip_bit_pos(flip_bit_pos(signal->start_bit) + signal->size - 1);
|
||||
signal->msb = signal->start_bit;
|
||||
}
|
||||
}
|
||||
|
||||
inline double rawSignalValue(const Signal &signal, const uint8_t *data, size_t data_size) {
|
||||
const int msb_byte = signal.msb / 8;
|
||||
if (msb_byte >= static_cast<int>(data_size)) return 0.0;
|
||||
|
||||
const int lsb_byte = signal.lsb / 8;
|
||||
uint64_t val = 0;
|
||||
if (msb_byte == lsb_byte) {
|
||||
val = (data[msb_byte] >> (signal.lsb & 7)) & ((1ULL << signal.size) - 1);
|
||||
} else {
|
||||
int bits = signal.size;
|
||||
int i = msb_byte;
|
||||
const int step = signal.is_little_endian ? -1 : 1;
|
||||
while (i >= 0 && i < static_cast<int>(data_size) && bits > 0) {
|
||||
const int msb = (i == msb_byte) ? signal.msb & 7 : 7;
|
||||
const int lsb = (i == lsb_byte) ? signal.lsb & 7 : 0;
|
||||
const int nbits = msb - lsb + 1;
|
||||
val = (val << nbits) | ((data[i] >> lsb) & ((1ULL << nbits) - 1));
|
||||
bits -= nbits;
|
||||
i += step;
|
||||
}
|
||||
}
|
||||
|
||||
if (signal.is_signed && (val & (1ULL << (signal.size - 1)))) {
|
||||
val |= ~((1ULL << signal.size) - 1);
|
||||
}
|
||||
|
||||
return static_cast<int64_t>(val) * signal.factor + signal.offset;
|
||||
}
|
||||
|
||||
[[noreturn]] inline void parse_error(const std::string &filename, int line_number, const std::string &message, const std::string &line) {
|
||||
std::ostringstream out;
|
||||
out << "[" << filename << ":" << line_number << "] " << message << ": " << line;
|
||||
throw std::runtime_error(out.str());
|
||||
}
|
||||
|
||||
inline Database::Database(const std::filesystem::path &path) {
|
||||
const std::string content = util::read_file(path.string());
|
||||
if (content.empty() && !std::filesystem::exists(path)) {
|
||||
throw std::runtime_error("Failed to open DBC " + path.string());
|
||||
}
|
||||
parse(content, path.filename().string());
|
||||
}
|
||||
|
||||
inline Database Database::fromContent(const std::string &content, const std::string &filename) {
|
||||
Database db;
|
||||
db.parse(content, filename);
|
||||
return db;
|
||||
}
|
||||
|
||||
inline const Message *Database::message(uint32_t address) const {
|
||||
auto it = messages_.find(address);
|
||||
return it == messages_.end() ? nullptr : &it->second;
|
||||
}
|
||||
|
||||
inline std::vector<std::string> Database::enumNames(const Signal &signal) const {
|
||||
if (signal.value_descriptions.empty()) return {};
|
||||
int max_index = -1;
|
||||
for (const auto &entry : signal.value_descriptions) {
|
||||
const double rounded = std::round(entry.value);
|
||||
if (std::abs(entry.value - rounded) > 1e-6 || rounded < 0.0 || rounded > 512.0) return {};
|
||||
max_index = std::max(max_index, static_cast<int>(rounded));
|
||||
}
|
||||
if (max_index < 0) return {};
|
||||
std::vector<std::string> names(static_cast<size_t>(max_index + 1));
|
||||
for (const auto &entry : signal.value_descriptions) {
|
||||
names[static_cast<size_t>(std::llround(entry.value))] = entry.text;
|
||||
}
|
||||
return names;
|
||||
}
|
||||
|
||||
inline void Database::parse(const std::string &content, const std::string &filename) {
|
||||
filename_ = filename;
|
||||
messages_.clear();
|
||||
std::istringstream stream(content);
|
||||
std::string raw_line;
|
||||
Message *current_message = nullptr;
|
||||
int line_number = 0;
|
||||
while (std::getline(stream, raw_line)) {
|
||||
++line_number;
|
||||
std::string line = util::strip(raw_line);
|
||||
if (line.empty()) continue;
|
||||
if (util::starts_with(line, "BO_ ")) {
|
||||
parseBo(line, line_number, ¤t_message);
|
||||
} else if (util::starts_with(line, "SG_ ")) {
|
||||
if (current_message == nullptr) {
|
||||
parse_error(filename, line_number, "Signal without current message", line);
|
||||
}
|
||||
parseSg(line, line_number, current_message);
|
||||
} else if (util::starts_with(line, "VAL_ ")) {
|
||||
parseVal(line, line_number);
|
||||
} else if (util::starts_with(line, "CM_ BO_")) {
|
||||
parseCmBo(read_multiline_statement(stream, raw_line, &line_number), line_number);
|
||||
} else if (util::starts_with(line, "CM_ SG_")) {
|
||||
parseCmSg(read_multiline_statement(stream, raw_line, &line_number), line_number);
|
||||
}
|
||||
}
|
||||
finalize();
|
||||
}
|
||||
|
||||
inline void Database::parseBo(const std::string &line, int line_number, Message **current_message) {
|
||||
static const std::regex pattern(R"(^BO_\s+(\w+)\s+(\w+)\s*:\s*(\w+)\s+(\w+)\s*$)");
|
||||
std::smatch match;
|
||||
if (!std::regex_match(line, match, pattern)) {
|
||||
parse_error("<dbc>", line_number, "Invalid BO_ line format", line);
|
||||
}
|
||||
uint32_t address = static_cast<uint32_t>(std::stoul(match[1].str(), nullptr, 0));
|
||||
if (messages_.find(address) != messages_.end()) {
|
||||
parse_error(filename_, line_number, "Duplicate message address", line);
|
||||
}
|
||||
Message &message = messages_[address];
|
||||
message.address = address;
|
||||
message.name = match[2].str();
|
||||
message.size = static_cast<uint32_t>(std::stoul(match[3].str(), nullptr, 0));
|
||||
message.transmitter = match[4].str();
|
||||
message.signals.clear();
|
||||
message.multiplexor_index = -1;
|
||||
*current_message = &message;
|
||||
}
|
||||
|
||||
inline void Database::parseSg(const std::string &line, int line_number, Message *current_message) {
|
||||
static const std::regex multiplex_pattern(R"(^SG_\s+(\w+)\s+(\w+)\s*:\s*(\d+)\|(\d+)@(\d)([+-])\s+\(([0-9.+\-eE]+),([0-9.+\-eE]+)\)\s+\[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\]\s+\"(.*)\"\s+(.*)$)");
|
||||
static const std::regex normal_pattern(R"(^SG_\s+(\w+)\s*:\s*(\d+)\|(\d+)@(\d)([+-])\s+\(([0-9.+\-eE]+),([0-9.+\-eE]+)\)\s+\[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\]\s+\"(.*)\"\s+(.*)$)");
|
||||
|
||||
std::smatch match;
|
||||
Signal signal;
|
||||
int offset = 0;
|
||||
if (std::regex_match(line, match, normal_pattern)) {
|
||||
offset = 0;
|
||||
} else if (std::regex_match(line, match, multiplex_pattern)) {
|
||||
offset = 1;
|
||||
const std::string indicator = match[2].str();
|
||||
if (indicator == "M") {
|
||||
if (std::any_of(current_message->signals.begin(), current_message->signals.end(), [](const Signal &existing) {
|
||||
return existing.type == Signal::Type::Multiplexor;
|
||||
})) {
|
||||
parse_error(filename_, line_number, "Multiple multiplexor", line);
|
||||
}
|
||||
signal.type = Signal::Type::Multiplexor;
|
||||
} else if (!indicator.empty() && indicator.front() == 'm') {
|
||||
signal.type = Signal::Type::Multiplexed;
|
||||
signal.multiplex_value = std::stoi(indicator.substr(1));
|
||||
} else {
|
||||
parse_error("<dbc>", line_number, "Invalid multiplex indicator", line);
|
||||
}
|
||||
} else {
|
||||
parse_error("<dbc>", line_number, "Invalid SG_ line format", line);
|
||||
}
|
||||
|
||||
signal.name = match[1].str();
|
||||
if (std::any_of(current_message->signals.begin(), current_message->signals.end(), [&](const Signal &existing) {
|
||||
return existing.name == signal.name;
|
||||
})) {
|
||||
parse_error(filename_, line_number, "Duplicate signal name", line);
|
||||
}
|
||||
signal.start_bit = std::stoi(match[2 + offset].str());
|
||||
signal.size = std::stoi(match[3 + offset].str());
|
||||
signal.is_little_endian = match[4 + offset].str() == "1";
|
||||
signal.is_signed = match[5 + offset].str() == "-";
|
||||
signal.factor = std::stod(match[6 + offset].str());
|
||||
signal.offset = std::stod(match[7 + offset].str());
|
||||
signal.min = std::stod(match[8 + offset].str());
|
||||
signal.max = std::stod(match[9 + offset].str());
|
||||
signal.unit = match[10 + offset].str();
|
||||
signal.receiver_name = util::strip(match[11 + offset].str());
|
||||
updateMsbLsb(&signal);
|
||||
current_message->signals.push_back(std::move(signal));
|
||||
}
|
||||
|
||||
inline void Database::parseVal(const std::string &line, int line_number) {
|
||||
static const std::regex prefix(R"(^VAL_\s+(\w+)\s+(\w+)\s+(.*);$)");
|
||||
std::smatch match;
|
||||
if (!std::regex_match(line, match, prefix)) {
|
||||
parse_error("<dbc>", line_number, "Invalid VAL_ line format", line);
|
||||
}
|
||||
|
||||
const uint32_t address = static_cast<uint32_t>(std::stoul(match[1].str(), nullptr, 0));
|
||||
auto msg_it = messages_.find(address);
|
||||
if (msg_it == messages_.end()) {
|
||||
return;
|
||||
}
|
||||
auto sig_it = std::find_if(msg_it->second.signals.begin(), msg_it->second.signals.end(), [&](const Signal &signal) {
|
||||
return signal.name == match[2].str();
|
||||
});
|
||||
if (sig_it == msg_it->second.signals.end()) {
|
||||
return;
|
||||
}
|
||||
|
||||
static const std::regex entry_pattern(R"(([+-]?\d+(?:\.\d+)?)\s+\"((?:[^\"\\]|\\.)*)\")");
|
||||
const std::string defs = match[3].str();
|
||||
for (std::sregex_iterator it(defs.begin(), defs.end(), entry_pattern), end; it != end; ++it) {
|
||||
sig_it->value_descriptions.push_back(ValueDescriptionEntry{
|
||||
.value = std::stod((*it)[1].str()),
|
||||
.text = (*it)[2].str(),
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
inline void Database::parseCmBo(const std::string &line, int line_number) {
|
||||
static const std::regex pattern(R"(^CM_\s+BO_\s*(\w+)\s*\"((?:[^\"\\]|\\.|[\r\n])*)\"\s*;\s*$)");
|
||||
std::smatch match;
|
||||
if (!std::regex_match(line, match, pattern)) {
|
||||
parse_error(filename_, line_number, "Invalid message comment format", line);
|
||||
}
|
||||
const uint32_t address = static_cast<uint32_t>(std::stoul(match[1].str(), nullptr, 0));
|
||||
auto it = messages_.find(address);
|
||||
if (it != messages_.end()) {
|
||||
it->second.comment = unescape_dbc_string(match[2].str());
|
||||
}
|
||||
}
|
||||
|
||||
inline void Database::parseCmSg(const std::string &line, int line_number) {
|
||||
static const std::regex pattern(R"(^CM_\s+SG_\s*(\w+)\s*(\w+)\s*\"((?:[^\"\\]|\\.|[\r\n])*)\"\s*;\s*$)");
|
||||
std::smatch match;
|
||||
if (!std::regex_match(line, match, pattern)) {
|
||||
parse_error(filename_, line_number, "Invalid signal comment format", line);
|
||||
}
|
||||
|
||||
const uint32_t address = static_cast<uint32_t>(std::stoul(match[1].str(), nullptr, 0));
|
||||
auto msg_it = messages_.find(address);
|
||||
if (msg_it == messages_.end()) return;
|
||||
|
||||
auto sig_it = std::find_if(msg_it->second.signals.begin(), msg_it->second.signals.end(), [&](const Signal &signal) {
|
||||
return signal.name == match[2].str();
|
||||
});
|
||||
if (sig_it != msg_it->second.signals.end()) {
|
||||
sig_it->comment = unescape_dbc_string(match[3].str());
|
||||
}
|
||||
}
|
||||
|
||||
inline void Database::finalize() {
|
||||
for (auto &[_, message] : messages_) {
|
||||
std::sort(message.signals.begin(), message.signals.end(), [](const Signal &left, const Signal &right) {
|
||||
return std::tie(right.type, left.multiplex_value, left.start_bit, left.name)
|
||||
< std::tie(left.type, right.multiplex_value, right.start_bit, right.name);
|
||||
});
|
||||
message.multiplexor_index = -1;
|
||||
for (size_t i = 0; i < message.signals.size(); ++i) {
|
||||
if (message.signals[i].type == Signal::Type::Multiplexor) {
|
||||
message.multiplexor_index = static_cast<int>(i);
|
||||
break;
|
||||
}
|
||||
}
|
||||
for (Signal &signal : message.signals) {
|
||||
signal.multiplexor_index = signal.type == Signal::Type::Multiplexed ? message.multiplexor_index : -1;
|
||||
if (signal.type == Signal::Type::Multiplexed && signal.multiplexor_index < 0) {
|
||||
signal.type = Signal::Type::Normal;
|
||||
signal.multiplex_value = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inline std::optional<double> signalValue(const Signal &signal, const Message &message, const uint8_t *data, size_t data_size) {
|
||||
if (signal.multiplexor_index >= 0) {
|
||||
const Signal &multiplexor = message.signals[static_cast<size_t>(signal.multiplexor_index)];
|
||||
const double mux_value = rawSignalValue(multiplexor, data, data_size);
|
||||
if (std::llround(mux_value) != signal.multiplex_value) return std::nullopt;
|
||||
}
|
||||
return rawSignalValue(signal, data, data_size);
|
||||
}
|
||||
|
||||
} // namespace dbc
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user