Summary
Add the ability to load and replay multiple ULog files simultaneously in a single scene, with automatic temporal alignment at takeoff, a unified timeline, and an optional --ghost flag that renders comparison drones at reduced opacity. Without --ghost, all drones render equally as a normal swarm replay.
Problem
Currently, mavsim-viewer supports only a single ULog file at a time (sources[0] in replay mode). Comparing two flights requires opening them separately and mentally aligning events. There is no way to:
- Load multiple
.ulg files and replay them in sync
- Automatically determine where "flight starts" in each log and align them
- Optionally distinguish a reference drone from comparison drones visually
- See a unified timeline when flights have different durations
The ulog_replay.h comment at lines 110-112 already anticipates this:
// Future scope: multi-file swarm replay with time synchronization.
// Each vehicle would get its own ulog_replay_ctx_t with a time_offset
// to align different log start times to a common playback clock.
Proposed Solution
1. Multi-Log Loading
Each additional ULog file gets its own ulog_replay_ctx_t and occupies a slot in the existing sources[] / vehicles[] arrays (which already support MAX_VEHICLES = 129).
Loading:
mavsim-viewer --replay flight1.ulg flight2.ulg [flight3.ulg ...]
mavsim-viewer --ghost flight1.ulg flight2.ulg # ghost mode: first file = reference
- Each file creates an independent
data_source_t via data_source_ulog_create(&sources[i], path)
- Without
--ghost: all drones render equally as a swarm replay
- With
--ghost: first file is the opaque reference, subsequent files render at reduced alpha
Platform notes:
- File path handling uses the existing
asset_path.c which resolves paths correctly on Windows, macOS, and Linux
- ULog parsing is pure C with
fopen/fread — fully portable
- Multiple CLI args work identically across
cmd.exe, PowerShell, bash, and zsh
2. Automatic Temporal Alignment (Takeoff Sync)
ULog timestamps are microseconds from boot — two logs share no common epoch. Pre-flight data contains sensor noise (GPS wander +/-0.3 m/s, handling spikes, vibration). The method must find a "start of flight" anchor in each log independently.
Method: CUSUM changepoint detection with nav_state corroboration.
Key constraint: vehicle_status with nav_state is often missing in simulation logs (the parser falls back silently), so kinematic detection must be the primary path, not a fallback.
Algorithm
STAGE 1 — CUSUM on velocity energy (always runs, O(N))
K(t) = sqrt(vx^2 + vy^2 + vz^2) // uses guaranteed vx/vy/vz fields
mu_0 = mean(K[first 5-10s]) // pre-flight baseline (~0.03 m/s)
sigma_0 = std(K[first 5-10s]) // noise std dev (~0.02 m/s)
delta = 0.5 m/s // minimum detectable shift
S(0) = 0
S(n) = max(0, S(n-1) + K(n) - mu_0 - delta/2)
t_onset = first n where S(n) > h AND sustained >= 500ms
STAGE 2 — nav_state corroboration (when vehicle_status exists)
Scan mode_changes[] for nav_state in {17, 3, 14}
If |t_nav - t_onset| < 2.0s: corroborated, high confidence
If nav_state absent: proceed with CUSUM alone, moderate confidence
STAGE 3 — Confidence scoring
C = weighted(CUSUM_SNR:0.35, nav_state:0.25, stillness:0.20,
onset_sharpness:0.12, altitude_confirm:0.08)
CUSUM is provably optimal for sequential changepoint detection (Moustakides 1986). It accumulates evidence over time — a single handling spike resets the accumulator to zero. With a pre-flight noise floor of ~0.03 m/s and takeoff velocity > 0.5 m/s, SNR is approximately 23.5, giving detection delay of ~40-60ms at 50 Hz.
Data structure:
typedef struct {
uint64_t anchor_usec;
int method; // 1=CUSUM, 2=CUSUM+nav_state, 3=nav_state only
float confidence; // 0.0 - 1.0
float onset_snr;
bool nav_state_corroborated;
} takeoff_anchor_t;
takeoff_anchor_t ulog_replay_detect_takeoff(const ulog_replay_ctx_t *ctx);
Alignment:
for (int i = 0; i < num_replay_files; i++) {
takeoff_anchor_t a = ulog_replay_detect_takeoff(replays[i]);
replays[i].time_offset = anchor_ref - a.anchor_usec;
}
Thresholds:
| Parameter |
Value |
Rationale |
CUSUM_DELTA |
0.5 m/s |
Minimum velocity shift to detect |
CUSUM_H_FACTOR |
5.0 |
Threshold = factor x sigma_0 |
PERSIST_GATE |
500ms |
Handling artifacts last 100-300ms |
NOISE_WINDOW |
5-10s |
Pre-flight noise characterization |
NAV_AGREE_WINDOW |
2.0s |
Max CUSUM-nav_state disagreement |
3. Ghost Mode (--ghost flag)
Without --ghost: All drones render identically — normal swarm replay. Each drone gets its own color from the existing 16-color palette + HSV procedural. No visual hierarchy.
With --ghost: The first loaded file is the opaque reference. All subsequent files render at reduced opacity.
Implementation:
The lighting.fs fragment shader already computes final color per-fragment. Add a uniform float ghostAlpha (default 1.0). For ghost vehicles, set to 0.3-0.5:
// In lighting.fs final line
gl_FragColor = vec4(result, ghostAlpha);
On the C side:
if (ghost_mode && i > 0) { // i > 0 = not the reference drone
float alpha = 0.35f;
SetShaderValue(lighting_shader, loc_ghostAlpha, &alpha, SHADER_UNIFORM_FLOAT);
}
vehicle_draw(&vehicles[i], ...);
if (ghost_mode && i > 0) {
float full = 1.0f;
SetShaderValue(lighting_shader, loc_ghostAlpha, &full, SHADER_UNIFORM_FLOAT);
}
Rendering order: In ghost mode, draw the reference vehicle first, then ghost vehicles, for correct alpha blending. Raylib uses GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA by default.
Trail rendering: Ghost vehicle trails also render at reduced alpha. The trail system already uses per-vertex alpha for fading (vehicle.c:662), so multiply the existing alpha by the ghost factor.
Platform notes: OpenGL alpha blending is identical on Windows, macOS, and Linux. GLSL 330 is the baseline on all three platforms.
macOS note: OpenGL is deprecated but functional through Raylib 5.5 Cocoa framework. The ghost alpha uniform is standard GLSL — no compatibility concerns. If mavsim-viewer migrates to Metal via Raylib backend, the uniform translates directly.
4. Unified Timeline with Per-Drone Markers
The HUD timeline extends to the duration of the longest flight. Each drone gets colored start/end markers on the timeline.
If Drone A ends at 5:00 but Drone B continues to 7:30, the timeline extends to 7:30 with a marker at Drone A's endpoint in Drone A's color.
Timeline extent:
float timeline_duration = 0;
for (int i = 0; i < num_replay_files; i++) {
float dur_i = replays[i].duration_s + replays[i].time_offset / 1e6;
if (dur_i > timeline_duration) timeline_duration = dur_i;
}
Per-drone markers (using each vehicle.color):
- Takeoff anchor — the detected alignment point
- End of flight — last message timestamp + time_offset
- Mode transitions — existing
sys_marker system, offset by time_offset
The existing marker system (sys_marker_times[], sys_marker_labels[]) can be extended per-vehicle. System markers are already generated from mode changes during ulog_replay_init() pre-scan.
When a drone's log ends but the timeline continues, the ended drone's model freezes at its last known position (or disappears — user preference).
5. Confidence & Correlation Display in HUD
When comparison drones are active (pinned via existing Shift+1-9 bindings), display alignment confidence and an optional cross-correlation score below the compass and attitude indicator.
Layout:
+------------+ +------------+
| COMPASS | | ATTITUDE |
+------------+ +------------+
CONF 0.82 CORR 0.91 <-- only when pinned drones active
Implementation:
// After draw_compass() and draw_attitude() in hud_draw()
if (has_pinned_replay_drones) {
float readout_y = inst_y + inst_radius + 8 * s;
float font_sz = 9.0f * s;
Color conf_color = confidence > 0.65f ? green : (confidence > 0.35f ? amber : red);
DrawTextEx(font_label, "CONF", (Vector2){comp_cx - 20*s, readout_y}, font_sz, 1, dim);
DrawTextEx(font_value, TextFormat("%.2f", confidence),
(Vector2){comp_cx - 20*s + 30*s, readout_y}, font_sz, 1, conf_color);
DrawTextEx(font_label, "CORR", (Vector2){adi_cx - 20*s, readout_y}, font_sz, 1, dim);
DrawTextEx(font_value, TextFormat("%.2f", correlation),
(Vector2){adi_cx - 20*s + 30*s, readout_y}, font_sz, 1, corr_color);
}
Uses the same font pair (font_value / font_label) and view-mode accent colors throughout the HUD.
Color coding:
- C > 0.65: green (auto-aligned confidently)
- 0.35 < C <= 0.65: amber (auto-aligned, manual adjustment available)
- C <= 0.35: red (manual alignment recommended)
Integration with Existing Architecture
| Component |
Current State |
Required Change |
sources[] array |
MAX_VEHICLES=129, only sources[0] used for ULog |
Use sources[1..N] for additional ULog files |
vehicles[] array |
Supports 129 vehicles |
No change needed |
ulog_replay_ctx_t |
No time_offset field |
Add int64_t time_offset field |
ulog_replay_advance() |
Uses wall_accum directly |
Add time_offset to target timestamp calc |
mode_changes[] |
Pre-scanned per context |
Already per-context, works as-is |
vehicle_draw() |
Draws all vehicles equally |
Add ghost alpha parameter (only with --ghost) |
lighting.fs shader |
No alpha uniform |
Add uniform float ghostAlpha |
hud_draw() |
Compass + attitude at fixed position |
Add CONF/CORR readout below instruments |
Shift+1-9 bindings |
Toggle pin on secondary vehicles |
No change — works naturally for multi-log |
| Marker system |
128 user + system markers |
Extend with per-vehicle start/end markers |
| Playback controls |
Space/arrows on sources[0] |
Apply to all sources with offset |
| CLI argument parsing |
Single .ulg path |
Accept multiple .ulg paths + --ghost flag |
Platform Considerations
- All platforms: ULog parsing, CUSUM detection, timeline logic, and alignment are pure C math — zero platform-specific code
- Shader changes: GLSL 330 is the baseline on all three platforms (Raylib requires GL 3.3+)
- macOS: OpenGL deprecated but functional through Raylib 5.5 Cocoa framework. Ghost alpha is standard GLSL. Translates to Metal if Raylib backend changes
- Linux: No special considerations.
libm (already linked) provides all math functions. X11/Wayland handled by GLFW/Raylib
- Windows: Winsock2 only used for MAVLink UDP, not file replay. Multi-ULog loading uses standard
fopen/fread
- File paths:
asset_path.c handles platform path differences. Multiple CLI args work identically everywhere
Suggested Phasing
- Phase 1:
ulog_replay_detect_takeoff() — CUSUM detector on velocity energy. Handles 100% of log types (hardware + simulation). ~60-90 lines of C, no dependencies.
- Phase 2: Multi-file loading — accept multiple
.ulg paths, create per-file data_source_t, compute time_offset from Phase 1 anchors.
- Phase 3: Ghost mode —
--ghost flag, shader ghostAlpha uniform, draw order, trail alpha scaling.
- Phase 4: Unified timeline — extend duration to longest log, per-drone start/end markers with vehicle colors.
- Phase 5: HUD confidence/correlation display — CONF/CORR readout below instruments when drones are pinned.
- Phase 6: Manual offset slider — UI override when automatic alignment confidence is low.
Summary
Add the ability to load and replay multiple ULog files simultaneously in a single scene, with automatic temporal alignment at takeoff, a unified timeline, and an optional
--ghostflag that renders comparison drones at reduced opacity. Without--ghost, all drones render equally as a normal swarm replay.Problem
Currently, mavsim-viewer supports only a single ULog file at a time (
sources[0]in replay mode). Comparing two flights requires opening them separately and mentally aligning events. There is no way to:.ulgfiles and replay them in syncThe
ulog_replay.hcomment at lines 110-112 already anticipates this:Proposed Solution
1. Multi-Log Loading
Each additional ULog file gets its own
ulog_replay_ctx_tand occupies a slot in the existingsources[]/vehicles[]arrays (which already supportMAX_VEHICLES = 129).Loading:
data_source_tviadata_source_ulog_create(&sources[i], path)--ghost: all drones render equally as a swarm replay--ghost: first file is the opaque reference, subsequent files render at reduced alphaPlatform notes:
asset_path.cwhich resolves paths correctly on Windows, macOS, and Linuxfopen/fread— fully portablecmd.exe, PowerShell, bash, and zsh2. Automatic Temporal Alignment (Takeoff Sync)
ULog timestamps are microseconds from boot — two logs share no common epoch. Pre-flight data contains sensor noise (GPS wander +/-0.3 m/s, handling spikes, vibration). The method must find a "start of flight" anchor in each log independently.
Method: CUSUM changepoint detection with nav_state corroboration.
Key constraint:
vehicle_statuswithnav_stateis often missing in simulation logs (the parser falls back silently), so kinematic detection must be the primary path, not a fallback.Algorithm
CUSUM is provably optimal for sequential changepoint detection (Moustakides 1986). It accumulates evidence over time — a single handling spike resets the accumulator to zero. With a pre-flight noise floor of ~0.03 m/s and takeoff velocity > 0.5 m/s, SNR is approximately 23.5, giving detection delay of ~40-60ms at 50 Hz.
Data structure:
Alignment:
Thresholds:
CUSUM_DELTACUSUM_H_FACTORPERSIST_GATENOISE_WINDOWNAV_AGREE_WINDOW3. Ghost Mode (
--ghostflag)Without
--ghost: All drones render identically — normal swarm replay. Each drone gets its own color from the existing 16-color palette + HSV procedural. No visual hierarchy.With
--ghost: The first loaded file is the opaque reference. All subsequent files render at reduced opacity.Implementation:
The
lighting.fsfragment shader already computes final color per-fragment. Add auniform float ghostAlpha(default 1.0). For ghost vehicles, set to 0.3-0.5:On the C side:
Rendering order: In ghost mode, draw the reference vehicle first, then ghost vehicles, for correct alpha blending. Raylib uses
GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHAby default.Trail rendering: Ghost vehicle trails also render at reduced alpha. The trail system already uses per-vertex alpha for fading (
vehicle.c:662), so multiply the existing alpha by the ghost factor.Platform notes: OpenGL alpha blending is identical on Windows, macOS, and Linux. GLSL 330 is the baseline on all three platforms.
macOS note: OpenGL is deprecated but functional through Raylib 5.5 Cocoa framework. The ghost alpha uniform is standard GLSL — no compatibility concerns. If mavsim-viewer migrates to Metal via Raylib backend, the uniform translates directly.
4. Unified Timeline with Per-Drone Markers
The HUD timeline extends to the duration of the longest flight. Each drone gets colored start/end markers on the timeline.
If Drone A ends at 5:00 but Drone B continues to 7:30, the timeline extends to 7:30 with a marker at Drone A's endpoint in Drone A's color.
Timeline extent:
Per-drone markers (using each
vehicle.color):sys_markersystem, offset bytime_offsetThe existing marker system (
sys_marker_times[],sys_marker_labels[]) can be extended per-vehicle. System markers are already generated from mode changes duringulog_replay_init()pre-scan.When a drone's log ends but the timeline continues, the ended drone's model freezes at its last known position (or disappears — user preference).
5. Confidence & Correlation Display in HUD
When comparison drones are active (pinned via existing
Shift+1-9bindings), display alignment confidence and an optional cross-correlation score below the compass and attitude indicator.Layout:
Implementation:
Uses the same font pair (
font_value/font_label) and view-mode accent colors throughout the HUD.Color coding:
Integration with Existing Architecture
sources[]arrayMAX_VEHICLES=129, onlysources[0]used for ULogsources[1..N]for additional ULog filesvehicles[]arrayulog_replay_ctx_ttime_offsetfieldint64_t time_offsetfieldulog_replay_advance()wall_accumdirectlytime_offsetto target timestamp calcmode_changes[]vehicle_draw()--ghost)lighting.fsshaderuniform float ghostAlphahud_draw()Shift+1-9bindingssources[0].ulgpath.ulgpaths +--ghostflagPlatform Considerations
libm(already linked) provides all math functions. X11/Wayland handled by GLFW/Raylibfopen/freadasset_path.chandles platform path differences. Multiple CLI args work identically everywhereSuggested Phasing
ulog_replay_detect_takeoff()— CUSUM detector on velocity energy. Handles 100% of log types (hardware + simulation). ~60-90 lines of C, no dependencies..ulgpaths, create per-filedata_source_t, computetime_offsetfrom Phase 1 anchors.--ghostflag, shaderghostAlphauniform, draw order, trail alpha scaling.