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
This commit is contained in:
@@ -265,12 +265,51 @@ uv run python scripts/zed_batch_svo_to_mcap.py \
|
|||||||
|
|
||||||
The batch MCAP wrapper writes `<segment>/<segment>.mcap` by default, skips existing outputs unless told otherwise, and returns a nonzero exit code if any segment fails.
|
The batch MCAP wrapper writes `<segment>/<segment>.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.
|
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.
|
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.
|
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
|
### 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.
|
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.
|
||||||
|
|||||||
+43
-3
@@ -1,9 +1,10 @@
|
|||||||
# MCAP Layout
|
# MCAP Layout
|
||||||
|
|
||||||
`cvmmap-streamer` writes two related MCAP layouts:
|
`cvmmap-streamer` writes three related MCAP layouts:
|
||||||
|
|
||||||
- single-camera MCAP export
|
- 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.
|
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.
|
`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 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.
|
`/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.
|
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
|
## Corruption And Partial Bundles
|
||||||
|
|
||||||
Bundled `nearest` export is resilient to ZED `CORRUPTED FRAME` runs:
|
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
|
- corruption is skipped internally until recovery
|
||||||
- only fully present, threshold-qualified groups are emitted
|
- 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
|
## Validation Expectations
|
||||||
|
|
||||||
For single-camera MCAP files, the current validation contract is:
|
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.
|
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.
|
||||||
|
|||||||
@@ -12,5 +12,11 @@ dependencies = [
|
|||||||
"zstandard>=0.23",
|
"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]
|
[tool.uv]
|
||||||
package = false
|
package = false
|
||||||
|
|||||||
@@ -112,7 +112,7 @@ def record_single_camera_topic(
|
|||||||
|
|
||||||
|
|
||||||
def probe_single_camera_output(path: Path) -> batch.OutputProbeResult:
|
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":
|
if base_probe.status != "valid":
|
||||||
return base_probe
|
return base_probe
|
||||||
|
|
||||||
@@ -210,6 +210,7 @@ def summarize_mcap(path: Path) -> McapSummary:
|
|||||||
camera_labels: set[str] = set()
|
camera_labels: set[str] = set()
|
||||||
saw_single_camera_topic = False
|
saw_single_camera_topic = False
|
||||||
saw_namespaced_camera_topic = False
|
saw_namespaced_camera_topic = False
|
||||||
|
saw_bundle_manifest = False
|
||||||
|
|
||||||
with path.open("rb") as stream:
|
with path.open("rb") as stream:
|
||||||
reader = reader_module.make_reader(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
|
schema_name = schema.name if schema is not None else None
|
||||||
if topic == BUNDLE_TOPIC:
|
if topic == BUNDLE_TOPIC:
|
||||||
summary.layout = "bundled"
|
summary.layout = "bundled"
|
||||||
|
saw_bundle_manifest = True
|
||||||
if schema is None or schema.name != "cvmmap_streamer.BundleManifest":
|
if schema is None or schema.name != "cvmmap_streamer.BundleManifest":
|
||||||
summary.validation_status = "invalid"
|
summary.validation_status = "invalid"
|
||||||
summary.validation_reason = f"bundle topic '{BUNDLE_TOPIC}' is missing the BundleManifest schema"
|
summary.validation_reason = f"bundle topic '{BUNDLE_TOPIC}' is missing the BundleManifest schema"
|
||||||
@@ -257,7 +259,7 @@ def summarize_mcap(path: Path) -> McapSummary:
|
|||||||
continue
|
continue
|
||||||
saw_namespaced_camera_topic = True
|
saw_namespaced_camera_topic = True
|
||||||
if summary.layout == "unknown":
|
if summary.layout == "unknown":
|
||||||
summary.layout = "bundled"
|
summary.layout = "copy"
|
||||||
camera_labels.add(label)
|
camera_labels.add(label)
|
||||||
stats = summary.camera_stats.setdefault(label, CameraSummary())
|
stats = summary.camera_stats.setdefault(label, CameraSummary())
|
||||||
if stream_kind == "video":
|
if stream_kind == "video":
|
||||||
@@ -276,9 +278,12 @@ def summarize_mcap(path: Path) -> McapSummary:
|
|||||||
if saw_single_camera_topic and saw_namespaced_camera_topic:
|
if saw_single_camera_topic and saw_namespaced_camera_topic:
|
||||||
summary.layout = "mixed"
|
summary.layout = "mixed"
|
||||||
summary.validation_status = "invalid"
|
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
|
return summary
|
||||||
|
|
||||||
|
if saw_namespaced_camera_topic and not saw_bundle_manifest and summary.layout == "bundled":
|
||||||
|
summary.layout = "copy"
|
||||||
|
|
||||||
if summary.layout == "single-camera":
|
if summary.layout == "single-camera":
|
||||||
summary.camera_labels = ("camera",)
|
summary.camera_labels = ("camera",)
|
||||||
probe = probe_single_camera_output(path)
|
probe = probe_single_camera_output(path)
|
||||||
@@ -294,6 +299,7 @@ def summarize_mcap(path: Path) -> McapSummary:
|
|||||||
probe = batch.probe_output(
|
probe = batch.probe_output(
|
||||||
path,
|
path,
|
||||||
summary.camera_labels,
|
summary.camera_labels,
|
||||||
|
layout=summary.layout,
|
||||||
bundle_topic=BUNDLE_TOPIC if summary.layout == "bundled" else None,
|
bundle_topic=BUNDLE_TOPIC if summary.layout == "bundled" else None,
|
||||||
)
|
)
|
||||||
summary.validation_status = probe.status
|
summary.validation_status = probe.status
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@@ -36,6 +36,7 @@ class BatchConfig:
|
|||||||
depth_mode: str
|
depth_mode: str
|
||||||
depth_size: str
|
depth_size: str
|
||||||
bundle_policy: str
|
bundle_policy: str
|
||||||
|
copy_range: str
|
||||||
bundle_topic: str | None
|
bundle_topic: str | None
|
||||||
with_pose: bool
|
with_pose: bool
|
||||||
pose_config: Path | None
|
pose_config: Path | None
|
||||||
@@ -506,8 +507,10 @@ def command_for_job(job: ConversionJob, config: BatchConfig, encoder_device: str
|
|||||||
config.depth_size,
|
config.depth_size,
|
||||||
"--bundle-policy",
|
"--bundle-policy",
|
||||||
config.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])
|
command.extend(["--bundle-topic", config.bundle_topic])
|
||||||
if config.with_pose:
|
if config.with_pose:
|
||||||
command.append("--with-pose")
|
command.append("--with-pose")
|
||||||
@@ -616,6 +619,7 @@ def probe_output(
|
|||||||
output_path: Path,
|
output_path: Path,
|
||||||
camera_labels: tuple[str, ...],
|
camera_labels: tuple[str, ...],
|
||||||
*,
|
*,
|
||||||
|
layout: str,
|
||||||
bundle_topic: str | None,
|
bundle_topic: str | None,
|
||||||
) -> OutputProbeResult:
|
) -> OutputProbeResult:
|
||||||
if not output_path.is_file():
|
if not output_path.is_file():
|
||||||
@@ -623,7 +627,7 @@ def probe_output(
|
|||||||
|
|
||||||
reader_module = load_mcap_reader()
|
reader_module = load_mcap_reader()
|
||||||
expected_topics = required_topics_for(camera_labels)
|
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:
|
if require_bundle:
|
||||||
expected_topics.add(bundle_topic or "/bundle")
|
expected_topics.add(bundle_topic or "/bundle")
|
||||||
found_topics: set[str] = set()
|
found_topics: set[str] = set()
|
||||||
@@ -636,6 +640,12 @@ def probe_output(
|
|||||||
with output_path.open("rb") as stream:
|
with output_path.open("rb") as stream:
|
||||||
reader = reader_module.make_reader(stream)
|
reader = reader_module.make_reader(stream)
|
||||||
for schema, channel, message in reader.iter_messages():
|
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:
|
if channel.topic in expected_topics:
|
||||||
found_topics.add(channel.topic)
|
found_topics.add(channel.topic)
|
||||||
if channel.topic.endswith("/video"):
|
if channel.topic.endswith("/video"):
|
||||||
@@ -733,6 +743,17 @@ def probe_output(
|
|||||||
f"bundle_present={present_count} depth_messages={depth_counts[label]}"
|
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")
|
return OutputProbeResult(output_path=output_path, status="valid")
|
||||||
|
|
||||||
|
|
||||||
@@ -1156,11 +1177,18 @@ def build_worker_slots(
|
|||||||
)
|
)
|
||||||
@click.option(
|
@click.option(
|
||||||
"--bundle-policy",
|
"--bundle-policy",
|
||||||
type=click.Choice(("nearest", "strict")),
|
type=click.Choice(("nearest", "strict", "copy")),
|
||||||
default="nearest",
|
default="nearest",
|
||||||
show_default=True,
|
show_default=True,
|
||||||
help="Bundling policy for multi-camera MCAP export.",
|
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(
|
@click.option(
|
||||||
"--bundle-topic",
|
"--bundle-topic",
|
||||||
default="/bundle",
|
default="/bundle",
|
||||||
@@ -1227,6 +1255,7 @@ def main(
|
|||||||
depth_mode: str,
|
depth_mode: str,
|
||||||
depth_size: str,
|
depth_size: str,
|
||||||
bundle_policy: str,
|
bundle_policy: str,
|
||||||
|
copy_range: str,
|
||||||
bundle_topic: str,
|
bundle_topic: str,
|
||||||
with_pose: bool,
|
with_pose: bool,
|
||||||
pose_config: Path | None,
|
pose_config: Path | None,
|
||||||
@@ -1236,9 +1265,16 @@ def main(
|
|||||||
sync_tolerance_ms: float | None,
|
sync_tolerance_ms: float | None,
|
||||||
progress_ui: str,
|
progress_ui: str,
|
||||||
) -> None:
|
) -> 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:
|
if report_existing and dry_run:
|
||||||
raise click.ClickException("--report-existing and --dry-run are mutually exclusive")
|
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)
|
binary_path = None if report_existing else locate_binary(zed_bin)
|
||||||
sources = resolve_sources(input_dir, segment_dirs, segments_csv, csv_root, recursive)
|
sources = resolve_sources(input_dir, segment_dirs, segments_csv, csv_root, recursive)
|
||||||
@@ -1261,7 +1297,8 @@ def main(
|
|||||||
depth_mode=depth_mode,
|
depth_mode=depth_mode,
|
||||||
depth_size=depth_size,
|
depth_size=depth_size,
|
||||||
bundle_policy=bundle_policy,
|
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,
|
with_pose=with_pose,
|
||||||
pose_config=pose_config.expanduser().resolve() if pose_config is not None else None,
|
pose_config=pose_config.expanduser().resolve() if pose_config is not None else None,
|
||||||
world_frame_id=world_frame_id,
|
world_frame_id=world_frame_id,
|
||||||
@@ -1316,7 +1353,12 @@ def main(
|
|||||||
continue
|
continue
|
||||||
|
|
||||||
if report_existing:
|
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":
|
if probe_result.status == "valid":
|
||||||
valid_existing.append(probe_result)
|
valid_existing.append(probe_result)
|
||||||
elif probe_result.status == "invalid":
|
elif probe_result.status == "invalid":
|
||||||
@@ -1331,7 +1373,12 @@ def main(
|
|||||||
continue
|
continue
|
||||||
|
|
||||||
if config.probe_existing:
|
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":
|
if probe_result.status == "valid":
|
||||||
valid_existing.append(probe_result)
|
valid_existing.append(probe_result)
|
||||||
skipped_results.append(
|
skipped_results.append(
|
||||||
|
|||||||
+470
-183
@@ -56,11 +56,14 @@ struct CliOptions {
|
|||||||
std::string depth_mode{"neural_plus"};
|
std::string depth_mode{"neural_plus"};
|
||||||
std::string depth_size{"optimal"};
|
std::string depth_size{"optimal"};
|
||||||
std::string bundle_policy{"nearest"};
|
std::string bundle_policy{"nearest"};
|
||||||
|
std::string copy_range{"common"};
|
||||||
std::string bundle_topic{"/bundle"};
|
std::string bundle_topic{"/bundle"};
|
||||||
bool with_pose{false};
|
bool with_pose{false};
|
||||||
std::uint32_t start_frame{0};
|
std::uint32_t start_frame{0};
|
||||||
|
bool has_start_frame{false};
|
||||||
std::uint32_t end_frame{0};
|
std::uint32_t end_frame{0};
|
||||||
bool has_end_frame{false};
|
bool has_end_frame{false};
|
||||||
|
bool has_bundle_topic{false};
|
||||||
std::string frame_id{"camera"};
|
std::string frame_id{"camera"};
|
||||||
std::string video_topic{"/camera/video"};
|
std::string video_topic{"/camera/video"};
|
||||||
std::string depth_topic{"/camera/depth"};
|
std::string depth_topic{"/camera/depth"};
|
||||||
@@ -173,6 +176,17 @@ struct GrabResult {
|
|||||||
int last_corrupted_position{-1};
|
int last_corrupted_position{-1};
|
||||||
};
|
};
|
||||||
|
|
||||||
|
enum class MultiCameraExportPolicy {
|
||||||
|
Nearest,
|
||||||
|
Strict,
|
||||||
|
Copy,
|
||||||
|
};
|
||||||
|
|
||||||
|
enum class CopyRangeMode {
|
||||||
|
Common,
|
||||||
|
Full,
|
||||||
|
};
|
||||||
|
|
||||||
[[nodiscard]]
|
[[nodiscard]]
|
||||||
constexpr int exit_code(const ToolExitCode code) {
|
constexpr int exit_code(const ToolExitCode code) {
|
||||||
return static_cast<int>(code);
|
return static_cast<int>(code);
|
||||||
@@ -324,15 +338,61 @@ std::expected<sl::Resolution, std::string> parse_depth_size(const std::string_vi
|
|||||||
}
|
}
|
||||||
|
|
||||||
[[nodiscard]]
|
[[nodiscard]]
|
||||||
std::expected<cvmmap_streamer::record::BundlePolicy, std::string> parse_bundle_policy(const std::string_view raw) {
|
std::expected<MultiCameraExportPolicy, std::string> parse_bundle_policy(const std::string_view raw) {
|
||||||
const auto normalized = lowercase(std::string(raw));
|
const auto normalized = lowercase(std::string(raw));
|
||||||
if (normalized == "nearest") {
|
if (normalized == "nearest") {
|
||||||
return cvmmap_streamer::record::BundlePolicy::Nearest;
|
return MultiCameraExportPolicy::Nearest;
|
||||||
}
|
}
|
||||||
if (normalized == "strict") {
|
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<CopyRangeMode, std::string> 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]]
|
[[nodiscard]]
|
||||||
@@ -1415,6 +1475,126 @@ std::expected<std::optional<std::uint64_t>, std::string> next_synced_group_times
|
|||||||
return std::optional<std::uint64_t>{};
|
return std::optional<std::uint64_t>{};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
[[nodiscard]]
|
||||||
|
std::expected<void, std::string> 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<const std::uint8_t>(
|
||||||
|
left_frame.getPtr<sl::uchar1>(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<std::uint32_t>(depth_frame.getWidth());
|
||||||
|
const auto depth_height = static_cast<std::uint32_t>(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<std::size_t>(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<std::vector<std::uint16_t>> compact_depth{};
|
||||||
|
std::span<const std::uint16_t> depth_pixels{};
|
||||||
|
if (depth_step_bytes == packed_depth_bytes) {
|
||||||
|
depth_pixels = std::span<const std::uint16_t>(
|
||||||
|
depth_frame.getPtr<sl::ushort1>(sl::MEM::CPU),
|
||||||
|
static_cast<std::size_t>(depth_width) * static_cast<std::size_t>(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]]
|
[[nodiscard]]
|
||||||
std::expected<void, std::string> encode_and_write_group(
|
std::expected<void, std::string> encode_and_write_group(
|
||||||
cvmmap_streamer::record::MultiMcapRecordSink &sink,
|
cvmmap_streamer::record::MultiMcapRecordSink &sink,
|
||||||
@@ -1472,114 +1652,15 @@ std::expected<void, std::string> encode_and_write_group(
|
|||||||
const auto &left_frame = selected_left_frame(stream, selection);
|
const auto &left_frame = selected_left_frame(stream, selection);
|
||||||
const auto &depth_frame = selected_depth_frame(stream, selection);
|
const auto &depth_frame = selected_depth_frame(stream, selection);
|
||||||
const auto &tracking = selected_tracking(stream, selection);
|
const auto &tracking = selected_tracking(stream, selection);
|
||||||
|
if (auto write = encode_and_write_sample(
|
||||||
const auto video_step_bytes = left_frame.getStepBytes(sl::MEM::CPU);
|
sink,
|
||||||
const auto video_bytes = std::span<const std::uint8_t>(
|
stream,
|
||||||
left_frame.getPtr<sl::uchar1>(sl::MEM::CPU),
|
options,
|
||||||
video_step_bytes * left_frame.getHeight());
|
*selection.timestamp_ns,
|
||||||
cvmmap_streamer::encode::RawVideoFrame raw_video{
|
left_frame,
|
||||||
.info = stream.frame_info,
|
depth_frame,
|
||||||
.source_timestamp_ns = *selection.timestamp_ns,
|
tracking); !write) {
|
||||||
.row_stride_bytes = video_step_bytes,
|
return write;
|
||||||
.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<std::uint32_t>(depth_frame.getWidth());
|
|
||||||
const auto depth_height = static_cast<std::uint32_t>(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<std::size_t>(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<std::vector<std::uint16_t>> compact_depth{};
|
|
||||||
std::span<const std::uint16_t> depth_pixels{};
|
|
||||||
if (depth_step_bytes == packed_depth_bytes) {
|
|
||||||
depth_pixels = std::span<const std::uint16_t>(
|
|
||||||
depth_frame.getPtr<sl::ushort1>(sl::MEM::CPU),
|
|
||||||
static_cast<std::size_t>(depth_width) * static_cast<std::size_t>(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());
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return {};
|
return {};
|
||||||
@@ -1617,30 +1698,84 @@ std::expected<void, std::string> advance_after_emit(std::vector<CameraStream> &s
|
|||||||
}
|
}
|
||||||
|
|
||||||
[[nodiscard]]
|
[[nodiscard]]
|
||||||
double bundled_progress_fraction(
|
bool is_copy_stream_in_range(
|
||||||
const std::uint64_t common_start_ts,
|
const CameraStream &stream,
|
||||||
const std::uint64_t common_end_ts,
|
const std::optional<std::uint64_t> range_end_ts) {
|
||||||
const std::uint64_t group_timestamp_ns) {
|
if (stream.current_timestamp_ns == 0) {
|
||||||
if (common_end_ts <= common_start_ts) {
|
return false;
|
||||||
return 1.0;
|
|
||||||
}
|
}
|
||||||
const auto bounded_timestamp = std::clamp(group_timestamp_ns, common_start_ts, common_end_ts);
|
if (range_end_ts.has_value() && stream.current_timestamp_ns > *range_end_ts) {
|
||||||
return static_cast<double>(bounded_timestamp - common_start_ts) /
|
return false;
|
||||||
static_cast<double>(common_end_ts - common_start_ts);
|
}
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
[[nodiscard]]
|
[[nodiscard]]
|
||||||
std::string bundled_progress_detail(
|
std::optional<std::size_t> next_copy_stream_index(
|
||||||
const std::uint64_t common_start_ts,
|
const std::vector<CameraStream> &streams,
|
||||||
const std::uint64_t common_end_ts,
|
const std::optional<std::uint64_t> range_end_ts) {
|
||||||
const std::uint64_t group_timestamp_ns) {
|
std::optional<std::size_t> best_index{};
|
||||||
const auto bounded_timestamp = std::clamp(group_timestamp_ns, common_start_ts, common_end_ts);
|
for (std::size_t index = 0; index < streams.size(); ++index) {
|
||||||
const double elapsed_seconds = static_cast<double>(bounded_timestamp - common_start_ts) / 1'000'000'000.0;
|
const auto &stream = streams[index];
|
||||||
const double total_seconds = common_end_ts > common_start_ts
|
if (!is_copy_stream_in_range(stream, range_end_ts)) {
|
||||||
? static_cast<double>(common_end_ts - common_start_ts) / 1'000'000'000.0
|
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<void, std::string> 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<double>(bounded_timestamp - window_start_ts) /
|
||||||
|
static_cast<double>(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<double>(bounded_timestamp - window_start_ts) / 1'000'000'000.0;
|
||||||
|
const double total_seconds = window_end_ts > window_start_ts
|
||||||
|
? static_cast<double>(window_end_ts - window_start_ts) / 1'000'000'000.0
|
||||||
: 0.0;
|
: 0.0;
|
||||||
char buffer[96]{};
|
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);
|
return std::string(buffer);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -2186,7 +2321,22 @@ int run_multi_source(
|
|||||||
const sl::DEPTH_MODE depth_mode,
|
const sl::DEPTH_MODE depth_mode,
|
||||||
const sl::Resolution depth_size,
|
const sl::Resolution depth_size,
|
||||||
const PoseTrackingOptions &pose_tracking,
|
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) {
|
if (options.has_end_frame && options.end_frame < options.start_frame) {
|
||||||
spdlog::error(
|
spdlog::error(
|
||||||
"invalid bundled range: start-frame={} end-frame={}",
|
"invalid bundled range: start-frame={} end-frame={}",
|
||||||
@@ -2228,7 +2378,20 @@ int run_multi_source(
|
|||||||
[](const auto &left, const auto &right) {
|
[](const auto &left, const auto &right) {
|
||||||
return left.last_timestamp_ns < right.last_timestamp_ns;
|
return left.last_timestamp_ns < right.last_timestamp_ns;
|
||||||
})->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);
|
close_camera_streams(streams);
|
||||||
spdlog::error("synced time window is empty: start_ts={} end_ts={}", common_start_ts, common_end_ts);
|
spdlog::error("synced time window is empty: start_ts={} end_ts={}", common_start_ts, common_end_ts);
|
||||||
return exit_code(ToolExitCode::UsageError);
|
return exit_code(ToolExitCode::UsageError);
|
||||||
@@ -2240,24 +2403,33 @@ int run_multi_source(
|
|||||||
[](const auto &left, const auto &right) {
|
[](const auto &left, const auto &right) {
|
||||||
return left.nominal_frame_period_ns < right.nominal_frame_period_ns;
|
return left.nominal_frame_period_ns < right.nominal_frame_period_ns;
|
||||||
})->nominal_frame_period_ns;
|
})->nominal_frame_period_ns;
|
||||||
const auto bundle_policy_name = bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest
|
const auto bundle_policy_name = multi_camera_policy_name(bundle_policy);
|
||||||
? "nearest"
|
|
||||||
: "strict";
|
|
||||||
const auto tolerance_ns = options.has_sync_tolerance
|
const auto tolerance_ns = options.has_sync_tolerance
|
||||||
? static_cast<std::uint64_t>(std::llround(options.sync_tolerance_ms * 1'000'000.0))
|
? static_cast<std::uint64_t>(std::llround(options.sync_tolerance_ms * 1'000'000.0))
|
||||||
: std::max<std::uint64_t>(1, slowest_period_ns);
|
: std::max<std::uint64_t>(1, slowest_period_ns);
|
||||||
spdlog::info(
|
if (bundle_policy == MultiCameraExportPolicy::Copy) {
|
||||||
"multi-camera bundle window start_ts={} end_ts={} policy={} bundle_period_ns={} tolerance_ns={}",
|
const auto range_start_ts = copy_range_mode == CopyRangeMode::Common ? common_start_ts : full_start_ts;
|
||||||
common_start_ts,
|
const auto range_end_ts = copy_range_mode == CopyRangeMode::Common ? common_end_ts : full_end_ts;
|
||||||
common_end_ts,
|
spdlog::info(
|
||||||
bundle_policy_name,
|
"multi-camera copy window start_ts={} end_ts={} policy={} copy_range={}",
|
||||||
slowest_period_ns,
|
range_start_ts,
|
||||||
tolerance_ns);
|
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 render_progress = stderr_supports_progress_bar();
|
||||||
const auto total_timeline_bundles = common_end_ts >= common_start_ts
|
const auto total_timeline_bundles = common_end_ts >= common_start_ts
|
||||||
? ((common_end_ts - common_start_ts) / slowest_period_ns) + 1
|
? ((common_end_ts - common_start_ts) / slowest_period_ns) + 1
|
||||||
: 0;
|
: 0;
|
||||||
if (bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest &&
|
if (bundle_policy == MultiCameraExportPolicy::Nearest &&
|
||||||
options.start_frame >= total_timeline_bundles) {
|
options.start_frame >= total_timeline_bundles) {
|
||||||
close_camera_streams(streams);
|
close_camera_streams(streams);
|
||||||
spdlog::error(
|
spdlog::error(
|
||||||
@@ -2266,7 +2438,7 @@ int run_multi_source(
|
|||||||
total_timeline_bundles);
|
total_timeline_bundles);
|
||||||
return exit_code(ToolExitCode::UsageError);
|
return exit_code(ToolExitCode::UsageError);
|
||||||
}
|
}
|
||||||
if (bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest &&
|
if (bundle_policy == MultiCameraExportPolicy::Nearest &&
|
||||||
options.has_end_frame &&
|
options.has_end_frame &&
|
||||||
options.end_frame >= total_timeline_bundles) {
|
options.end_frame >= total_timeline_bundles) {
|
||||||
close_camera_streams(streams);
|
close_camera_streams(streams);
|
||||||
@@ -2279,28 +2451,30 @@ int run_multi_source(
|
|||||||
|
|
||||||
const auto selected_end_bundle = options.has_end_frame
|
const auto selected_end_bundle = options.has_end_frame
|
||||||
? static_cast<std::uint64_t>(options.end_frame)
|
? static_cast<std::uint64_t>(options.end_frame)
|
||||||
: (bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest
|
: (bundle_policy == MultiCameraExportPolicy::Nearest
|
||||||
? total_timeline_bundles - 1
|
? total_timeline_bundles - 1
|
||||||
: 0);
|
: 0);
|
||||||
const auto selected_total_groups = options.has_end_frame
|
const auto selected_total_groups = options.has_end_frame
|
||||||
? static_cast<std::uint64_t>(options.end_frame - options.start_frame) + 1
|
? static_cast<std::uint64_t>(options.end_frame - options.start_frame) + 1
|
||||||
: (bundle_policy == cvmmap_streamer::record::BundlePolicy::Nearest
|
: (bundle_policy == MultiCameraExportPolicy::Nearest
|
||||||
? total_timeline_bundles - static_cast<std::uint64_t>(options.start_frame)
|
? total_timeline_bundles - static_cast<std::uint64_t>(options.start_frame)
|
||||||
: 0);
|
: 0);
|
||||||
const bool exact_group_progress =
|
const bool exact_group_progress =
|
||||||
render_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 =
|
const bool approximate_time_progress =
|
||||||
render_progress &&
|
render_progress &&
|
||||||
bundle_policy == cvmmap_streamer::record::BundlePolicy::Strict &&
|
(bundle_policy == MultiCameraExportPolicy::Strict || bundle_policy == MultiCameraExportPolicy::Copy) &&
|
||||||
!options.has_end_frame;
|
(bundle_policy == MultiCameraExportPolicy::Copy || !options.has_end_frame);
|
||||||
ProgressBar progress{exact_group_progress ? selected_total_groups : 0};
|
ProgressBar progress{exact_group_progress ? selected_total_groups : 0};
|
||||||
double last_progress_fraction = 0.0;
|
double last_progress_fraction = 0.0;
|
||||||
std::string last_progress_detail{};
|
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<std::uint64_t>(options.start_frame) * slowest_period_ns
|
? common_start_ts + static_cast<std::uint64_t>(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) {
|
if (auto synced = sync_streams_to_timestamp(streams, initial_target_ts); !synced) {
|
||||||
close_camera_streams(streams);
|
close_camera_streams(streams);
|
||||||
if (synced.error() == "interrupted") {
|
if (synced.error() == "interrupted") {
|
||||||
@@ -2310,7 +2484,7 @@ int run_multi_source(
|
|||||||
return exit_code(ToolExitCode::RuntimeError);
|
return exit_code(ToolExitCode::RuntimeError);
|
||||||
}
|
}
|
||||||
auto effective_progress_start_ts = initial_target_ts;
|
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) {
|
if (auto skipped_to = skip_bundled_start_groups(streams, options.start_frame, tolerance_ns, common_end_ts); !skipped_to) {
|
||||||
close_camera_streams(streams);
|
close_camera_streams(streams);
|
||||||
if (skipped_to.error() == "interrupted") {
|
if (skipped_to.error() == "interrupted") {
|
||||||
@@ -2326,7 +2500,7 @@ int run_multi_source(
|
|||||||
auto sink = cvmmap_streamer::record::MultiMcapRecordSink::create(
|
auto sink = cvmmap_streamer::record::MultiMcapRecordSink::create(
|
||||||
output_path.string(),
|
output_path.string(),
|
||||||
compression,
|
compression,
|
||||||
options.bundle_topic);
|
bundle_policy == MultiCameraExportPolicy::Copy ? "" : options.bundle_topic);
|
||||||
if (!sink) {
|
if (!sink) {
|
||||||
if (approximate_time_progress) {
|
if (approximate_time_progress) {
|
||||||
progress.finish_fraction(last_progress_fraction, false, last_progress_detail);
|
progress.finish_fraction(last_progress_fraction, false, last_progress_detail);
|
||||||
@@ -2350,7 +2524,8 @@ int run_multi_source(
|
|||||||
}
|
}
|
||||||
|
|
||||||
std::uint64_t emitted_groups{0};
|
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) {
|
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")) {
|
if (log_shutdown_request(shutdown_logged, "multi-camera export")) {
|
||||||
interrupted = true;
|
interrupted = true;
|
||||||
@@ -2373,7 +2548,7 @@ int run_multi_source(
|
|||||||
*sink,
|
*sink,
|
||||||
streams,
|
streams,
|
||||||
options,
|
options,
|
||||||
bundle_policy,
|
manifest_bundle_policy(bundle_policy),
|
||||||
bundle_index,
|
bundle_index,
|
||||||
bundle_timestamp_ns,
|
bundle_timestamp_ns,
|
||||||
*selections); !write) {
|
*selections); !write) {
|
||||||
@@ -2393,7 +2568,7 @@ int run_multi_source(
|
|||||||
emitted_groups += 1;
|
emitted_groups += 1;
|
||||||
progress.update(emitted_groups);
|
progress.update(emitted_groups);
|
||||||
}
|
}
|
||||||
} else {
|
} else if (bundle_policy == MultiCameraExportPolicy::Strict) {
|
||||||
while (true) {
|
while (true) {
|
||||||
if (log_shutdown_request(shutdown_logged, "multi-camera export")) {
|
if (log_shutdown_request(shutdown_logged, "multi-camera export")) {
|
||||||
interrupted = true;
|
interrupted = true;
|
||||||
@@ -2424,7 +2599,7 @@ int run_multi_source(
|
|||||||
*sink,
|
*sink,
|
||||||
streams,
|
streams,
|
||||||
options,
|
options,
|
||||||
bundle_policy,
|
manifest_bundle_policy(bundle_policy),
|
||||||
bundle_index,
|
bundle_index,
|
||||||
**group_timestamp,
|
**group_timestamp,
|
||||||
selections); !write) {
|
selections); !write) {
|
||||||
@@ -2440,8 +2615,12 @@ int run_multi_source(
|
|||||||
}
|
}
|
||||||
emitted_groups += 1;
|
emitted_groups += 1;
|
||||||
if (approximate_time_progress) {
|
if (approximate_time_progress) {
|
||||||
last_progress_fraction = bundled_progress_fraction(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 = bundled_progress_detail(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);
|
progress.update_fraction(last_progress_fraction, last_progress_detail);
|
||||||
} else {
|
} else {
|
||||||
progress.update(emitted_groups);
|
progress.update(emitted_groups);
|
||||||
@@ -2466,6 +2645,61 @@ int run_multi_source(
|
|||||||
return exit_code(ToolExitCode::RuntimeError);
|
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<std::uint64_t>{common_end_ts}
|
||||||
|
: std::optional<std::uint64_t>{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) {
|
for (auto &stream : streams) {
|
||||||
@@ -2486,20 +2720,30 @@ int run_multi_source(
|
|||||||
if (approximate_time_progress) {
|
if (approximate_time_progress) {
|
||||||
if (!interrupted) {
|
if (!interrupted) {
|
||||||
last_progress_fraction = 1.0;
|
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);
|
progress.finish_fraction(last_progress_fraction, !interrupted, last_progress_detail);
|
||||||
} else {
|
} else {
|
||||||
progress.finish(emitted_groups, !interrupted);
|
progress.finish(bundle_policy == MultiCameraExportPolicy::Copy ? emitted_samples : emitted_groups, !interrupted);
|
||||||
}
|
}
|
||||||
for (const auto &stream : streams) {
|
for (const auto &stream : streams) {
|
||||||
spdlog::info(
|
spdlog::info(
|
||||||
"bundled {} dropped_frame(s) for {}",
|
"multi-camera export skipped {} frame(s) while aligning {}",
|
||||||
stream.dropped_frames,
|
stream.dropped_frames,
|
||||||
stream.source.label);
|
stream.source.label);
|
||||||
}
|
}
|
||||||
close_camera_streams(streams);
|
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::error_code remove_error{};
|
||||||
std::filesystem::remove(output_path, remove_error);
|
std::filesystem::remove(output_path, remove_error);
|
||||||
if (remove_error) {
|
if (remove_error) {
|
||||||
@@ -2508,29 +2752,58 @@ int run_multi_source(
|
|||||||
output_path.string(),
|
output_path.string(),
|
||||||
remove_error.message());
|
remove_error.message());
|
||||||
}
|
}
|
||||||
spdlog::error(
|
if (bundle_policy == MultiCameraExportPolicy::Copy) {
|
||||||
"no bundled frame groups were found across {} camera(s) for '{}' using policy={}",
|
spdlog::error(
|
||||||
sources.size(),
|
"no camera samples were found across {} camera(s) for '{}' using policy={} copy_range={}",
|
||||||
output_path.string(),
|
sources.size(),
|
||||||
bundle_policy_name);
|
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);
|
return exit_code(ToolExitCode::RuntimeError);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (interrupted) {
|
if (interrupted) {
|
||||||
spdlog::warn(
|
if (bundle_policy == MultiCameraExportPolicy::Copy) {
|
||||||
"gracefully stopped after writing {} bundled frame group(s) across {} camera(s) to '{}'",
|
spdlog::warn(
|
||||||
emitted_groups,
|
"gracefully stopped after writing {} camera sample(s) across {} camera(s) to '{}' using policy={} copy_range={}",
|
||||||
sources.size(),
|
emitted_count,
|
||||||
output_path.string());
|
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();
|
return interrupted_exit_code();
|
||||||
}
|
}
|
||||||
|
|
||||||
spdlog::info(
|
if (bundle_policy == MultiCameraExportPolicy::Copy) {
|
||||||
"wrote {} bundled frame group(s) across {} camera(s) to '{}' using policy={}",
|
spdlog::info(
|
||||||
emitted_groups,
|
"wrote {} camera sample(s) across {} camera(s) to '{}' using policy={} copy_range={}",
|
||||||
sources.size(),
|
emitted_count,
|
||||||
output_path.string(),
|
sources.size(),
|
||||||
bundle_policy_name);
|
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);
|
return exit_code(ToolExitCode::Success);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -2555,9 +2828,15 @@ int main(int argc, char **argv) {
|
|||||||
->check(CLI::IsMember({"neural_light", "neural", "neural_plus"}));
|
->check(CLI::IsMember({"neural_light", "neural", "neural_plus"}));
|
||||||
app.add_option("--depth-size", options.depth_size, "Depth output size (optimal|native|<width>x<height>)")
|
app.add_option("--depth-size", options.depth_size, "Depth output size (optimal|native|<width>x<height>)")
|
||||||
->default_val("optimal");
|
->default_val("optimal");
|
||||||
app.add_option("--bundle-policy", options.bundle_policy, "Bundling policy for multi-camera mode (nearest|strict)")
|
app.add_option("--bundle-policy", options.bundle_policy, "Bundling policy for multi-camera mode (nearest|strict|copy)")
|
||||||
->check(CLI::IsMember({"nearest", "strict"}));
|
->check(CLI::IsMember({"nearest", "strict", "copy"}));
|
||||||
app.add_option(
|
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",
|
"--start-frame",
|
||||||
options.start_frame,
|
options.start_frame,
|
||||||
"First frame/group to export (inclusive): raw SVO frame in single-camera mode, bundle index in multi-camera mode")
|
"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("--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("--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("--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(
|
app.add_option(
|
||||||
"--depth-calibration-topic",
|
"--depth-calibration-topic",
|
||||||
options.depth_calibration_topic,
|
options.depth_calibration_topic,
|
||||||
@@ -2594,7 +2873,9 @@ int main(int argc, char **argv) {
|
|||||||
} catch (const CLI::ParseError &error) {
|
} catch (const CLI::ParseError &error) {
|
||||||
return app.exit(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_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;
|
options.has_sync_tolerance = sync_tolerance_option->count() > 0;
|
||||||
|
|
||||||
auto codec = parse_codec(options.codec);
|
auto codec = parse_codec(options.codec);
|
||||||
@@ -2627,6 +2908,11 @@ int main(int argc, char **argv) {
|
|||||||
spdlog::error("{}", bundle_policy.error());
|
spdlog::error("{}", bundle_policy.error());
|
||||||
return exit_code(ToolExitCode::UsageError);
|
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);
|
auto pose_tracking = load_pose_tracking_options(options);
|
||||||
if (!pose_tracking) {
|
if (!pose_tracking) {
|
||||||
spdlog::error("{}", pose_tracking.error());
|
spdlog::error("{}", pose_tracking.error());
|
||||||
@@ -2663,5 +2949,6 @@ int main(int argc, char **argv) {
|
|||||||
*depth_mode,
|
*depth_mode,
|
||||||
*depth_size,
|
*depth_size,
|
||||||
*pose_tracking,
|
*pose_tracking,
|
||||||
*bundle_policy);
|
*bundle_policy,
|
||||||
|
*copy_range_mode);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -2,7 +2,8 @@ version = 1
|
|||||||
revision = 3
|
revision = 3
|
||||||
requires-python = ">=3.10"
|
requires-python = ">=3.10"
|
||||||
resolution-markers = [
|
resolution-markers = [
|
||||||
"python_full_version >= '3.11'",
|
"python_full_version >= '3.12'",
|
||||||
|
"python_full_version == '3.11.*'",
|
||||||
"python_full_version < '3.11'",
|
"python_full_version < '3.11'",
|
||||||
]
|
]
|
||||||
|
|
||||||
@@ -42,16 +43,47 @@ dependencies = [
|
|||||||
{ name = "zstandard" },
|
{ name = "zstandard" },
|
||||||
]
|
]
|
||||||
|
|
||||||
|
[package.optional-dependencies]
|
||||||
|
viewer = [
|
||||||
|
{ name = "dearpygui" },
|
||||||
|
{ name = "rvl-impl", marker = "python_full_version >= '3.12'" },
|
||||||
|
]
|
||||||
|
|
||||||
[package.metadata]
|
[package.metadata]
|
||||||
requires-dist = [
|
requires-dist = [
|
||||||
{ name = "click", specifier = ">=8.1" },
|
{ name = "click", specifier = ">=8.1" },
|
||||||
|
{ name = "dearpygui", marker = "extra == 'viewer'", specifier = ">=2.2" },
|
||||||
{ name = "duckdb", specifier = ">=1.0" },
|
{ name = "duckdb", specifier = ">=1.0" },
|
||||||
{ name = "numpy", specifier = ">=2.2" },
|
{ name = "numpy", specifier = ">=2.2" },
|
||||||
{ name = "opencv-python-headless", specifier = ">=4.11" },
|
{ name = "opencv-python-headless", specifier = ">=4.11" },
|
||||||
{ name = "progress-table", specifier = ">=3.2" },
|
{ name = "progress-table", specifier = ">=3.2" },
|
||||||
{ name = "protobuf", specifier = ">=5.29" },
|
{ 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" },
|
{ 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]]
|
[[package]]
|
||||||
name = "duckdb"
|
name = "duckdb"
|
||||||
@@ -165,7 +197,8 @@ name = "numpy"
|
|||||||
version = "2.4.3"
|
version = "2.4.3"
|
||||||
source = { registry = "https://pypi.org/simple" }
|
source = { registry = "https://pypi.org/simple" }
|
||||||
resolution-markers = [
|
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" }
|
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 = [
|
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" },
|
{ 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]]
|
[[package]]
|
||||||
name = "wcwidth"
|
name = "wcwidth"
|
||||||
version = "0.6.0"
|
version = "0.6.0"
|
||||||
|
|||||||
Reference in New Issue
Block a user