From 859797667899ec9c6f4403ea7746c6f7299c3903 Mon Sep 17 00:00:00 2001 From: crosstyan Date: Tue, 24 Mar 2026 10:13:09 +0000 Subject: [PATCH] feat(mcap): add copy mode for multi-camera exports Add an opt-in multi-camera copy layout for zed_svo_to_mcap. copy mode preserves each camera's original timestamps and cadence, writes namespaced /zedN topics without /bundle, and supports common-overlap or full-range export windows. Update the batch wrapper, Python validator, RGBD viewer, and documentation so copy-layout MCAP files are treated as a first-class format rather than invalid bundled output. Validation: - cmake --build build --target zed_svo_to_mcap -j4 - uv run python -m py_compile scripts/zed_batch_svo_to_mcap.py scripts/mcap_bundle_validator.py scripts/mcap_rgbd_viewer.py - build/bin/zed_svo_to_mcap --segment-dir /workspaces/data/kindergarten/bar/2026-03-18T11-59-41 --output /tmp/bar_11-59-41_copy_common.mcap --encoder-device nvidia --depth-mode neural_plus --depth-size optimal --bundle-policy copy --copy-range common - uv run python scripts/mcap_bundle_validator.py /tmp/bar_11-59-41_copy_common.mcap - uv run --extra viewer python scripts/mcap_rgbd_viewer.py /tmp/bar_11-59-41_copy_common.mcap --summary-only --- README.md | 43 +- docs/mcap_layout.md | 46 +- pyproject.toml | 6 + scripts/mcap_bundle_validator.py | 12 +- scripts/mcap_rgbd_viewer.py | 1168 ++++++++++++++++++++++++++++++ scripts/zed_batch_svo_to_mcap.py | 61 +- src/tools/zed_svo_to_mcap.cpp | 653 ++++++++++++----- uv.lock | 42 +- 8 files changed, 1831 insertions(+), 200 deletions(-) create mode 100644 scripts/mcap_rgbd_viewer.py diff --git a/README.md b/README.md index e8d0bcb..3f58de1 100644 --- a/README.md +++ b/README.md @@ -265,12 +265,51 @@ uv run python scripts/zed_batch_svo_to_mcap.py \ The batch MCAP wrapper writes `/.mcap` by default, skips existing outputs unless told otherwise, and returns a nonzero exit code if any segment fails. The repo includes a minimal pose config at `config/zed_pose_config.toml` so MCAP conversion does not depend on a separate `cv-mmap` checkout. -In bundled multi-camera mode, `--start-frame` and `--end-frame` mean the first and last emitted bundle indices from the common start timestamp, inclusive. +In bundled multi-camera timeline mode, `--start-frame` and `--end-frame` mean the first and last emitted bundle indices from the common start timestamp, inclusive. When stderr is attached to a TTY, `zed_batch_svo_to_mcap.py` uses a `progress-table` view by default; otherwise it emits line-oriented start/completion/failure logs plus periodic heartbeat summaries. Use `--progress-ui table` or `--progress-ui text` to override the automatic mode selection. -Bundled MCAP export now defaults to `--bundle-policy nearest`. That mode emits one `/bundle` manifest message per bundle timestamp on the common timeline and keeps the original per-camera timestamps on `/zedN/video`, `/zedN/depth`, and optional `/zedN/pose`. Consumers that care about grouping should follow `/bundle` instead of inferring bundle membership from identical message timestamps. Use `--bundle-policy strict` when you want the older thresholded sync behavior, and `--sync-tolerance-ms` only applies in that strict mode. +Bundled MCAP export now defaults to `--bundle-policy nearest`. That mode emits one `/bundle` manifest message per bundle timestamp on the common timeline and keeps the original per-camera timestamps on `/zedN/video`, `/zedN/depth`, and optional `/zedN/pose`. Faster cameras are sampled onto the slowest common timeline there, so they can end up with the same message count as slower cameras. Consumers that care about grouping should follow `/bundle` instead of inferring bundle membership from identical message timestamps. + +Use `--bundle-policy strict` when you want thresholded grouping; `--sync-tolerance-ms` only applies in that strict mode. Use `--bundle-policy copy` when you want one MCAP containing all camera namespaces with their original per-camera cadence and no `/bundle` manifest. `copy` disables `--start-frame`, `--end-frame`, and `--sync-tolerance-ms`; `--copy-range common|full` controls whether it trims to the overlap window or preserves each camera’s full timestamp range. See [docs/mcap_layout.md](./docs/mcap_layout.md) for the full bundled and single-camera MCAP topic contract. +### MCAP RGBD Viewer + +The repo includes an example RGB+depth viewer at `scripts/mcap_rgbd_viewer.py`. It supports standalone `/camera/*` MCAPs, bundled `/bundle` + `/zedN/*` MCAPs, and multi-camera `copy` MCAPs with namespaced `/zedN/*` topics and no `/bundle`. + +Install the optional viewer dependencies first: + +```bash +uv sync --extra viewer +``` + +Then launch the interactive viewer: + +```bash +uv run --extra viewer python scripts/mcap_rgbd_viewer.py \ + /workspaces/data/kindergarten/bar/2026-03-18T11-59-41/2026-03-18T11-59-41.mcap \ + --camera-label zed1 +``` + +You can also use the same script without a GUI to inspect metadata or render a preview PNG: + +```bash +uv run --extra viewer python scripts/mcap_rgbd_viewer.py \ + --summary-only \ + /workspaces/data/kindergarten/bar/2026-03-18T11-59-41/2026-03-18T11-59-41.mcap +``` + +```bash +uv run --extra viewer python scripts/mcap_rgbd_viewer.py \ + --camera-label zed2 \ + --frame-index 150 \ + --export-preview /tmp/mcap_bundled_gap_preview.png \ + /workspaces/data/kindergarten/throw/2026-03-18T12-58-13/2026-03-18T12-58-13.mcap +``` + +The viewer depends on `ffmpeg` being on `PATH` so it can build a seek-friendly preview cache for H.264/H.265 MCAP video streams. +This is intentionally a simple preview script: it transcodes only the RGB video stream into a temporary intra-frame `mjpeg` cache and then uses that same cache for both scrubbing and normal playback. Depth data is not transcoded to `mjpeg`; it stays in the temporary raw depth cache and is decoded and color-mapped on demand. + ### Why Mixed Hardware/Software Mode Exists Bundled MCAP export opens one video encoder per camera stream. A four-camera segment therefore consumes four H.264/H.265 encoder sessions at once. diff --git a/docs/mcap_layout.md b/docs/mcap_layout.md index 2596eb9..ffcddf0 100644 --- a/docs/mcap_layout.md +++ b/docs/mcap_layout.md @@ -1,9 +1,10 @@ # MCAP Layout -`cvmmap-streamer` writes two related MCAP layouts: +`cvmmap-streamer` writes three related MCAP layouts: - single-camera MCAP export -- bundled multi-camera MCAP export +- bundled multi-camera timeline export +- multi-camera copy export This document covers the topic layout, schema types, and timestamp semantics for both. @@ -40,6 +41,30 @@ Bundled export namespaces each camera stream and adds one bundle manifest topic: `strict` is still available. In strict mode, bundle membership is thresholded by timestamp skew and `--sync-tolerance-ms` applies. In `nearest` mode, `--sync-tolerance-ms` is not used. +Because `nearest` emits on the slowest common timeline, faster cameras can legitimately end up with the same message count as slower cameras in bundled output. + +## Multi-Camera Copy Layout + +`copy` export also namespaces each camera stream under `/zedN/...`, but it does not emit `/bundle`. + +| Topic | Schema / Encoding | Notes | +|------|------|------| +| `/zedN/video` | `foxglove.CompressedVideo` | Per-camera encoded video | +| `/zedN/depth` | `cvmmap_streamer.DepthMap` | Per-camera depth | +| `/zedN/calibration` | `foxglove.CameraCalibration` | Per-camera video intrinsics | +| `/zedN/depth_calibration` | `foxglove.CameraCalibration` | Written only when exported depth resolution differs from video | +| `/zedN/pose` | `foxglove.PoseInFrame` | Optional per-camera pose | +| `/zedN/body` | raw `cvmmap.body_tracking.v1` | Optional raw body packets; see [mcap_body_tracking.md](./mcap_body_tracking.md) | + +`copy` preserves each camera topic exactly as an independent stream inside one MCAP: + +- no `/bundle` topic +- no shared bundle index +- no resampling to a common timeline +- original per-camera timestamps and cadence are preserved + +`--copy-range common` trims each camera to the common overlap window without resampling. `--copy-range full` preserves each camera’s full readable timestamp range from the grouped segment. + ## Bundle Manifest Contract `/bundle` is the authoritative grouping contract for bundled MCAP files. Consumers should not infer grouping from identical MCAP `logTime` values or from matching per-camera timestamps. @@ -76,6 +101,8 @@ The bundled MCAP contract intentionally separates bundle time from per-camera sa This means a single bundle can legitimately contain different per-camera timestamps, especially in `nearest` mode. +`copy` has no separate bundle time. Its `/zedN/video`, `/zedN/depth`, and `/zedN/pose` messages all use the original per-camera sample timestamp directly. + ## Corruption And Partial Bundles Bundled `nearest` export is resilient to ZED `CORRUPTED FRAME` runs: @@ -91,6 +118,13 @@ Bundled `strict` export stays strict: - corruption is skipped internally until recovery - only fully present, threshold-qualified groups are emitted +`copy` is also resilient to ZED `CORRUPTED FRAME` runs: + +- unreadable tail frames are treated as end-of-stream +- mid-stream corruption is skipped until a readable frame is found +- there is no placeholder or manifest entry because `copy` has no grouping contract +- the affected camera topic simply resumes at the recovered readable frame + ## Validation Expectations For single-camera MCAP files, the current validation contract is: @@ -111,4 +145,10 @@ For bundled MCAP files, the current validation contract is: That is why a partially written MCAP with topic presence but mismatched counts is treated as invalid. -The repository-level Python helper [scripts/mcap_bundle_validator.py](../scripts/mcap_bundle_validator.py) now understands both layouts and reports which one it found before applying the corresponding validation rules. +For multi-camera `copy` MCAP files, the current validation contract is: + +- `/bundle` must not exist +- each camera must have `/zedN/video`, `/zedN/depth`, and `/zedN/calibration` +- for each camera, `/zedN/video` and `/zedN/depth` message counts must match + +The repository-level Python helper [scripts/mcap_bundle_validator.py](../scripts/mcap_bundle_validator.py) now understands all three layouts and reports which one it found before applying the corresponding validation rules. diff --git a/pyproject.toml b/pyproject.toml index 88ab608..8ba0701 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -12,5 +12,11 @@ dependencies = [ "zstandard>=0.23", ] +[project.optional-dependencies] +viewer = [ + "dearpygui>=2.2", + "rvl-impl @ git+https://github.com/crosstyan/rvl-impl.git@74308bcaf184cb39428237e8f4f99a67a6de22d9 ; python_version >= '3.12'", +] + [tool.uv] package = false diff --git a/scripts/mcap_bundle_validator.py b/scripts/mcap_bundle_validator.py index 40624ec..a13953e 100644 --- a/scripts/mcap_bundle_validator.py +++ b/scripts/mcap_bundle_validator.py @@ -112,7 +112,7 @@ def record_single_camera_topic( def probe_single_camera_output(path: Path) -> batch.OutputProbeResult: - base_probe = batch.probe_output(path, ("camera",), bundle_topic=None) + base_probe = batch.probe_output(path, ("camera",), layout="single-camera", bundle_topic=None) if base_probe.status != "valid": return base_probe @@ -210,6 +210,7 @@ def summarize_mcap(path: Path) -> McapSummary: camera_labels: set[str] = set() saw_single_camera_topic = False saw_namespaced_camera_topic = False + saw_bundle_manifest = False with path.open("rb") as stream: reader = reader_module.make_reader(stream) @@ -218,6 +219,7 @@ def summarize_mcap(path: Path) -> McapSummary: schema_name = schema.name if schema is not None else None if topic == BUNDLE_TOPIC: summary.layout = "bundled" + saw_bundle_manifest = True if schema is None or schema.name != "cvmmap_streamer.BundleManifest": summary.validation_status = "invalid" summary.validation_reason = f"bundle topic '{BUNDLE_TOPIC}' is missing the BundleManifest schema" @@ -257,7 +259,7 @@ def summarize_mcap(path: Path) -> McapSummary: continue saw_namespaced_camera_topic = True if summary.layout == "unknown": - summary.layout = "bundled" + summary.layout = "copy" camera_labels.add(label) stats = summary.camera_stats.setdefault(label, CameraSummary()) if stream_kind == "video": @@ -276,9 +278,12 @@ def summarize_mcap(path: Path) -> McapSummary: if saw_single_camera_topic and saw_namespaced_camera_topic: summary.layout = "mixed" summary.validation_status = "invalid" - summary.validation_reason = "MCAP mixes single-camera and bundled topic layouts" + summary.validation_reason = "MCAP mixes single-camera and multi-camera topic layouts" return summary + if saw_namespaced_camera_topic and not saw_bundle_manifest and summary.layout == "bundled": + summary.layout = "copy" + if summary.layout == "single-camera": summary.camera_labels = ("camera",) probe = probe_single_camera_output(path) @@ -294,6 +299,7 @@ def summarize_mcap(path: Path) -> McapSummary: probe = batch.probe_output( path, summary.camera_labels, + layout=summary.layout, bundle_topic=BUNDLE_TOPIC if summary.layout == "bundled" else None, ) summary.validation_status = probe.status diff --git a/scripts/mcap_rgbd_viewer.py b/scripts/mcap_rgbd_viewer.py new file mode 100644 index 0000000..6a56cca --- /dev/null +++ b/scripts/mcap_rgbd_viewer.py @@ -0,0 +1,1168 @@ +#!/usr/bin/env python3 + +from __future__ import annotations + +import contextlib +import importlib +import subprocess +import sys +import tempfile +import time +from collections import deque +from dataclasses import dataclass +from pathlib import Path +from typing import BinaryIO + +import click +import cv2 +import numpy as np +from google.protobuf import descriptor_pb2, descriptor_pool, message_factory, timestamp_pb2 + +import zed_batch_svo_to_mcap as batch + + +SCRIPT_PATH = Path(__file__).resolve() +REPO_ROOT = SCRIPT_PATH.parents[1] +WORKSPACE_ROOT = REPO_ROOT.parent +MCAP_PYTHON_ROOT = WORKSPACE_ROOT / "mcap" / "python" / "mcap" +if str(SCRIPT_PATH.parent) not in sys.path: + sys.path.insert(0, str(SCRIPT_PATH.parent)) +if str(MCAP_PYTHON_ROOT) not in sys.path: + sys.path.insert(0, str(MCAP_PYTHON_ROOT)) + + +BUNDLE_TOPIC = "/bundle" +SINGLE_CAMERA_LABEL = "camera" +DISPLAY_WIDTH = 720 +DISPLAY_HEIGHT = 420 +TEXT_LINE_HEIGHT = 28 +WINDOW_PADDING = 24 +METADATA_PANEL_WIDTH = 380 +VIEWPORT_WIDTH = DISPLAY_WIDTH * 2 + METADATA_PANEL_WIDTH + WINDOW_PADDING * 4 +VIEWPORT_HEIGHT = DISPLAY_HEIGHT + 260 +FRAME_SLIDER_DEBOUNCE_SECONDS = 0.08 +PLAYBACK_FPS_WARNING_RATIO = 0.9 +PLAYBACK_FPS_WARNING_ABS_TOLERANCE = 1.0 +PLAYBACK_FPS_WINDOW_SECONDS = 2.0 + +_MCAP_READER_MODULE = None +_MESSAGE_CLASS_CACHE: dict[tuple[bytes, str], object] = {} +DEPTH_PALETTE_TO_OPENCV = { + "Gray": None, + "Turbo": cv2.COLORMAP_TURBO, + "Inferno": cv2.COLORMAP_INFERNO, + "Plasma": cv2.COLORMAP_PLASMA, + "Viridis": cv2.COLORMAP_VIRIDIS, + "Cividis": cv2.COLORMAP_CIVIDIS, + "Magma": cv2.COLORMAP_MAGMA, + "Parula": cv2.COLORMAP_PARULA, +} + + +@dataclass(slots=True, frozen=True) +class CalibrationInfo: + width: int + height: int + + +@dataclass(slots=True, frozen=True) +class VideoFrameInfo: + timestamp_ns: int + + +@dataclass(slots=True, frozen=True) +class DepthFrameInfo: + timestamp_ns: int + offset: int + length: int + width: int + height: int + encoding_name: str + source_unit_name: str + storage_unit_name: str + + +@dataclass(slots=True, frozen=True) +class BundleSlot: + bundle_index: int + bundle_timestamp_ns: int + status_name: str + corrupted_frames_skipped: int + sample_timestamp_ns: int | None + video_index: int | None + depth_index: int | None + + +@dataclass(slots=True) +class McapLayoutInfo: + path: Path + layout: str + camera_labels: tuple[str, ...] + bundled_policy_counts: dict[str, int] + + +@dataclass(slots=True) +class CameraViewState: + mcap_path: Path + layout: str + camera_label: str + video_format: str | None + video_frames: list[VideoFrameInfo] + depth_frames: list[DepthFrameInfo] + slots: list[BundleSlot] + video_calibration: CalibrationInfo | None + depth_calibration: CalibrationInfo | None + preview_video_path: Path | None + depth_cache_path: Path + temp_dir: tempfile.TemporaryDirectory[str] + + def close(self) -> None: + self.temp_dir.cleanup() + + +@dataclass(slots=True) +class RenderedSlot: + rgb_bgr: np.ndarray + depth_bgr: np.ndarray + title: str + metadata_lines: list[str] + + +def load_mcap_reader(): + global _MCAP_READER_MODULE + if _MCAP_READER_MODULE is not None: + return _MCAP_READER_MODULE + if str(MCAP_PYTHON_ROOT) not in sys.path: + sys.path.insert(0, str(MCAP_PYTHON_ROOT)) + _MCAP_READER_MODULE = importlib.import_module("mcap.reader") + return _MCAP_READER_MODULE + + +def load_message_class(schema_data: bytes, message_type_name: str): + cache_key = (schema_data, message_type_name) + cached = _MESSAGE_CLASS_CACHE.get(cache_key) + if cached is not None: + return cached + + descriptor_set = descriptor_pb2.FileDescriptorSet() + descriptor_set.ParseFromString(schema_data) + pool = descriptor_pool.DescriptorPool() + has_embedded_timestamp = any( + file_descriptor.name == "google/protobuf/timestamp.proto" + for file_descriptor in descriptor_set.file + ) + if has_embedded_timestamp: + for file_descriptor in descriptor_set.file: + if file_descriptor.name == "google/protobuf/timestamp.proto": + pool.Add(file_descriptor) + break + else: + pool.AddSerializedFile(timestamp_pb2.DESCRIPTOR.serialized_pb) + for file_descriptor in descriptor_set.file: + if file_descriptor.name == "google/protobuf/timestamp.proto": + continue + pool.Add(file_descriptor) + + message_descriptor = pool.FindMessageTypeByName(message_type_name) + message_class = message_factory.GetMessageClass(message_descriptor) + _MESSAGE_CLASS_CACHE[cache_key] = message_class + return message_class + + +def parse_timestamp_ns(timestamp_message: object, fallback_log_time_ns: int) -> int: + seconds = int(getattr(timestamp_message, "seconds", 0)) + nanos = int(getattr(timestamp_message, "nanos", 0)) + if seconds == 0 and nanos == 0: + return fallback_log_time_ns + return seconds * 1_000_000_000 + nanos + + +def format_timestamp_ns(timestamp_ns: int | None) -> str: + if timestamp_ns is None: + return "-" + seconds, nanos = divmod(timestamp_ns, 1_000_000_000) + return f"{seconds}.{nanos:09d}" + + +def enum_name(message: object, field_name: str) -> str: + field_descriptor = message.DESCRIPTOR.fields_by_name[field_name] + value = int(getattr(message, field_name)) + resolved = field_descriptor.enum_type.values_by_number.get(value) + return resolved.name if resolved is not None else str(value) + + +def is_present_status(status_name: str) -> bool: + return status_name in {"PRESENT", "BUNDLE_MEMBER_STATUS_PRESENT"} + + +def is_corrupted_gap_status(status_name: str) -> bool: + return status_name in {"CORRUPTED_GAP", "BUNDLE_MEMBER_STATUS_CORRUPTED_GAP"} + + +def infer_layout(path: Path) -> McapLayoutInfo: + reader_module = load_mcap_reader() + camera_labels: set[str] = set() + bundled_policy_counts: dict[str, int] = {} + saw_single = False + saw_bundled = False + saw_bundle_manifest = False + + with path.open("rb") as stream: + reader = reader_module.make_reader(stream) + for schema, channel, message in reader.iter_messages(): + topic = channel.topic + if topic.startswith("/camera/"): + saw_single = True + continue + if topic == BUNDLE_TOPIC: + saw_bundled = True + saw_bundle_manifest = True + if schema is None or schema.name != "cvmmap_streamer.BundleManifest": + continue + bundle_class, _ = batch.load_bundle_manifest_type(schema.data) + bundle = bundle_class() + bundle.ParseFromString(message.data) + for member in bundle.members: + camera_labels.add(str(member.camera_label)) + policy_name = enum_name(bundle, "policy") + bundled_policy_counts[policy_name] = bundled_policy_counts.get(policy_name, 0) + 1 + continue + if topic.count("/") == 2 and topic.startswith("/"): + label = topic.split("/")[1] + if label and label != "camera": + saw_bundled = True + camera_labels.add(label) + + if saw_single and saw_bundled: + raise click.ClickException("MCAP mixes single-camera and multi-camera topics") + if saw_single: + return McapLayoutInfo( + path=path, + layout="single-camera", + camera_labels=(SINGLE_CAMERA_LABEL,), + bundled_policy_counts=bundled_policy_counts, + ) + if saw_bundled and camera_labels: + return McapLayoutInfo( + path=path, + layout="bundled" if saw_bundle_manifest else "copy", + camera_labels=tuple(sorted(camera_labels)), + bundled_policy_counts=bundled_policy_counts, + ) + raise click.ClickException(f"could not infer a supported MCAP layout from {path}") + + +def topic_for(layout: str, camera_label: str, kind: str) -> str: + if layout == "single-camera": + return f"/camera/{kind}" + return f"/{camera_label}/{kind}" + + +def build_preview_video( + ffmpeg_bin: str, + raw_video_path: Path, + video_format: str, + preview_width: int, + temp_dir: Path, +) -> Path: + input_format = {"h264": "h264", "h265": "hevc"}[video_format] + # This script uses one simple RGB preview path for both sequential playback and + # random-access scrubbing, so it builds an intra-frame MJPEG cache first. + preview_path = temp_dir / "preview.avi" + command = [ + ffmpeg_bin, + "-hide_banner", + "-loglevel", + "error", + "-y", + "-fflags", + "+genpts", + "-f", + input_format, + "-i", + str(raw_video_path), + "-vf", + f"scale=min(iw\\,{preview_width}):-2:flags=lanczos", + "-c:v", + "mjpeg", + "-q:v", + "3", + str(preview_path), + ] + completed = subprocess.run(command, check=False, capture_output=True, text=True) + if completed.returncode != 0: + reason = completed.stderr.strip() or completed.stdout.strip() or "ffmpeg failed to build preview cache" + raise click.ClickException(reason) + return preview_path + + +def read_camera_state( + path: Path, + *, + layout_info: McapLayoutInfo, + camera_label: str, + ffmpeg_bin: str, + preview_width: int, +) -> CameraViewState: + reader_module = load_mcap_reader() + temp_dir = tempfile.TemporaryDirectory(prefix="mcap_rgbd_viewer_") + temp_root = Path(temp_dir.name) + raw_video_path = temp_root / "stream.bin" + depth_cache_path = temp_root / "depth.cache" + + video_topic = topic_for(layout_info.layout, camera_label, "video") + depth_topic = topic_for(layout_info.layout, camera_label, "depth") + calibration_topic = topic_for(layout_info.layout, camera_label, "calibration") + depth_calibration_topic = topic_for(layout_info.layout, camera_label, "depth_calibration") + + video_frames: list[VideoFrameInfo] = [] + depth_frames: list[DepthFrameInfo] = [] + bundle_members: list[tuple[int, int, str, int, int | None]] = [] + video_format: str | None = None + video_calibration: CalibrationInfo | None = None + depth_calibration: CalibrationInfo | None = None + + with raw_video_path.open("wb") as video_stream, depth_cache_path.open("wb") as depth_stream: + with path.open("rb") as stream: + reader = reader_module.make_reader(stream) + for schema, channel, message in reader.iter_messages(): + topic = channel.topic + if topic == video_topic: + if schema is None or schema.name != "foxglove.CompressedVideo": + raise click.ClickException(f"unexpected schema on {video_topic}: {schema.name if schema else 'none'}") + message_class = load_message_class(schema.data, "foxglove.CompressedVideo") + payload = message_class() + payload.ParseFromString(message.data) + frame_format = str(payload.format) + if frame_format not in {"h264", "h265"}: + raise click.ClickException(f"unsupported video format '{frame_format}' on {video_topic}") + if video_format is None: + video_format = frame_format + elif frame_format != video_format: + raise click.ClickException( + f"inconsistent video format on {video_topic}: {video_format} then {frame_format}" + ) + video_stream.write(payload.data) + video_frames.append( + VideoFrameInfo( + timestamp_ns=parse_timestamp_ns(payload.timestamp, int(message.log_time)), + ) + ) + continue + + if topic == depth_topic: + if schema is None or schema.name != "cvmmap_streamer.DepthMap": + raise click.ClickException(f"unexpected schema on {depth_topic}: {schema.name if schema else 'none'}") + message_class = load_message_class(schema.data, "cvmmap_streamer.DepthMap") + payload = message_class() + payload.ParseFromString(message.data) + offset = depth_stream.tell() + depth_bytes = bytes(payload.data) + depth_stream.write(depth_bytes) + depth_frames.append( + DepthFrameInfo( + timestamp_ns=parse_timestamp_ns(payload.timestamp, int(message.log_time)), + offset=offset, + length=len(depth_bytes), + width=int(payload.width), + height=int(payload.height), + encoding_name=enum_name(payload, "encoding"), + source_unit_name=enum_name(payload, "source_unit"), + storage_unit_name=enum_name(payload, "storage_unit"), + ) + ) + continue + + if topic == calibration_topic: + if schema is None or schema.name != "foxglove.CameraCalibration": + continue + message_class = load_message_class(schema.data, "foxglove.CameraCalibration") + payload = message_class() + payload.ParseFromString(message.data) + if video_calibration is None: + video_calibration = CalibrationInfo(width=int(payload.width), height=int(payload.height)) + continue + + if topic == depth_calibration_topic: + if schema is None or schema.name != "foxglove.CameraCalibration": + continue + message_class = load_message_class(schema.data, "foxglove.CameraCalibration") + payload = message_class() + payload.ParseFromString(message.data) + if depth_calibration is None: + depth_calibration = CalibrationInfo(width=int(payload.width), height=int(payload.height)) + continue + + if layout_info.layout == "bundled" and topic == BUNDLE_TOPIC: + if schema is None or schema.name != "cvmmap_streamer.BundleManifest": + continue + bundle_class, present_value = batch.load_bundle_manifest_type(schema.data) + bundle = bundle_class() + bundle.ParseFromString(message.data) + for member in bundle.members: + if str(member.camera_label) != camera_label: + continue + status_name = "PRESENT" if member.HasField("timestamp") else "UNKNOWN" + if present_value is not None: + field_descriptor = member.DESCRIPTOR.fields_by_name["status"] + enum_value = field_descriptor.enum_type.values_by_number.get(int(member.status)) + status_name = enum_value.name if enum_value is not None else str(member.status) + sample_timestamp_ns = None + if member.HasField("timestamp"): + sample_timestamp_ns = parse_timestamp_ns(member.timestamp, int(message.log_time)) + bundle_members.append( + ( + int(bundle.bundle_index), + parse_timestamp_ns(bundle.timestamp, int(message.log_time)), + status_name, + int(getattr(member, "corrupted_frames_skipped", 0)), + sample_timestamp_ns, + ) + ) + break + + preview_video_path: Path | None = None + if video_format is not None and video_frames: + suffix = ".h265" if video_format == "h265" else ".h264" + renamed_raw_video_path = raw_video_path.with_suffix(suffix) + raw_video_path.replace(renamed_raw_video_path) + preview_video_path = build_preview_video( + ffmpeg_bin=ffmpeg_bin, + raw_video_path=renamed_raw_video_path, + video_format=video_format, + preview_width=preview_width, + temp_dir=temp_root, + ) + + slots: list[BundleSlot] = [] + if layout_info.layout == "bundled" and bundle_members: + present_cursor = 0 + usable_present_frames = min(len(video_frames), len(depth_frames)) + for bundle_index, bundle_timestamp_ns, status_name, corrupted_frames_skipped, sample_timestamp_ns in bundle_members: + video_index: int | None = None + depth_index: int | None = None + if is_present_status(status_name) and present_cursor < usable_present_frames: + video_index = present_cursor + depth_index = present_cursor + present_cursor += 1 + slots.append( + BundleSlot( + bundle_index=bundle_index, + bundle_timestamp_ns=bundle_timestamp_ns, + status_name=status_name, + corrupted_frames_skipped=corrupted_frames_skipped, + sample_timestamp_ns=sample_timestamp_ns, + video_index=video_index, + depth_index=depth_index, + ) + ) + else: + paired_frames = min(len(video_frames), len(depth_frames)) + slots = [ + BundleSlot( + bundle_index=index, + bundle_timestamp_ns=video_frames[index].timestamp_ns, + status_name="PRESENT", + corrupted_frames_skipped=0, + sample_timestamp_ns=video_frames[index].timestamp_ns, + video_index=index, + depth_index=index, + ) + for index in range(paired_frames) + ] + + if not slots: + raise click.ClickException(f"no viewable RGB+depth pairs found for camera '{camera_label}'") + + return CameraViewState( + mcap_path=path, + layout=layout_info.layout, + camera_label=camera_label, + video_format=video_format, + video_frames=video_frames, + depth_frames=depth_frames, + slots=slots, + video_calibration=video_calibration, + depth_calibration=depth_calibration, + preview_video_path=preview_video_path, + depth_cache_path=depth_cache_path, + temp_dir=temp_dir, + ) + + +def render_placeholder(text: str) -> np.ndarray: + canvas = np.zeros((DISPLAY_HEIGHT, DISPLAY_WIDTH, 3), dtype=np.uint8) + cv2.putText( + canvas, + text, + (40, DISPLAY_HEIGHT // 2), + cv2.FONT_HERSHEY_SIMPLEX, + 1.0, + (255, 255, 255), + 2, + cv2.LINE_AA, + ) + return canvas + + +def fit_to_panel(frame_bgr: np.ndarray) -> np.ndarray: + src_height, src_width = frame_bgr.shape[:2] + scale = min(DISPLAY_WIDTH / src_width, DISPLAY_HEIGHT / src_height) + resized_width = max(1, int(round(src_width * scale))) + resized_height = max(1, int(round(src_height * scale))) + resized = cv2.resize(frame_bgr, (resized_width, resized_height), interpolation=cv2.INTER_AREA) + canvas = np.zeros((DISPLAY_HEIGHT, DISPLAY_WIDTH, 3), dtype=np.uint8) + x_offset = (DISPLAY_WIDTH - resized_width) // 2 + y_offset = (DISPLAY_HEIGHT - resized_height) // 2 + canvas[y_offset : y_offset + resized_height, x_offset : x_offset + resized_width] = resized + return canvas + + +def read_video_frame( + preview_video_path: Path | None, + video_index: int | None, + *, + capture: cv2.VideoCapture | None = None, +) -> np.ndarray: + if preview_video_path is None or video_index is None: + return render_placeholder("NO VIDEO") + created_capture = False + if capture is None: + capture = cv2.VideoCapture(str(preview_video_path)) + created_capture = True + if not capture.isOpened(): + raise click.ClickException(f"OpenCV could not open preview cache {preview_video_path}") + try: + capture.set(cv2.CAP_PROP_POS_FRAMES, float(video_index)) + ok, frame = capture.read() + finally: + if created_capture: + capture.release() + if not ok or frame is None: + return render_placeholder("VIDEO SEEK FAILED") + return fit_to_panel(frame) + + +def decode_depth_frame( + state: CameraViewState, + depth_index: int | None, + *, + depth_min_m: float, + depth_max_m: float, + depth_palette_name: str, + depth_cache_stream: BinaryIO | None = None, +) -> np.ndarray: + if depth_index is None: + return render_placeholder("NO DEPTH") + try: + import rvl + except ModuleNotFoundError as error: + raise click.ClickException( + "the viewer needs the optional rvl-impl binding; run `uv sync --extra viewer`" + ) from error + + ref = state.depth_frames[depth_index] + if depth_cache_stream is None: + with state.depth_cache_path.open("rb") as stream: + stream.seek(ref.offset) + payload = stream.read(ref.length) + else: + depth_cache_stream.seek(ref.offset) + payload = depth_cache_stream.read(ref.length) + + if ref.encoding_name == "RVL_U16_LOSSLESS": + depth = rvl.decompress_u16(payload).astype(np.float32) + if ref.storage_unit_name == "STORAGE_UNIT_MILLIMETER" or ref.source_unit_name == "DEPTH_UNIT_MILLIMETER": + depth_m = depth / 1000.0 + else: + depth_m = depth + elif ref.encoding_name == "RVL_F32": + depth_m = rvl.decompress_f32(payload).astype(np.float32) + else: + return render_placeholder(ref.encoding_name) + + valid = np.isfinite(depth_m) & (depth_m > 0.0) + span = max(depth_max_m - depth_min_m, 1e-6) + clipped = np.clip((depth_m - depth_min_m) / span, 0.0, 1.0) + normalized = np.zeros(depth_m.shape, dtype=np.uint8) + normalized[valid] = np.round((1.0 - clipped[valid]) * 255.0).astype(np.uint8) + colormap = DEPTH_PALETTE_TO_OPENCV[depth_palette_name] + if colormap is None: + colored = cv2.cvtColor(normalized, cv2.COLOR_GRAY2BGR) + else: + colored = cv2.applyColorMap(normalized, colormap) + colored[~valid] = 0 + return fit_to_panel(colored) + + +def build_metadata_lines( + state: CameraViewState, + slot: BundleSlot, + *, + depth_min_m: float, + depth_max_m: float, + depth_palette_name: str, +) -> list[str]: + lines = [ + f"file: {state.mcap_path.name}", + f"layout: {state.layout}", + f"camera: {state.camera_label}", + f"slots: {len(state.slots)}", + f"video frames: {len(state.video_frames)}", + f"depth frames: {len(state.depth_frames)}", + f"bundle/frame index: {slot.bundle_index}", + f"bundle ts: {format_timestamp_ns(slot.bundle_timestamp_ns)}", + f"sample ts: {format_timestamp_ns(slot.sample_timestamp_ns)}", + f"status: {slot.status_name}", + ] + if slot.corrupted_frames_skipped: + lines.append(f"corrupted frames skipped: {slot.corrupted_frames_skipped}") + if state.video_format is not None: + lines.append(f"video format: {state.video_format}") + if state.video_calibration is not None: + lines.append(f"video calib: {state.video_calibration.width}x{state.video_calibration.height}") + if state.depth_calibration is not None: + lines.append(f"depth calib: {state.depth_calibration.width}x{state.depth_calibration.height}") + elif slot.depth_index is not None: + ref = state.depth_frames[slot.depth_index] + lines.append(f"depth frame: {ref.width}x{ref.height} {ref.encoding_name}") + lines.append(f"depth range: {depth_min_m:.2f}m .. {depth_max_m:.2f}m") + lines.append(f"depth palette: {depth_palette_name}") + return lines + + +def render_slot( + state: CameraViewState, + slot_index: int, + *, + depth_min_m: float, + depth_max_m: float, + depth_palette_name: str, + preview_capture: cv2.VideoCapture | None = None, + depth_cache_stream: BinaryIO | None = None, +) -> RenderedSlot: + slot = state.slots[slot_index] + if is_corrupted_gap_status(slot.status_name): + rgb_frame = render_placeholder("CORRUPTED GAP") + depth_frame = render_placeholder("CORRUPTED GAP") + else: + rgb_frame = read_video_frame(state.preview_video_path, slot.video_index, capture=preview_capture) + depth_frame = decode_depth_frame( + state, + slot.depth_index, + depth_min_m=depth_min_m, + depth_max_m=depth_max_m, + depth_palette_name=depth_palette_name, + depth_cache_stream=depth_cache_stream, + ) + + title = ( + f"{state.camera_label} " + f"{'bundle' if state.layout == 'bundled' else 'frame'}={slot.bundle_index} " + f"status={slot.status_name}" + ) + return RenderedSlot( + rgb_bgr=rgb_frame, + depth_bgr=depth_frame, + title=title, + metadata_lines=build_metadata_lines( + state, + slot, + depth_min_m=depth_min_m, + depth_max_m=depth_max_m, + depth_palette_name=depth_palette_name, + ), + ) + + +def compose_preview_image(rendered: RenderedSlot) -> np.ndarray: + banner_height = 64 + banner = np.zeros((banner_height, DISPLAY_WIDTH * 2, 3), dtype=np.uint8) + cv2.putText( + banner, + rendered.title, + (16, 40), + cv2.FONT_HERSHEY_SIMPLEX, + 0.8, + (255, 255, 255), + 2, + cv2.LINE_AA, + ) + pair = np.concatenate([rendered.rgb_bgr, rendered.depth_bgr], axis=1) + return np.concatenate([banner, pair], axis=0) + + +def print_summary(layout_info: McapLayoutInfo, state: CameraViewState) -> None: + click.echo(f"path: {state.mcap_path}") + click.echo(f"layout: {layout_info.layout}") + click.echo(f"camera labels: {', '.join(layout_info.camera_labels)}") + if layout_info.bundled_policy_counts: + policy_text = ", ".join( + f"{policy}={count}" + for policy, count in sorted(layout_info.bundled_policy_counts.items()) + ) + click.echo(f"bundle policies: {policy_text}") + click.echo(f"selected camera: {state.camera_label}") + click.echo(f"viewable slots: {len(state.slots)}") + click.echo(f"video frames: {len(state.video_frames)}") + click.echo(f"depth frames: {len(state.depth_frames)}") + if state.video_format is not None: + click.echo(f"video format: {state.video_format}") + if state.video_calibration is not None: + click.echo(f"video calibration: {state.video_calibration.width}x{state.video_calibration.height}") + if state.depth_calibration is not None: + click.echo(f"depth calibration: {state.depth_calibration.width}x{state.depth_calibration.height}") + if state.slots: + click.echo(f"first slot timestamp: {format_timestamp_ns(state.slots[0].bundle_timestamp_ns)}") + click.echo(f"last slot timestamp: {format_timestamp_ns(state.slots[-1].bundle_timestamp_ns)}") + corrupted_gap_count = sum(1 for slot in state.slots if is_corrupted_gap_status(slot.status_name)) + if corrupted_gap_count: + click.echo(f"corrupted gap slots: {corrupted_gap_count}") + + +def write_preview_image( + state: CameraViewState, + output_path: Path, + frame_index: int, + depth_min_m: float, + depth_max_m: float, + depth_palette_name: str, +) -> None: + if frame_index < 0 or frame_index >= len(state.slots): + raise click.ClickException(f"--frame-index {frame_index} is outside 0..{len(state.slots) - 1}") + rendered = render_slot( + state, + frame_index, + depth_min_m=depth_min_m, + depth_max_m=depth_max_m, + depth_palette_name=depth_palette_name, + ) + preview = compose_preview_image(rendered) + output_path.parent.mkdir(parents=True, exist_ok=True) + if not cv2.imwrite(str(output_path), preview): + raise click.ClickException(f"failed to write preview image to {output_path}") + click.echo(f"wrote preview: {output_path}") + + +def slot_target_timestamp_ns(slot: BundleSlot) -> int: + return slot.sample_timestamp_ns if slot.sample_timestamp_ns is not None else slot.bundle_timestamp_ns + + +def nearest_slot_index(slots: list[BundleSlot], target_timestamp_ns: int) -> int: + if not slots: + return 0 + return min( + range(len(slots)), + key=lambda index: abs(slot_target_timestamp_ns(slots[index]) - target_timestamp_ns), + ) + + +def bgr_to_texture(frame_bgr: np.ndarray) -> np.ndarray: + rgba = cv2.cvtColor(frame_bgr, cv2.COLOR_BGR2RGBA) + return np.ascontiguousarray(rgba, dtype=np.float32) / 255.0 + + +class ViewerApp: + def __init__( + self, + *, + mcap_path: Path, + layout_info: McapLayoutInfo, + initial_state: CameraViewState, + ffmpeg_bin: str, + preview_width: int, + depth_min_m: float, + depth_max_m: float, + ) -> None: + try: + import dearpygui.dearpygui as dpg + except ModuleNotFoundError as error: + raise click.ClickException( + "the GUI viewer needs DearPyGui; run `uv sync --extra viewer` first" + ) from error + + self.dpg = dpg + self.mcap_path = mcap_path + self.layout_info = layout_info + self.state = initial_state + self.ffmpeg_bin = ffmpeg_bin + self.preview_width = preview_width + self.depth_min_m = depth_min_m + self.depth_max_m = depth_max_m + self.depth_palette_name = "Turbo" + self.current_index = 0 + self.pending_index: int | None = None + self.pending_index_requested_at = 0.0 + self.playing = False + self.playback_fps = 15.0 + self.next_playback_deadline = time.monotonic() + self.playback_progress_samples: deque[tuple[float, int]] = deque() + self.playback_advanced_frames = 0 + self.actual_playback_fps = 0.0 + self.preview_capture: cv2.VideoCapture | None = None + self.depth_cache_stream: BinaryIO | None = None + self.open_state_resources() + + def open_state_resources(self) -> None: + if self.state.preview_video_path is not None: + capture = cv2.VideoCapture(str(self.state.preview_video_path)) + if not capture.isOpened(): + capture.release() + raise click.ClickException(f"OpenCV could not open preview cache {self.state.preview_video_path}") + self.preview_capture = capture + else: + self.preview_capture = None + self.depth_cache_stream = self.state.depth_cache_path.open("rb") + + def close_state_resources(self) -> None: + if self.preview_capture is not None: + self.preview_capture.release() + self.preview_capture = None + if self.depth_cache_stream is not None: + self.depth_cache_stream.close() + self.depth_cache_stream = None + + def replace_state(self, camera_label: str) -> None: + source_index = self.pending_index if self.pending_index is not None else self.current_index + source_index = max(0, min(source_index, len(self.state.slots) - 1)) + target_timestamp_ns = slot_target_timestamp_ns(self.state.slots[source_index]) + new_state = read_camera_state( + self.mcap_path, + layout_info=self.layout_info, + camera_label=camera_label, + ffmpeg_bin=self.ffmpeg_bin, + preview_width=self.preview_width, + ) + self.close_state_resources() + self.state.close() + self.state = new_state + self.open_state_resources() + self.current_index = nearest_slot_index(self.state.slots, target_timestamp_ns) + self.pending_index = None + self.next_playback_deadline = time.monotonic() + 1.0 / max(self.playback_fps, 1.0) + self.reset_playback_metrics() + self.dpg.configure_item("frame_slider", max_value=max(0, len(self.state.slots) - 1)) + self.refresh() + + def refresh(self) -> None: + rendered = render_slot( + self.state, + self.current_index, + depth_min_m=self.depth_min_m, + depth_max_m=self.depth_max_m, + depth_palette_name=self.depth_palette_name, + preview_capture=self.preview_capture, + depth_cache_stream=self.depth_cache_stream, + ) + self.dpg.set_value("rgb_texture", bgr_to_texture(rendered.rgb_bgr).ravel()) + self.dpg.set_value("depth_texture", bgr_to_texture(rendered.depth_bgr).ravel()) + self.dpg.set_value("viewer_title", rendered.title) + self.dpg.set_value("frame_slider", self.current_index) + self.dpg.set_value("frame_text", f"{self.current_index + 1}/{len(self.state.slots)}") + self.dpg.set_value("metadata_text", "\n".join(rendered.metadata_lines)) + + def set_frame_index(self, index: int, *, debounce: bool = False) -> None: + clamped = max(0, min(index, len(self.state.slots) - 1)) + if debounce: + self.pending_index = clamped + self.pending_index_requested_at = time.monotonic() + self.dpg.set_value("frame_text", f"{clamped + 1}/{len(self.state.slots)}") + return + self.pending_index = None + self.current_index = clamped + self.refresh() + + def set_playing(self, playing: bool) -> None: + self.playing = playing + self.next_playback_deadline = time.monotonic() + 1.0 / max(self.playback_fps, 1.0) + self.reset_playback_metrics() + + def toggle_playing(self) -> None: + self.set_playing(not self.playing) + + def set_playback_fps(self, playback_fps: float) -> None: + self.playback_fps = playback_fps + self.next_playback_deadline = time.monotonic() + 1.0 / max(self.playback_fps, 1.0) + self.update_playback_status() + + def reset_playback_metrics(self) -> None: + self.playback_progress_samples.clear() + self.playback_advanced_frames = 0 + self.actual_playback_fps = 0.0 + self.update_playback_status() + + def record_playback_step(self, timestamp_s: float, frames_advanced: int) -> None: + self.playback_advanced_frames += frames_advanced + self.playback_progress_samples.append((timestamp_s, self.playback_advanced_frames)) + cutoff = timestamp_s - PLAYBACK_FPS_WINDOW_SECONDS + while self.playback_progress_samples and self.playback_progress_samples[0][0] < cutoff: + self.playback_progress_samples.popleft() + + if len(self.playback_progress_samples) >= 2: + elapsed_s = self.playback_progress_samples[-1][0] - self.playback_progress_samples[0][0] + if elapsed_s > 0.0: + advanced_frames = self.playback_progress_samples[-1][1] - self.playback_progress_samples[0][1] + self.actual_playback_fps = advanced_frames / elapsed_s + else: + self.actual_playback_fps = 0.0 + else: + self.actual_playback_fps = 0.0 + self.update_playback_status() + + def update_playback_status(self) -> None: + if not self.dpg.does_item_exist("playback_status_text"): + return + if ( + self.playing + and self.actual_playback_fps > 0.0 + and ( + self.actual_playback_fps < self.playback_fps * PLAYBACK_FPS_WARNING_RATIO + and self.actual_playback_fps < self.playback_fps - PLAYBACK_FPS_WARNING_ABS_TOLERANCE + ) + ): + self.dpg.set_value( + "playback_status_text", + f"Warning: actual playback {self.actual_playback_fps:.1f} FPS is below target {self.playback_fps:.1f} FPS", + ) + return + self.dpg.set_value("playback_status_text", "") + + def flush_pending_index(self) -> None: + if self.pending_index is None: + return + if time.monotonic() - self.pending_index_requested_at < FRAME_SLIDER_DEBOUNCE_SECONDS: + return + target_index = self.pending_index + self.pending_index = None + self.current_index = target_index + self.refresh() + + def maybe_advance(self) -> None: + self.flush_pending_index() + if not self.playing: + return + interval_s = 1.0 / max(self.playback_fps, 1.0) + now = time.monotonic() + if now < self.next_playback_deadline: + return + frames_due = max(1, int((now - self.next_playback_deadline) / interval_s) + 1) + self.next_playback_deadline += frames_due * interval_s + next_index = self.current_index + frames_due + if next_index >= len(self.state.slots): + frames_due = len(self.state.slots) - 1 - self.current_index + if frames_due <= 0: + self.set_playing(False) + return + next_index = len(self.state.slots) - 1 + self.set_frame_index(next_index) + self.record_playback_step(time.monotonic(), frames_due) + if next_index >= len(self.state.slots) - 1: + self.set_playing(False) + + def process_ui_callbacks(self) -> None: + jobs = self.dpg.get_callback_queue() + if jobs: + self.dpg.run_callbacks(jobs) + + def run(self) -> None: + dpg = self.dpg + dpg.create_context() + dpg.configure_app(manual_callback_management=True) + with dpg.texture_registry(show=False): + dpg.add_dynamic_texture(DISPLAY_WIDTH, DISPLAY_HEIGHT, [0.0] * (DISPLAY_WIDTH * DISPLAY_HEIGHT * 4), tag="rgb_texture") + dpg.add_dynamic_texture(DISPLAY_WIDTH, DISPLAY_HEIGHT, [0.0] * (DISPLAY_WIDTH * DISPLAY_HEIGHT * 4), tag="depth_texture") + + with dpg.window(tag="main_window", label="MCAP RGBD Viewer", no_close=True): + dpg.add_text(default_value="", tag="viewer_title") + with dpg.group(horizontal=True): + if self.layout_info.layout != "single-camera": + dpg.add_combo( + items=list(self.layout_info.camera_labels), + default_value=self.state.camera_label, + label="Camera", + width=160, + callback=lambda _s, app_data: self.replace_state(str(app_data)), + ) + dpg.add_button( + label="Play/Pause", + callback=lambda *_args: self.toggle_playing(), + ) + dpg.add_button(label="Prev", callback=lambda *_args: self.set_frame_index(self.current_index - 1)) + dpg.add_button(label="Next", callback=lambda *_args: self.set_frame_index(self.current_index + 1)) + dpg.add_slider_float( + label="Playback FPS", + min_value=1.0, + max_value=60.0, + default_value=self.playback_fps, + width=240, + callback=lambda _s, app_data: self.set_playback_fps(float(app_data)), + ) + dpg.add_text(default_value="", tag="playback_status_text", color=(255, 96, 96)) + with dpg.group(horizontal=True): + dpg.add_slider_float( + label="Depth Min (m)", + min_value=0.0, + max_value=10.0, + default_value=self.depth_min_m, + width=260, + callback=lambda _s, app_data: self._set_depth_min(float(app_data)), + ) + dpg.add_slider_float( + label="Depth Max (m)", + min_value=0.1, + max_value=20.0, + default_value=self.depth_max_m, + width=260, + callback=lambda _s, app_data: self._set_depth_max(float(app_data)), + ) + dpg.add_combo( + items=list(DEPTH_PALETTE_TO_OPENCV.keys()), + default_value=self.depth_palette_name, + label="Palette", + width=160, + callback=lambda _s, app_data: self._set_depth_palette(str(app_data)), + ) + with dpg.group(horizontal=True): + with dpg.child_window(width=DISPLAY_WIDTH + 16, height=DISPLAY_HEIGHT + 20): + dpg.add_text("RGB") + dpg.add_image("rgb_texture") + with dpg.child_window(width=DISPLAY_WIDTH + 16, height=DISPLAY_HEIGHT + 20): + dpg.add_text("Depth") + dpg.add_image("depth_texture") + with dpg.child_window(width=METADATA_PANEL_WIDTH, height=DISPLAY_HEIGHT + 20): + dpg.add_text("Metadata") + dpg.add_text(default_value="", wrap=METADATA_PANEL_WIDTH - 24, tag="metadata_text") + with dpg.group(horizontal=True): + dpg.add_slider_int( + label="Frame/Bundle", + min_value=0, + max_value=max(0, len(self.state.slots) - 1), + default_value=0, + tag="frame_slider", + width=DISPLAY_WIDTH * 2 + 80, + callback=lambda _s, app_data: self.set_frame_index(int(app_data), debounce=True), + ) + dpg.add_text(default_value="", tag="frame_text") + + with dpg.handler_registry(): + dpg.add_key_press_handler(dpg.mvKey_Left, callback=lambda *_args: self.set_frame_index(self.current_index - 1)) + dpg.add_key_press_handler(dpg.mvKey_Right, callback=lambda *_args: self.set_frame_index(self.current_index + 1)) + dpg.add_key_press_handler(dpg.mvKey_Home, callback=lambda *_args: self.set_frame_index(0)) + dpg.add_key_press_handler(dpg.mvKey_End, callback=lambda *_args: self.set_frame_index(len(self.state.slots) - 1)) + dpg.add_key_press_handler(dpg.mvKey_Spacebar, callback=lambda *_args: self.toggle_playing()) + + dpg.create_viewport( + title=f"MCAP RGBD Viewer - {self.mcap_path.name}", + width=VIEWPORT_WIDTH, + height=VIEWPORT_HEIGHT, + ) + dpg.setup_dearpygui() + dpg.show_viewport() + self.refresh() + try: + while dpg.is_dearpygui_running(): + dpg.render_dearpygui_frame() + self.process_ui_callbacks() + self.maybe_advance() + finally: + self.close_state_resources() + dpg.destroy_context() + self.state.close() + + def _set_depth_min(self, value: float) -> None: + self.depth_min_m = min(value, self.depth_max_m - 0.01) + self.refresh() + + def _set_depth_max(self, value: float) -> None: + self.depth_max_m = max(value, self.depth_min_m + 0.01) + self.refresh() + + def _set_depth_palette(self, value: str) -> None: + if value in DEPTH_PALETTE_TO_OPENCV: + self.depth_palette_name = value + self.refresh() + + +@click.command() +@click.argument("mcap_path", type=click.Path(path_type=Path, exists=True)) +@click.option("--camera-label", help="Camera label to view. Defaults to 'camera' or the first sorted multi-camera label.") +@click.option("--ffmpeg-bin", default="ffmpeg", show_default=True, help="ffmpeg binary used to build the preview cache.") +@click.option("--preview-width", default=1280, show_default=True, type=click.IntRange(min=64), help="Maximum width of the temporary decoded preview cache.") +@click.option("--frame-index", default=0, show_default=True, type=click.IntRange(min=0), help="Frame or bundle index used for --export-preview.") +@click.option("--depth-min-m", default=0.2, show_default=True, type=float, help="Minimum displayed depth in meters.") +@click.option("--depth-max-m", default=5.0, show_default=True, type=float, help="Maximum displayed depth in meters.") +@click.option( + "--depth-palette", + default="Turbo", + show_default=True, + type=click.Choice(tuple(DEPTH_PALETTE_TO_OPENCV.keys()), case_sensitive=False), + help="Depth color palette.", +) +@click.option("--summary-only", is_flag=True, help="Print layout/camera/frame metadata and exit without opening a GUI.") +@click.option("--export-preview", type=click.Path(path_type=Path), help="Write a side-by-side RGB/depth preview PNG and exit.") +def main( + mcap_path: Path, + camera_label: str | None, + ffmpeg_bin: str, + preview_width: int, + frame_index: int, + depth_min_m: float, + depth_max_m: float, + depth_palette: str, + summary_only: bool, + export_preview: Path | None, +) -> None: + layout_info = infer_layout(mcap_path.resolve()) + if camera_label is None: + selected_camera = layout_info.camera_labels[0] + else: + selected_camera = camera_label + if selected_camera not in layout_info.camera_labels: + raise click.ClickException( + f"camera label '{selected_camera}' not found. available: {', '.join(layout_info.camera_labels)}" + ) + + selected_depth_palette = next( + palette_name for palette_name in DEPTH_PALETTE_TO_OPENCV if palette_name.lower() == depth_palette.lower() + ) + + state = read_camera_state( + mcap_path.resolve(), + layout_info=layout_info, + camera_label=selected_camera, + ffmpeg_bin=ffmpeg_bin, + preview_width=preview_width, + ) + try: + if summary_only: + print_summary(layout_info, state) + return + if export_preview is not None: + export_preview_path = export_preview.expanduser().resolve() + write_preview_image( + state, + export_preview_path, + frame_index=frame_index, + depth_min_m=depth_min_m, + depth_max_m=depth_max_m, + depth_palette_name=selected_depth_palette, + ) + return + viewer = ViewerApp( + mcap_path=mcap_path.resolve(), + layout_info=layout_info, + initial_state=state, + ffmpeg_bin=ffmpeg_bin, + preview_width=preview_width, + depth_min_m=depth_min_m, + depth_max_m=depth_max_m, + ) + viewer.depth_palette_name = selected_depth_palette + viewer.run() + finally: + with contextlib.suppress(Exception): + state.close() + + +if __name__ == "__main__": + main() diff --git a/scripts/zed_batch_svo_to_mcap.py b/scripts/zed_batch_svo_to_mcap.py index 26121e9..9dcecde 100644 --- a/scripts/zed_batch_svo_to_mcap.py +++ b/scripts/zed_batch_svo_to_mcap.py @@ -36,6 +36,7 @@ class BatchConfig: depth_mode: str depth_size: str bundle_policy: str + copy_range: str bundle_topic: str | None with_pose: bool pose_config: Path | None @@ -506,8 +507,10 @@ def command_for_job(job: ConversionJob, config: BatchConfig, encoder_device: str config.depth_size, "--bundle-policy", config.bundle_policy, + "--copy-range", + config.copy_range, ] - if config.bundle_topic: + if config.bundle_topic and config.bundle_policy != "copy": command.extend(["--bundle-topic", config.bundle_topic]) if config.with_pose: command.append("--with-pose") @@ -616,6 +619,7 @@ def probe_output( output_path: Path, camera_labels: tuple[str, ...], *, + layout: str, bundle_topic: str | None, ) -> OutputProbeResult: if not output_path.is_file(): @@ -623,7 +627,7 @@ def probe_output( reader_module = load_mcap_reader() expected_topics = required_topics_for(camera_labels) - require_bundle = len(camera_labels) > 1 and bool(bundle_topic) + require_bundle = layout == "bundled" and len(camera_labels) > 1 and bool(bundle_topic) if require_bundle: expected_topics.add(bundle_topic or "/bundle") found_topics: set[str] = set() @@ -636,6 +640,12 @@ def probe_output( with output_path.open("rb") as stream: reader = reader_module.make_reader(stream) for schema, channel, message in reader.iter_messages(): + if layout == "copy" and channel.topic == "/bundle": + return OutputProbeResult( + output_path=output_path, + status="invalid", + reason="copy-layout MCAP must not contain /bundle", + ) if channel.topic in expected_topics: found_topics.add(channel.topic) if channel.topic.endswith("/video"): @@ -733,6 +743,17 @@ def probe_output( f"bundle_present={present_count} depth_messages={depth_counts[label]}" ), ) + else: + for label in camera_labels: + if video_counts[label] != depth_counts[label]: + return OutputProbeResult( + output_path=output_path, + status="invalid", + reason=( + f"video/depth count mismatch for {label}: " + f"video_messages={video_counts[label]} depth_messages={depth_counts[label]}" + ), + ) return OutputProbeResult(output_path=output_path, status="valid") @@ -1156,11 +1177,18 @@ def build_worker_slots( ) @click.option( "--bundle-policy", - type=click.Choice(("nearest", "strict")), + type=click.Choice(("nearest", "strict", "copy")), default="nearest", show_default=True, help="Bundling policy for multi-camera MCAP export.", ) +@click.option( + "--copy-range", + type=click.Choice(("common", "full")), + default="common", + show_default=True, + help="Timestamp range used when --bundle-policy copy is selected.", +) @click.option( "--bundle-topic", default="/bundle", @@ -1227,6 +1255,7 @@ def main( depth_mode: str, depth_size: str, bundle_policy: str, + copy_range: str, bundle_topic: str, with_pose: bool, pose_config: Path | None, @@ -1236,9 +1265,16 @@ def main( sync_tolerance_ms: float | None, progress_ui: str, ) -> None: - """Batch-convert multi-camera ZED segments into bundled MCAP files.""" + """Batch-convert multi-camera ZED segments into grouped MCAP files.""" if report_existing and dry_run: raise click.ClickException("--report-existing and --dry-run are mutually exclusive") + if bundle_policy == "copy": + if start_frame is not None or end_frame is not None: + raise click.ClickException("--start-frame/--end-frame cannot be used with --bundle-policy copy") + if sync_tolerance_ms is not None: + raise click.ClickException("--sync-tolerance-ms cannot be used with --bundle-policy copy") + if bundle_topic != "/bundle": + raise click.ClickException("--bundle-topic cannot be customized with --bundle-policy copy") binary_path = None if report_existing else locate_binary(zed_bin) sources = resolve_sources(input_dir, segment_dirs, segments_csv, csv_root, recursive) @@ -1261,7 +1297,8 @@ def main( depth_mode=depth_mode, depth_size=depth_size, bundle_policy=bundle_policy, - bundle_topic=bundle_topic, + copy_range=copy_range, + bundle_topic=None if bundle_policy == "copy" else bundle_topic, with_pose=with_pose, pose_config=pose_config.expanduser().resolve() if pose_config is not None else None, world_frame_id=world_frame_id, @@ -1316,7 +1353,12 @@ def main( continue if report_existing: - probe_result = probe_output(output_path, job.camera_labels, bundle_topic=config.bundle_topic) + probe_result = probe_output( + output_path, + job.camera_labels, + layout="copy" if config.bundle_policy == "copy" else "bundled", + bundle_topic=config.bundle_topic, + ) if probe_result.status == "valid": valid_existing.append(probe_result) elif probe_result.status == "invalid": @@ -1331,7 +1373,12 @@ def main( continue if config.probe_existing: - probe_result = probe_output(output_path, job.camera_labels, bundle_topic=config.bundle_topic) + probe_result = probe_output( + output_path, + job.camera_labels, + layout="copy" if config.bundle_policy == "copy" else "bundled", + bundle_topic=config.bundle_topic, + ) if probe_result.status == "valid": valid_existing.append(probe_result) skipped_results.append( diff --git a/src/tools/zed_svo_to_mcap.cpp b/src/tools/zed_svo_to_mcap.cpp index 302cdc5..06e4cc8 100644 --- a/src/tools/zed_svo_to_mcap.cpp +++ b/src/tools/zed_svo_to_mcap.cpp @@ -56,11 +56,14 @@ struct CliOptions { std::string depth_mode{"neural_plus"}; std::string depth_size{"optimal"}; std::string bundle_policy{"nearest"}; + std::string copy_range{"common"}; std::string bundle_topic{"/bundle"}; bool with_pose{false}; std::uint32_t start_frame{0}; + bool has_start_frame{false}; std::uint32_t end_frame{0}; bool has_end_frame{false}; + bool has_bundle_topic{false}; std::string frame_id{"camera"}; std::string video_topic{"/camera/video"}; std::string depth_topic{"/camera/depth"}; @@ -173,6 +176,17 @@ struct GrabResult { int last_corrupted_position{-1}; }; +enum class MultiCameraExportPolicy { + Nearest, + Strict, + Copy, +}; + +enum class CopyRangeMode { + Common, + Full, +}; + [[nodiscard]] constexpr int exit_code(const ToolExitCode code) { return static_cast(code); @@ -324,15 +338,61 @@ std::expected parse_depth_size(const std::string_vi } [[nodiscard]] -std::expected parse_bundle_policy(const std::string_view raw) { +std::expected parse_bundle_policy(const std::string_view raw) { const auto normalized = lowercase(std::string(raw)); if (normalized == "nearest") { - return cvmmap_streamer::record::BundlePolicy::Nearest; + return MultiCameraExportPolicy::Nearest; } if (normalized == "strict") { - return cvmmap_streamer::record::BundlePolicy::Strict; + return MultiCameraExportPolicy::Strict; } - return std::unexpected("invalid bundle policy: '" + std::string(raw) + "' (expected: nearest|strict)"); + if (normalized == "copy") { + return MultiCameraExportPolicy::Copy; + } + return std::unexpected("invalid bundle policy: '" + std::string(raw) + "' (expected: nearest|strict|copy)"); +} + +[[nodiscard]] +std::expected parse_copy_range(const std::string_view raw) { + const auto normalized = lowercase(std::string(raw)); + if (normalized == "common") { + return CopyRangeMode::Common; + } + if (normalized == "full") { + return CopyRangeMode::Full; + } + return std::unexpected("invalid copy range: '" + std::string(raw) + "' (expected: common|full)"); +} + +[[nodiscard]] +std::string_view multi_camera_policy_name(const MultiCameraExportPolicy policy) { + switch (policy) { + case MultiCameraExportPolicy::Strict: + return "strict"; + case MultiCameraExportPolicy::Copy: + return "copy"; + case MultiCameraExportPolicy::Nearest: + default: + return "nearest"; + } +} + +[[nodiscard]] +std::string_view copy_range_name(const CopyRangeMode range_mode) { + switch (range_mode) { + case CopyRangeMode::Full: + return "full"; + case CopyRangeMode::Common: + default: + return "common"; + } +} + +[[nodiscard]] +cvmmap_streamer::record::BundlePolicy manifest_bundle_policy(const MultiCameraExportPolicy policy) { + return policy == MultiCameraExportPolicy::Strict + ? cvmmap_streamer::record::BundlePolicy::Strict + : cvmmap_streamer::record::BundlePolicy::Nearest; } [[nodiscard]] @@ -1415,6 +1475,126 @@ std::expected, std::string> next_synced_group_times return std::optional{}; } +[[nodiscard]] +std::expected encode_and_write_sample( + cvmmap_streamer::record::MultiMcapRecordSink &sink, + CameraStream &stream, + const CliOptions &options, + const std::uint64_t timestamp_ns, + const sl::Mat &left_frame, + const sl::Mat &depth_frame, + const TrackingSample &tracking) { + const auto video_step_bytes = left_frame.getStepBytes(sl::MEM::CPU); + const auto video_bytes = std::span( + left_frame.getPtr(sl::MEM::CPU), + video_step_bytes * left_frame.getHeight()); + cvmmap_streamer::encode::RawVideoFrame raw_video{ + .info = stream.frame_info, + .source_timestamp_ns = timestamp_ns, + .row_stride_bytes = video_step_bytes, + .bytes = video_bytes, + }; + if (auto push = (*stream.backend)->push_frame(raw_video); !push) { + return std::unexpected( + "failed to encode frame for " + stream.source.label + ": " + cvmmap_streamer::format_error(push.error())); + } + + auto drained = (*stream.backend)->drain(); + if (!drained) { + return std::unexpected( + "failed to drain encoded access units for " + stream.source.label + ": " + + cvmmap_streamer::format_error(drained.error())); + } + if (auto write = write_access_units(sink, stream.mcap_stream_id, *drained); !write) { + return std::unexpected("failed to write video access unit for " + stream.source.label + ": " + write.error()); + } + + if (!stream.calibration_written) { + cvmmap_streamer::record::RawCameraCalibrationView calibration{ + .timestamp_ns = timestamp_ns, + .width = stream.video_calibration.width, + .height = stream.video_calibration.height, + .distortion_model = "plumb_bob", + .distortion = stream.video_calibration.distortion, + .intrinsic_matrix = stream.video_calibration.intrinsic_matrix, + .rectification_matrix = stream.video_calibration.rectification_matrix, + .projection_matrix = stream.video_calibration.projection_matrix, + }; + if (auto write = sink.write_camera_calibration(stream.mcap_stream_id, calibration); !write) { + return std::unexpected("failed to write calibration for " + stream.source.label + ": " + write.error()); + } + stream.calibration_written = true; + } + + if (!stream.depth_calibration_written && + (stream.depth_width != stream.width || stream.depth_height != stream.height)) { + cvmmap_streamer::record::RawCameraCalibrationView depth_calibration{ + .timestamp_ns = timestamp_ns, + .width = stream.depth_calibration.width, + .height = stream.depth_calibration.height, + .distortion_model = "plumb_bob", + .distortion = stream.depth_calibration.distortion, + .intrinsic_matrix = stream.depth_calibration.intrinsic_matrix, + .rectification_matrix = stream.depth_calibration.rectification_matrix, + .projection_matrix = stream.depth_calibration.projection_matrix, + }; + if (auto write = sink.write_depth_camera_calibration(stream.mcap_stream_id, depth_calibration); !write) { + return std::unexpected("failed to write depth calibration for " + stream.source.label + ": " + write.error()); + } + stream.depth_calibration_written = true; + } + + const auto depth_width = static_cast(depth_frame.getWidth()); + const auto depth_height = static_cast(depth_frame.getHeight()); + if (depth_width != stream.depth_width || depth_height != stream.depth_height) { + return std::unexpected( + "depth resolution changed unexpectedly for " + stream.source.label + ": " + + std::to_string(depth_width) + "x" + std::to_string(depth_height) + " vs " + + std::to_string(stream.depth_width) + "x" + std::to_string(stream.depth_height)); + } + const auto depth_step_bytes = depth_frame.getStepBytes(sl::MEM::CPU); + const auto packed_depth_bytes = static_cast(depth_width) * sizeof(std::uint16_t); + if (depth_step_bytes < packed_depth_bytes) { + return std::unexpected( + "depth stride " + std::to_string(depth_step_bytes) + " is smaller than packed row size " + + std::to_string(packed_depth_bytes) + " for " + stream.source.label); + } + + std::optional> compact_depth{}; + std::span depth_pixels{}; + if (depth_step_bytes == packed_depth_bytes) { + depth_pixels = std::span( + depth_frame.getPtr(sl::MEM::CPU), + static_cast(depth_width) * static_cast(depth_height)); + } else { + compact_depth = copy_compact_u16_plane(depth_frame); + depth_pixels = *compact_depth; + } + + cvmmap_streamer::record::RawDepthMapU16View depth_map{ + .timestamp_ns = timestamp_ns, + .width = depth_width, + .height = depth_height, + .pixels = depth_pixels, + }; + if (auto write = sink.write_depth_map_u16(stream.mcap_stream_id, depth_map); !write) { + return std::unexpected("failed to write depth map for " + stream.source.label + ": " + write.error()); + } + + if (options.with_pose && tracking.has_pose) { + cvmmap_streamer::record::RawPoseView pose_view{ + .timestamp_ns = timestamp_ns, + .reference_frame_id = pose_reference_frame_id(stream.pose_tracking, stream.source.label), + .position = tracking.position, + .orientation = tracking.orientation, + }; + if (auto write = sink.write_pose(stream.mcap_stream_id, pose_view); !write) { + return std::unexpected("failed to write pose for " + stream.source.label + ": " + write.error()); + } + } + return {}; +} + [[nodiscard]] std::expected encode_and_write_group( cvmmap_streamer::record::MultiMcapRecordSink &sink, @@ -1472,114 +1652,15 @@ std::expected encode_and_write_group( const auto &left_frame = selected_left_frame(stream, selection); const auto &depth_frame = selected_depth_frame(stream, selection); const auto &tracking = selected_tracking(stream, selection); - - const auto video_step_bytes = left_frame.getStepBytes(sl::MEM::CPU); - const auto video_bytes = std::span( - left_frame.getPtr(sl::MEM::CPU), - video_step_bytes * left_frame.getHeight()); - cvmmap_streamer::encode::RawVideoFrame raw_video{ - .info = stream.frame_info, - .source_timestamp_ns = *selection.timestamp_ns, - .row_stride_bytes = video_step_bytes, - .bytes = video_bytes, - }; - if (auto push = (*stream.backend)->push_frame(raw_video); !push) { - return std::unexpected( - "failed to encode frame for " + stream.source.label + ": " + cvmmap_streamer::format_error(push.error())); - } - - auto drained = (*stream.backend)->drain(); - if (!drained) { - return std::unexpected( - "failed to drain encoded access units for " + stream.source.label + ": " + - cvmmap_streamer::format_error(drained.error())); - } - if (auto write = write_access_units(sink, stream.mcap_stream_id, *drained); !write) { - return std::unexpected("failed to write video access unit for " + stream.source.label + ": " + write.error()); - } - - if (!stream.calibration_written) { - cvmmap_streamer::record::RawCameraCalibrationView calibration{ - .timestamp_ns = *selection.timestamp_ns, - .width = stream.video_calibration.width, - .height = stream.video_calibration.height, - .distortion_model = "plumb_bob", - .distortion = stream.video_calibration.distortion, - .intrinsic_matrix = stream.video_calibration.intrinsic_matrix, - .rectification_matrix = stream.video_calibration.rectification_matrix, - .projection_matrix = stream.video_calibration.projection_matrix, - }; - if (auto write = sink.write_camera_calibration(stream.mcap_stream_id, calibration); !write) { - return std::unexpected("failed to write calibration for " + stream.source.label + ": " + write.error()); - } - stream.calibration_written = true; - } - - if (!stream.depth_calibration_written && - (stream.depth_width != stream.width || stream.depth_height != stream.height)) { - cvmmap_streamer::record::RawCameraCalibrationView depth_calibration{ - .timestamp_ns = *selection.timestamp_ns, - .width = stream.depth_calibration.width, - .height = stream.depth_calibration.height, - .distortion_model = "plumb_bob", - .distortion = stream.depth_calibration.distortion, - .intrinsic_matrix = stream.depth_calibration.intrinsic_matrix, - .rectification_matrix = stream.depth_calibration.rectification_matrix, - .projection_matrix = stream.depth_calibration.projection_matrix, - }; - if (auto write = sink.write_depth_camera_calibration(stream.mcap_stream_id, depth_calibration); !write) { - return std::unexpected("failed to write depth calibration for " + stream.source.label + ": " + write.error()); - } - stream.depth_calibration_written = true; - } - - const auto depth_width = static_cast(depth_frame.getWidth()); - const auto depth_height = static_cast(depth_frame.getHeight()); - if (depth_width != stream.depth_width || depth_height != stream.depth_height) { - return std::unexpected( - "depth resolution changed unexpectedly for " + stream.source.label + ": " + - std::to_string(depth_width) + "x" + std::to_string(depth_height) + " vs " + - std::to_string(stream.depth_width) + "x" + std::to_string(stream.depth_height)); - } - const auto depth_step_bytes = depth_frame.getStepBytes(sl::MEM::CPU); - const auto packed_depth_bytes = static_cast(depth_width) * sizeof(std::uint16_t); - if (depth_step_bytes < packed_depth_bytes) { - return std::unexpected( - "depth stride " + std::to_string(depth_step_bytes) + " is smaller than packed row size " + - std::to_string(packed_depth_bytes) + " for " + stream.source.label); - } - - std::optional> compact_depth{}; - std::span depth_pixels{}; - if (depth_step_bytes == packed_depth_bytes) { - depth_pixels = std::span( - depth_frame.getPtr(sl::MEM::CPU), - static_cast(depth_width) * static_cast(depth_height)); - } else { - compact_depth = copy_compact_u16_plane(depth_frame); - depth_pixels = *compact_depth; - } - - cvmmap_streamer::record::RawDepthMapU16View depth_map{ - .timestamp_ns = *selection.timestamp_ns, - .width = depth_width, - .height = depth_height, - .pixels = depth_pixels, - }; - if (auto write = sink.write_depth_map_u16(stream.mcap_stream_id, depth_map); !write) { - return std::unexpected("failed to write depth map for " + stream.source.label + ": " + write.error()); - } - - if (options.with_pose && tracking.has_pose) { - cvmmap_streamer::record::RawPoseView pose_view{ - .timestamp_ns = *selection.timestamp_ns, - .reference_frame_id = pose_reference_frame_id(stream.pose_tracking, stream.source.label), - .position = tracking.position, - .orientation = tracking.orientation, - }; - if (auto write = sink.write_pose(stream.mcap_stream_id, pose_view); !write) { - return std::unexpected("failed to write pose for " + stream.source.label + ": " + write.error()); - } + if (auto write = encode_and_write_sample( + sink, + stream, + options, + *selection.timestamp_ns, + left_frame, + depth_frame, + tracking); !write) { + return write; } } return {}; @@ -1617,30 +1698,84 @@ std::expected advance_after_emit(std::vector &s } [[nodiscard]] -double bundled_progress_fraction( - const std::uint64_t common_start_ts, - const std::uint64_t common_end_ts, - const std::uint64_t group_timestamp_ns) { - if (common_end_ts <= common_start_ts) { - return 1.0; +bool is_copy_stream_in_range( + const CameraStream &stream, + const std::optional range_end_ts) { + if (stream.current_timestamp_ns == 0) { + return false; } - const auto bounded_timestamp = std::clamp(group_timestamp_ns, common_start_ts, common_end_ts); - return static_cast(bounded_timestamp - common_start_ts) / - static_cast(common_end_ts - common_start_ts); + if (range_end_ts.has_value() && stream.current_timestamp_ns > *range_end_ts) { + return false; + } + return true; } [[nodiscard]] -std::string bundled_progress_detail( - const std::uint64_t common_start_ts, - const std::uint64_t common_end_ts, - const std::uint64_t group_timestamp_ns) { - const auto bounded_timestamp = std::clamp(group_timestamp_ns, common_start_ts, common_end_ts); - const double elapsed_seconds = static_cast(bounded_timestamp - common_start_ts) / 1'000'000'000.0; - const double total_seconds = common_end_ts > common_start_ts - ? static_cast(common_end_ts - common_start_ts) / 1'000'000'000.0 +std::optional next_copy_stream_index( + const std::vector &streams, + const std::optional range_end_ts) { + std::optional best_index{}; + for (std::size_t index = 0; index < streams.size(); ++index) { + const auto &stream = streams[index]; + if (!is_copy_stream_in_range(stream, range_end_ts)) { + continue; + } + if (!best_index.has_value()) { + best_index = index; + continue; + } + const auto &best_stream = streams[*best_index]; + if (stream.current_timestamp_ns < best_stream.current_timestamp_ns) { + best_index = index; + continue; + } + if (stream.current_timestamp_ns == best_stream.current_timestamp_ns && + stream.source.label < best_stream.source.label) { + best_index = index; + } + } + return best_index; +} + +[[nodiscard]] +std::expected advance_copy_stream(CameraStream &stream) { + if (!stream.has_next) { + stream.current_timestamp_ns = 0; + return {}; + } + auto promote = promote_next_frame(stream); + if (!promote) { + return std::unexpected(promote.error()); + } + return {}; +} + +[[nodiscard]] +double time_window_progress_fraction( + const std::uint64_t window_start_ts, + const std::uint64_t window_end_ts, + const std::uint64_t current_timestamp_ns) { + if (window_end_ts <= window_start_ts) { + return 1.0; + } + const auto bounded_timestamp = std::clamp(current_timestamp_ns, window_start_ts, window_end_ts); + return static_cast(bounded_timestamp - window_start_ts) / + static_cast(window_end_ts - window_start_ts); +} + +[[nodiscard]] +std::string time_window_progress_detail( + const std::uint64_t window_start_ts, + const std::uint64_t window_end_ts, + const std::uint64_t current_timestamp_ns, + const std::string_view window_label) { + const auto bounded_timestamp = std::clamp(current_timestamp_ns, window_start_ts, window_end_ts); + const double elapsed_seconds = static_cast(bounded_timestamp - window_start_ts) / 1'000'000'000.0; + const double total_seconds = window_end_ts > window_start_ts + ? static_cast(window_end_ts - window_start_ts) / 1'000'000'000.0 : 0.0; char buffer[96]{}; - std::snprintf(buffer, sizeof(buffer), "%.1fs/%.1fs overlap", elapsed_seconds, total_seconds); + std::snprintf(buffer, sizeof(buffer), "%.1fs/%.1fs %s", elapsed_seconds, total_seconds, std::string(window_label).c_str()); return std::string(buffer); } @@ -2186,7 +2321,22 @@ int run_multi_source( const sl::DEPTH_MODE depth_mode, const sl::Resolution depth_size, const PoseTrackingOptions &pose_tracking, - const cvmmap_streamer::record::BundlePolicy bundle_policy) { + const MultiCameraExportPolicy bundle_policy, + const CopyRangeMode copy_range_mode) { + if (bundle_policy == MultiCameraExportPolicy::Copy) { + if (options.has_start_frame || options.has_end_frame) { + spdlog::error("--start-frame/--end-frame are not supported with --bundle-policy copy"); + return exit_code(ToolExitCode::UsageError); + } + if (options.has_sync_tolerance) { + spdlog::error("--sync-tolerance-ms is not supported with --bundle-policy copy"); + return exit_code(ToolExitCode::UsageError); + } + if (options.has_bundle_topic) { + spdlog::error("--bundle-topic is not supported with --bundle-policy copy"); + return exit_code(ToolExitCode::UsageError); + } + } if (options.has_end_frame && options.end_frame < options.start_frame) { spdlog::error( "invalid bundled range: start-frame={} end-frame={}", @@ -2228,7 +2378,20 @@ int run_multi_source( [](const auto &left, const auto &right) { return left.last_timestamp_ns < right.last_timestamp_ns; })->last_timestamp_ns; - if (common_start_ts > common_end_ts) { + const auto full_start_ts = std::min_element( + streams.begin(), + streams.end(), + [](const auto &left, const auto &right) { + return left.first_timestamp_ns < right.first_timestamp_ns; + })->first_timestamp_ns; + const auto full_end_ts = std::max_element( + streams.begin(), + streams.end(), + [](const auto &left, const auto &right) { + return left.last_timestamp_ns < right.last_timestamp_ns; + })->last_timestamp_ns; + if ((bundle_policy != MultiCameraExportPolicy::Copy || copy_range_mode == CopyRangeMode::Common) && + common_start_ts > common_end_ts) { close_camera_streams(streams); spdlog::error("synced time window is empty: start_ts={} end_ts={}", common_start_ts, common_end_ts); return exit_code(ToolExitCode::UsageError); @@ -2240,24 +2403,33 @@ int run_multi_source( [](const auto &left, const auto &right) { return left.nominal_frame_period_ns < right.nominal_frame_period_ns; })->nominal_frame_period_ns; - const auto bundle_policy_name = bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest - ? "nearest" - : "strict"; + const auto bundle_policy_name = multi_camera_policy_name(bundle_policy); const auto tolerance_ns = options.has_sync_tolerance ? static_cast(std::llround(options.sync_tolerance_ms * 1'000'000.0)) : std::max(1, slowest_period_ns); - spdlog::info( - "multi-camera bundle window start_ts={} end_ts={} policy={} bundle_period_ns={} tolerance_ns={}", - common_start_ts, - common_end_ts, - bundle_policy_name, - slowest_period_ns, - tolerance_ns); + if (bundle_policy == MultiCameraExportPolicy::Copy) { + const auto range_start_ts = copy_range_mode == CopyRangeMode::Common ? common_start_ts : full_start_ts; + const auto range_end_ts = copy_range_mode == CopyRangeMode::Common ? common_end_ts : full_end_ts; + spdlog::info( + "multi-camera copy window start_ts={} end_ts={} policy={} copy_range={}", + range_start_ts, + range_end_ts, + bundle_policy_name, + copy_range_name(copy_range_mode)); + } else { + spdlog::info( + "multi-camera bundle window start_ts={} end_ts={} policy={} bundle_period_ns={} tolerance_ns={}", + common_start_ts, + common_end_ts, + bundle_policy_name, + slowest_period_ns, + tolerance_ns); + } const auto render_progress = stderr_supports_progress_bar(); const auto total_timeline_bundles = common_end_ts >= common_start_ts ? ((common_end_ts - common_start_ts) / slowest_period_ns) + 1 : 0; - if (bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest && + if (bundle_policy == MultiCameraExportPolicy::Nearest && options.start_frame >= total_timeline_bundles) { close_camera_streams(streams); spdlog::error( @@ -2266,7 +2438,7 @@ int run_multi_source( total_timeline_bundles); return exit_code(ToolExitCode::UsageError); } - if (bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest && + if (bundle_policy == MultiCameraExportPolicy::Nearest && options.has_end_frame && options.end_frame >= total_timeline_bundles) { close_camera_streams(streams); @@ -2279,28 +2451,30 @@ int run_multi_source( const auto selected_end_bundle = options.has_end_frame ? static_cast(options.end_frame) - : (bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest + : (bundle_policy == MultiCameraExportPolicy::Nearest ? total_timeline_bundles - 1 : 0); const auto selected_total_groups = options.has_end_frame ? static_cast(options.end_frame - options.start_frame) + 1 - : (bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest + : (bundle_policy == MultiCameraExportPolicy::Nearest ? total_timeline_bundles - static_cast(options.start_frame) : 0); const bool exact_group_progress = render_progress && - (bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest || options.has_end_frame); + (bundle_policy == MultiCameraExportPolicy::Nearest || options.has_end_frame); const bool approximate_time_progress = render_progress && - bundle_policy == cvmmap_streamer::record::BundlePolicy::Strict && - !options.has_end_frame; + (bundle_policy == MultiCameraExportPolicy::Strict || bundle_policy == MultiCameraExportPolicy::Copy) && + (bundle_policy == MultiCameraExportPolicy::Copy || !options.has_end_frame); ProgressBar progress{exact_group_progress ? selected_total_groups : 0}; double last_progress_fraction = 0.0; std::string last_progress_detail{}; - const auto initial_target_ts = bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest + const auto initial_target_ts = bundle_policy == MultiCameraExportPolicy::Nearest ? common_start_ts + static_cast(options.start_frame) * slowest_period_ns - : common_start_ts; + : (bundle_policy == MultiCameraExportPolicy::Copy + ? (copy_range_mode == CopyRangeMode::Common ? common_start_ts : full_start_ts) + : common_start_ts); if (auto synced = sync_streams_to_timestamp(streams, initial_target_ts); !synced) { close_camera_streams(streams); if (synced.error() == "interrupted") { @@ -2310,7 +2484,7 @@ int run_multi_source( return exit_code(ToolExitCode::RuntimeError); } auto effective_progress_start_ts = initial_target_ts; - if (bundle_policy == cvmmap_streamer::record::BundlePolicy::Strict && options.start_frame > 0) { + if (bundle_policy == MultiCameraExportPolicy::Strict && options.start_frame > 0) { if (auto skipped_to = skip_bundled_start_groups(streams, options.start_frame, tolerance_ns, common_end_ts); !skipped_to) { close_camera_streams(streams); if (skipped_to.error() == "interrupted") { @@ -2326,7 +2500,7 @@ int run_multi_source( auto sink = cvmmap_streamer::record::MultiMcapRecordSink::create( output_path.string(), compression, - options.bundle_topic); + bundle_policy == MultiCameraExportPolicy::Copy ? "" : options.bundle_topic); if (!sink) { if (approximate_time_progress) { progress.finish_fraction(last_progress_fraction, false, last_progress_detail); @@ -2350,7 +2524,8 @@ int run_multi_source( } std::uint64_t emitted_groups{0}; - if (bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest) { + std::uint64_t emitted_samples{0}; + if (bundle_policy == MultiCameraExportPolicy::Nearest) { for (std::uint64_t bundle_index = options.start_frame; bundle_index <= selected_end_bundle; ++bundle_index) { if (log_shutdown_request(shutdown_logged, "multi-camera export")) { interrupted = true; @@ -2373,7 +2548,7 @@ int run_multi_source( *sink, streams, options, - bundle_policy, + manifest_bundle_policy(bundle_policy), bundle_index, bundle_timestamp_ns, *selections); !write) { @@ -2393,7 +2568,7 @@ int run_multi_source( emitted_groups += 1; progress.update(emitted_groups); } - } else { + } else if (bundle_policy == MultiCameraExportPolicy::Strict) { while (true) { if (log_shutdown_request(shutdown_logged, "multi-camera export")) { interrupted = true; @@ -2424,7 +2599,7 @@ int run_multi_source( *sink, streams, options, - bundle_policy, + manifest_bundle_policy(bundle_policy), bundle_index, **group_timestamp, selections); !write) { @@ -2440,8 +2615,12 @@ int run_multi_source( } emitted_groups += 1; if (approximate_time_progress) { - last_progress_fraction = bundled_progress_fraction(effective_progress_start_ts, common_end_ts, **group_timestamp); - last_progress_detail = bundled_progress_detail(effective_progress_start_ts, common_end_ts, **group_timestamp); + last_progress_fraction = time_window_progress_fraction(effective_progress_start_ts, common_end_ts, **group_timestamp); + last_progress_detail = time_window_progress_detail( + effective_progress_start_ts, + common_end_ts, + **group_timestamp, + "overlap"); progress.update_fraction(last_progress_fraction, last_progress_detail); } else { progress.update(emitted_groups); @@ -2466,6 +2645,61 @@ int run_multi_source( return exit_code(ToolExitCode::RuntimeError); } } + } else { + const auto range_start_ts = copy_range_mode == CopyRangeMode::Common ? common_start_ts : full_start_ts; + const auto range_end_ts = copy_range_mode == CopyRangeMode::Common + ? std::optional{common_end_ts} + : std::optional{full_end_ts}; + while (true) { + if (log_shutdown_request(shutdown_logged, "multi-camera copy export")) { + interrupted = true; + break; + } + const auto next_stream_index = next_copy_stream_index(streams, range_end_ts); + if (!next_stream_index.has_value()) { + break; + } + auto &stream = streams[*next_stream_index]; + if (auto write = encode_and_write_sample( + *sink, + stream, + options, + stream.current_timestamp_ns, + stream.current_left_frame, + stream.current_depth_frame, + stream.current_tracking); !write) { + if (approximate_time_progress) { + progress.finish_fraction(last_progress_fraction, false, last_progress_detail); + } else { + progress.finish(emitted_samples, false); + } + sink->close(); + close_camera_streams(streams); + spdlog::error("{}", write.error()); + return exit_code(ToolExitCode::RuntimeError); + } + emitted_samples += 1; + if (approximate_time_progress) { + last_progress_fraction = time_window_progress_fraction(range_start_ts, *range_end_ts, stream.current_timestamp_ns); + last_progress_detail = time_window_progress_detail( + range_start_ts, + *range_end_ts, + stream.current_timestamp_ns, + copy_range_mode == CopyRangeMode::Common ? "copy overlap" : "copy range"); + progress.update_fraction(last_progress_fraction, last_progress_detail); + } + if (auto advance = advance_copy_stream(stream); !advance) { + if (approximate_time_progress) { + progress.finish_fraction(last_progress_fraction, false, last_progress_detail); + } else { + progress.finish(emitted_samples, false); + } + sink->close(); + close_camera_streams(streams); + spdlog::error("{}", advance.error()); + return exit_code(ToolExitCode::RuntimeError); + } + } } for (auto &stream : streams) { @@ -2486,20 +2720,30 @@ int run_multi_source( if (approximate_time_progress) { if (!interrupted) { last_progress_fraction = 1.0; - last_progress_detail = bundled_progress_detail(effective_progress_start_ts, common_end_ts, common_end_ts); + const auto progress_end_ts = bundle_policy == MultiCameraExportPolicy::Copy + ? (copy_range_mode == CopyRangeMode::Common ? common_end_ts : full_end_ts) + : common_end_ts; + last_progress_detail = time_window_progress_detail( + effective_progress_start_ts, + progress_end_ts, + progress_end_ts, + bundle_policy == MultiCameraExportPolicy::Copy + ? (copy_range_mode == CopyRangeMode::Common ? "copy overlap" : "copy range") + : "overlap"); } progress.finish_fraction(last_progress_fraction, !interrupted, last_progress_detail); } else { - progress.finish(emitted_groups, !interrupted); + progress.finish(bundle_policy == MultiCameraExportPolicy::Copy ? emitted_samples : emitted_groups, !interrupted); } for (const auto &stream : streams) { spdlog::info( - "bundled {} dropped_frame(s) for {}", + "multi-camera export skipped {} frame(s) while aligning {}", stream.dropped_frames, stream.source.label); } close_camera_streams(streams); - if (!interrupted && emitted_groups == 0) { + const auto emitted_count = bundle_policy == MultiCameraExportPolicy::Copy ? emitted_samples : emitted_groups; + if (!interrupted && emitted_count == 0) { std::error_code remove_error{}; std::filesystem::remove(output_path, remove_error); if (remove_error) { @@ -2508,29 +2752,58 @@ int run_multi_source( output_path.string(), remove_error.message()); } - spdlog::error( - "no bundled frame groups were found across {} camera(s) for '{}' using policy={}", - sources.size(), - output_path.string(), - bundle_policy_name); + if (bundle_policy == MultiCameraExportPolicy::Copy) { + spdlog::error( + "no camera samples were found across {} camera(s) for '{}' using policy={} copy_range={}", + sources.size(), + output_path.string(), + bundle_policy_name, + copy_range_name(copy_range_mode)); + } else { + spdlog::error( + "no bundled frame groups were found across {} camera(s) for '{}' using policy={}", + sources.size(), + output_path.string(), + bundle_policy_name); + } return exit_code(ToolExitCode::RuntimeError); } if (interrupted) { - spdlog::warn( - "gracefully stopped after writing {} bundled frame group(s) across {} camera(s) to '{}'", - emitted_groups, - sources.size(), - output_path.string()); + if (bundle_policy == MultiCameraExportPolicy::Copy) { + spdlog::warn( + "gracefully stopped after writing {} camera sample(s) across {} camera(s) to '{}' using policy={} copy_range={}", + emitted_count, + sources.size(), + output_path.string(), + bundle_policy_name, + copy_range_name(copy_range_mode)); + } else { + spdlog::warn( + "gracefully stopped after writing {} bundled frame group(s) across {} camera(s) to '{}'", + emitted_groups, + sources.size(), + output_path.string()); + } return interrupted_exit_code(); } - spdlog::info( - "wrote {} bundled frame group(s) across {} camera(s) to '{}' using policy={}", - emitted_groups, - sources.size(), - output_path.string(), - bundle_policy_name); + if (bundle_policy == MultiCameraExportPolicy::Copy) { + spdlog::info( + "wrote {} camera sample(s) across {} camera(s) to '{}' using policy={} copy_range={}", + emitted_count, + sources.size(), + output_path.string(), + bundle_policy_name, + copy_range_name(copy_range_mode)); + } else { + spdlog::info( + "wrote {} bundled frame group(s) across {} camera(s) to '{}' using policy={}", + emitted_groups, + sources.size(), + output_path.string(), + bundle_policy_name); + } return exit_code(ToolExitCode::Success); } @@ -2555,9 +2828,15 @@ int main(int argc, char **argv) { ->check(CLI::IsMember({"neural_light", "neural", "neural_plus"})); app.add_option("--depth-size", options.depth_size, "Depth output size (optimal|native|x)") ->default_val("optimal"); - app.add_option("--bundle-policy", options.bundle_policy, "Bundling policy for multi-camera mode (nearest|strict)") - ->check(CLI::IsMember({"nearest", "strict"})); + app.add_option("--bundle-policy", options.bundle_policy, "Bundling policy for multi-camera mode (nearest|strict|copy)") + ->check(CLI::IsMember({"nearest", "strict", "copy"})); app.add_option( + "--copy-range", + options.copy_range, + "Timestamp range used by --bundle-policy copy (common|full)") + ->default_val("common") + ->check(CLI::IsMember({"common", "full"})); + auto *start_frame_option = app.add_option( "--start-frame", options.start_frame, "First frame/group to export (inclusive): raw SVO frame in single-camera mode, bundle index in multi-camera mode") @@ -2571,7 +2850,7 @@ int main(int argc, char **argv) { app.add_option("--video-topic", options.video_topic, "MCAP topic for foxglove.CompressedVideo"); app.add_option("--depth-topic", options.depth_topic, "MCAP topic for cvmmap_streamer.DepthMap"); app.add_option("--calibration-topic", options.calibration_topic, "MCAP topic for foxglove.CameraCalibration"); - app.add_option("--bundle-topic", options.bundle_topic, "MCAP topic for bundled multi-camera manifests"); + auto *bundle_topic_option = app.add_option("--bundle-topic", options.bundle_topic, "MCAP topic for bundled multi-camera manifests"); app.add_option( "--depth-calibration-topic", options.depth_calibration_topic, @@ -2594,7 +2873,9 @@ int main(int argc, char **argv) { } catch (const CLI::ParseError &error) { return app.exit(error); } + options.has_start_frame = start_frame_option->count() > 0; options.has_end_frame = end_frame_option->count() > 0; + options.has_bundle_topic = bundle_topic_option->count() > 0; options.has_sync_tolerance = sync_tolerance_option->count() > 0; auto codec = parse_codec(options.codec); @@ -2627,6 +2908,11 @@ int main(int argc, char **argv) { spdlog::error("{}", bundle_policy.error()); return exit_code(ToolExitCode::UsageError); } + auto copy_range_mode = parse_copy_range(options.copy_range); + if (!copy_range_mode) { + spdlog::error("{}", copy_range_mode.error()); + return exit_code(ToolExitCode::UsageError); + } auto pose_tracking = load_pose_tracking_options(options); if (!pose_tracking) { spdlog::error("{}", pose_tracking.error()); @@ -2663,5 +2949,6 @@ int main(int argc, char **argv) { *depth_mode, *depth_size, *pose_tracking, - *bundle_policy); + *bundle_policy, + *copy_range_mode); } diff --git a/uv.lock b/uv.lock index fef1689..482d153 100644 --- a/uv.lock +++ b/uv.lock @@ -2,7 +2,8 @@ version = 1 revision = 3 requires-python = ">=3.10" resolution-markers = [ - "python_full_version >= '3.11'", + "python_full_version >= '3.12'", + "python_full_version == '3.11.*'", "python_full_version < '3.11'", ] @@ -42,16 +43,47 @@ dependencies = [ { name = "zstandard" }, ] +[package.optional-dependencies] +viewer = [ + { name = "dearpygui" }, + { name = "rvl-impl", marker = "python_full_version >= '3.12'" }, +] + [package.metadata] requires-dist = [ { name = "click", specifier = ">=8.1" }, + { name = "dearpygui", marker = "extra == 'viewer'", specifier = ">=2.2" }, { name = "duckdb", specifier = ">=1.0" }, { name = "numpy", specifier = ">=2.2" }, { name = "opencv-python-headless", specifier = ">=4.11" }, { name = "progress-table", specifier = ">=3.2" }, { name = "protobuf", specifier = ">=5.29" }, + { name = "rvl-impl", marker = "python_full_version >= '3.12' and extra == 'viewer'", git = "https://github.com/crosstyan/rvl-impl.git?rev=74308bcaf184cb39428237e8f4f99a67a6de22d9" }, { name = "zstandard", specifier = ">=0.23" }, ] +provides-extras = ["viewer"] + +[[package]] +name = "dearpygui" +version = "2.2" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/59/71/114626e9b77b07b2d5d92e0030b00b4a78e73de1212cbe63656af3da636e/dearpygui-2.2-cp310-cp310-macosx_13_0_arm64.whl", hash = "sha256:9805b99abcdf89b18c6877cfd4865f844398e1c555316d2f7347b1e8e62f29fd", size = 1931334, upload-time = "2026-02-17T14:21:51.362Z" }, + { url = "https://files.pythonhosted.org/packages/28/f5/dbd692d64a27c94d7bf4f05b87a4bd74bcd61699248a7fb1166635cef17a/dearpygui-2.2-cp310-cp310-manylinux1_x86_64.whl", hash = "sha256:8b42ebd0a73ddf03ab5fb0777636216035716089ae449f904fe37ccebbed0061", size = 2592856, upload-time = "2026-02-17T14:22:00.223Z" }, + { url = "https://files.pythonhosted.org/packages/58/e0/4be23bd80453b5ee216319a1f2005b57a7c25d00872056f7a96a0a21ef4e/dearpygui-2.2-cp310-cp310-win_amd64.whl", hash = "sha256:9872af7c4d1c7f8b4f1031c1c333ff83c778332674ac3d54178fa7ca0230c6ab", size = 1830505, upload-time = "2026-02-17T14:21:40.74Z" }, + { url = "https://files.pythonhosted.org/packages/b7/80/c62a26549688a9a2251fede8c1ba10f5e41964a4bb97dba486bcb1e0be28/dearpygui-2.2-cp311-cp311-macosx_13_0_arm64.whl", hash = "sha256:a2dbbd975e1dbdf4688ef49b95651192b6417c8722e470b9ad2b7f5029555c63", size = 1931280, upload-time = "2026-02-17T14:21:52.98Z" }, + { url = "https://files.pythonhosted.org/packages/01/a1/6c40624fcaa0ea429aa2b6906b19c639175de0677b2af52f00c2794a56ce/dearpygui-2.2-cp311-cp311-manylinux1_x86_64.whl", hash = "sha256:87c16bc00b94ee748c8c156c10f353b7f0b6e843ecec54121cb3b9f254abf940", size = 2592871, upload-time = "2026-02-17T14:22:01.806Z" }, + { url = "https://files.pythonhosted.org/packages/58/ca/3683b74526a869403ca63bac33c47c8d1bbabe57d186eb33490b5d18459a/dearpygui-2.2-cp311-cp311-win_amd64.whl", hash = "sha256:d5a38e58a03a41e09915f9b026759899d772d32e920bcd114d1b3f344946e0f0", size = 1830497, upload-time = "2026-02-17T14:21:42.108Z" }, + { url = "https://files.pythonhosted.org/packages/17/c8/b4afdac89c7bf458513366af3143f7383d7b09721637989c95788d93e24c/dearpygui-2.2-cp312-cp312-macosx_13_0_arm64.whl", hash = "sha256:34ceae1ca1b65444e49012d6851312e44f08713da1b8cc0150cf41f1c207af9c", size = 1931443, upload-time = "2026-02-17T14:21:54.394Z" }, + { url = "https://files.pythonhosted.org/packages/43/93/a2d083b2e0edb095be815662cc41e40cf9ea7b65d6323e47bb30df7eb284/dearpygui-2.2-cp312-cp312-manylinux1_x86_64.whl", hash = "sha256:e1fae9ae59fec0e41773df64c80311a6ba67696219dde5506a2a4c013e8bcdfa", size = 2592645, upload-time = "2026-02-17T14:22:02.869Z" }, + { url = "https://files.pythonhosted.org/packages/80/ba/eae13acaad479f522db853e8b1ccd695a7bc8da2b9685c1d70a3b318df89/dearpygui-2.2-cp312-cp312-win_amd64.whl", hash = "sha256:7d399543b5a26ab6426ef3bbd776e55520b491b3e169647bde5e6b2de3701b35", size = 1830531, upload-time = "2026-02-17T14:21:43.386Z" }, + { url = "https://files.pythonhosted.org/packages/18/ab/eb8070ca8fd881d4a9ac49fca5fb7b54ce66cc2742afa38e59d72b2c2dec/dearpygui-2.2-cp313-cp313-macosx_13_0_arm64.whl", hash = "sha256:084c309c56d3e05fcf75eef872df6df97f5e3e19da5ecad393a57cf7a5e56294", size = 1931423, upload-time = "2026-02-17T14:21:56.397Z" }, + { url = "https://files.pythonhosted.org/packages/bc/03/5988d5f4cf3ddc7c3d886623bb904b76c5f5f628a0256ac53d848df33cf7/dearpygui-2.2-cp313-cp313-manylinux1_x86_64.whl", hash = "sha256:05d8c18a0134d72f680e333c80ccab264351170293f86a05f5a0e14222992f27", size = 2592542, upload-time = "2026-02-17T14:22:03.949Z" }, + { url = "https://files.pythonhosted.org/packages/6e/5a/573df5f7277a13b5044daa9a27797fbd4e766da03cab6462a151b557727c/dearpygui-2.2-cp313-cp313-win_amd64.whl", hash = "sha256:500087e88d61b4ef0c841f30b12a05f5128774db3883fde7ff7c6172f03f6d79", size = 1830558, upload-time = "2026-02-17T14:21:44.551Z" }, + { url = "https://files.pythonhosted.org/packages/8b/76/3ccaec465021b647f13c83be42a635043a08255076984a658ed691701498/dearpygui-2.2-cp314-cp314-macosx_13_0_arm64.whl", hash = "sha256:22451146968729429ba37afa2602957dfefc03ff92dcc627dd4d85ba3f93e771", size = 1931385, upload-time = "2026-02-17T14:21:58.193Z" }, + { url = "https://files.pythonhosted.org/packages/52/ac/8e591f33a712563742fe77b0731c1c900fe2fcc3d3e75bd4c7d8e60057a8/dearpygui-2.2-cp314-cp314-manylinux1_x86_64.whl", hash = "sha256:dcc9377d8d9fe27f659ae6b016fe96aa37d8b26b57ce60c47985290e1be7801e", size = 2592691, upload-time = "2026-02-17T14:22:05.191Z" }, + { url = "https://files.pythonhosted.org/packages/f8/03/aeb4ebe09a0240c8c9337018d2ac3e087fd911f6051a3bb0131248fbd942/dearpygui-2.2-cp314-cp314-win_amd64.whl", hash = "sha256:fe3c8dc37be3ddce0356afb0c16721c0e485a4c94a831886935a0692bb9a9966", size = 1889279, upload-time = "2026-02-17T14:21:46.16Z" }, +] [[package]] name = "duckdb" @@ -165,7 +197,8 @@ name = "numpy" version = "2.4.3" source = { registry = "https://pypi.org/simple" } resolution-markers = [ - "python_full_version >= '3.11'", + "python_full_version >= '3.12'", + "python_full_version == '3.11.*'", ] sdist = { url = "https://files.pythonhosted.org/packages/10/8b/c265f4823726ab832de836cdd184d0986dcf94480f81e8739692a7ac7af2/numpy-2.4.3.tar.gz", hash = "sha256:483a201202b73495f00dbc83796c6ae63137a9bdade074f7648b3e32613412dd", size = 20727743, upload-time = "2026-03-09T07:58:53.426Z" } wheels = [ @@ -289,6 +322,11 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/88/95/608f665226bca68b736b79e457fded9a2a38c4f4379a4a7614303d9db3bc/protobuf-7.34.1-py3-none-any.whl", hash = "sha256:bb3812cd53aefea2b028ef42bd780f5b96407247f20c6ef7c679807e9d188f11", size = 170715, upload-time = "2026-03-20T17:34:45.384Z" }, ] +[[package]] +name = "rvl-impl" +version = "0.1.0" +source = { git = "https://github.com/crosstyan/rvl-impl.git?rev=74308bcaf184cb39428237e8f4f99a67a6de22d9#74308bcaf184cb39428237e8f4f99a67a6de22d9" } + [[package]] name = "wcwidth" version = "0.6.0"