Skip to content

Nav pt3: Enable PGO topics, Optimize PGO, and add KITTI-360 benchmark scaffolding#2099

Open
jeff-hykin wants to merge 93 commits into
mainfrom
jeff/feat/better_pgo
Open

Nav pt3: Enable PGO topics, Optimize PGO, and add KITTI-360 benchmark scaffolding#2099
jeff-hykin wants to merge 93 commits into
mainfrom
jeff/feat/better_pgo

Conversation

@jeff-hykin
Copy link
Copy Markdown
Member

@jeff-hykin jeff-hykin commented May 15, 2026

Closes #2007

Changes

  1. Make PGO publish loop-transform events and related data (pose graph)
  2. Add a meaninful loop closure benchmark

How to Test

without benchmark

source .venv/bin/activate

# native rebuild
cd dimos/navigation/nav_stack/modules/pgo/cpp && nix build .#default

# unit/integration
uv run pytest dimos/navigation/nav_stack/modules/pgo -v

# slow tests (rosbag + synthetic drift)
./bin/pytest-slow dimos/navigation/nav_stack/modules/pgo -v

With benchmark

The benchmark is KITTI 360 - a standard dataset but its stuck behind a registration page (no public download). Its also 12Gb. https://www.cvlibs.net/datasets/kitti-360/user_login.php

There's no good 100% public loop closure benchmark that I could find.

Not in this PR

  • KITTI-360 actual precision/recall numbers (needs the ~12 GB Test SLAM split downloaded manually).
  • On-start relocalization via Scan Context (the descriptor/ring-key index is already populated — wiring this is a follow-up).
  • Intensity Scan Context / SC++ — would close the gap on reverse-heavy sequences (seq 09), but not needed for the cross-wall sim case.

Contributor License Agreement

  • I have read and approved the CLA.

jeff-hykin added 10 commits May 12, 2026 07:48
… rrb

Native module (cpp/main.cpp) now publishes two new streams on every
keyframe: GraphNodes3D for keyframe optimized poses, LineSegments3D for
odometry (traversability=1.0) and loop-closure (0.4) edges. Both wire
through SimplePGO::keyPoses() + historyPairs() — no changes needed to
simple_pgo.{h,cpp} since the accessors already exist. Native binary
rebuilt cleanly via nix build .#default --no-write-lock-file.

Python (pgo.py) declares matching pgo_graph_nodes / pgo_graph_edges Out
streams so the rerun bridge auto-discovers and logs them.

nav_stack_rerun_config() now picks _agentic_debug_rerun_blueprint when
agentic_debug=True — an rrb.Horizontal layout with a 3D pane and a
dedicated top-down pane (both Spatial3DView over origin="world", named
"3D" and "top_down" so dimos-viewer persists camera state separately).

demo_better_pgo_viz.py composes the cross-wall sim blueprint with
agentic_debug=True so the new layout + pose graph render together. Used
for manual screenshot validation.
Adds visual_override entries for world/pgo_graph_nodes and
world/pgo_graph_edges that mirror the existing FAR pattern: when
agentic_debug=True, the PGO pose graph renders at z=_AGENTIC_DEBUG_LIFT
(3.0m) instead of the default 1.7m, with slightly larger node radii
(0.15) and edge thickness (0.06) so the green keyframe trajectory
stands out clearly above the terrain cloud in the top-down pane.

Verified visually via demo_better_pgo_viz with the cross-wall sim —
green keyframe nodes + edges are now plainly identifiable above
terrain in both the 3D and top_down rerun panels.
rerun's Spatial3DView doesn't have a top-down camera API, so the
"top_down" pane introduced in a7a9be9 was just a duplicate 3D view.
Drop _agentic_debug_rerun_blueprint and use _default_rerun_blueprint
unconditionally — the agentic_debug lift on visual_override is what
actually makes the pose graph and nav markers readable from any angle.
C++ side (main.cpp): when searchForLoopPairs sets m_cache_pairs (i.e.
this keyframe will be incorporated into iSAM2 with a loop factor),
snapshot the current global poses before smoothAndUpdate. After the
update, build a nav_msgs::Path-encoded LoopClosureDeltas message:
position = post.t - r_delta * pre.t, orientation = quaternion(post.R *
pre.R^T). Publish on the new pgo_loop_closure topic. Stderr logs the
event count for live observability.

Python side (pgo.py): declare pgo_loop_closure: Out[NavPath] so the
new topic is registered alongside corrected_odometry/pgo_tf/etc.

Slow test (test_pgo_loop_closure.py): replays og_nav_60s through the
native binary with permissive thresholds (loop_time_thresh=5s,
min_loop_detect_duration=1s, loop_search_radius=2m,
loop_score_thresh=0.5) so the recording reliably triggers loop
closures. Subscribes to pgo_loop_closure, logs each event the moment
it arrives (event #, poses_length, frame_id, first delta), and after
the run validates each event has >0 poses, finite translations
(<100m), and unit-norm quaternions (drift <0.05). Stdout from a run
shows 19 events, sizes 10..35, max |t|=0.0013m, max |q|-1|=1e-6 —
exactly the small-nudge profile expected from a self-consistent
recording.
Replaces the kdtree-on-keyframe-positions loop search with a Scan
Context (Kim & Kim 2018) descriptor-based pipeline:

  1. addKeyPose now also caches a polar-binned (20 rings × 60 sectors)
     max-z descriptor + the per-row mean "ring key" for each keyframe.
     The descriptor is appearance-based and pose-independent, so it
     keeps working even when odometry has drifted enough that the new
     keyframe is no longer "near" its old neighbours in pose-space.

  2. searchForLoopPairs first asks Scan Context for a candidate:
     ring-key L2 distance ranks all past keyframes, top-K are scored
     by column-shifted cosine distance on the full descriptor, the
     best below the threshold (default 0.4) is the candidate. The
     winning column shift is also converted to a yaw rotation and used
     to seed ICP, which dramatically improves convergence on revisits
     that arrive at a different heading from the original pass.

  3. Position-based search is retained as a fallback when SC is
     disabled or finds nothing, so existing behaviour is preserved.

Replaces ~50 lines of position-search with ~30 lines of SC retrieval
in searchForLoopPairs; new scan_context.{h,cpp} (~150 lines, MIT
attribution to upstream irapkaist/scancontext concepts but no source
copied) implements the descriptor + distance.

Side-effect: this makes on-start relocalization a small follow-up
addition — descriptors + ring-keys + poses are now per-keyframe state
that can be serialised, and the SC search path already does
"appearance-based pose recovery without an initial pose guess."

Verified via test_pgo_loop_closure.py: 17 loop-closure events fired
across the og_nav_60s rosbag (was 19 with naive position search; SC
is more selective and rejects two borderline-position matches that
weren't actually visual revisits). All events have valid shape + tiny
quaternion/translation deltas as expected for a self-consistent bag.
…n search misses

Adds CLI args to expose Scan Context config on the native binary
(--use_scan_context, --sc_n_rings, --sc_n_sectors, --sc_max_range_m,
--sc_top_k, --sc_match_threshold).

New slow test test_pgo_synthetic_drift.py:
- Synthesises a 4-wall point-cloud room with two distinctive interior
  columns (so the scene isn't rotationally symmetric).
- Generates an out-and-back trajectory: drives east 8m then returns
  to the origin, heading unchanged.
- Injects DRIFT_AT_REVISIT_M = 5m of additive y-drift into the
  reported odometry, ramped linearly with travelled distance. The
  body-frame scan stays byte-identical between first and second visit
  (same true sensor view of the same scene); the odom pose at revisit
  is 5m offset.
- Runs the native PGO binary twice over the same input:
  * use_scan_context=true  → expect ≥1 loop event
  * use_scan_context=false → expect 0 loop events (drift >> 1m radius)
- Dumps PGO stderr after each run for diagnostics.

Result: SC fires 10 loop closure events on the synthetic trajectory;
position-based search fires 0 — exactly the demonstration of why we
swapped to appearance-based place recognition. Both assertions pass.

Verifies the core SC value prop: appearance-based place recognition
doesn't depend on the (drifted) pose, so it keeps working when the
odometry has wandered far enough that the kdtree-on-positions search
no longer finds neighbours.
Test files now use setup_logger() / logger.info(...) per the
fix_nits rule "no print() calls in tests; use logging if diagnostics
are genuinely needed." Matches the existing test_pgo_rosbag.py
convention. Also drops the now-unused sys import.

Also clears a stale docstring on demo_better_pgo_viz.py: it claimed
the demo enabled a "horizontal 3D + top-down panes" layout, which was
reverted in 1801759 — rerun's Spatial3DView didn't support an
initial camera angle (rrb.EyeControls3D existed at the time but
wasn't used). The remaining value of agentic_debug=True is the visual
override lift, which the new docstring describes accurately.

No behavioural change. Tests still pass.
Sweep over names introduced by the better_pgo work that hit fix_nits
"expand mod -> module" rule:

- scan_context: cfg -> config (param + 12 call-sites); d (return val) ->
  descriptor in make_descriptor/make_ring_key/make_sector_key; pt -> point
  in the descriptor build loop; zf -> point_z (float cast); q_col/c_col
  -> query_column/candidate_column; q_norm/c_norm -> query_norm/
  candidate_norm; cj -> shifted_j; d (in best_distance return loop) ->
  distance with min_distance for the running best.

- simple_pgo: desc -> descriptor on the per-keyframe cache; k ->
  top_k_count for the partial-sort bound; structured-binding `auto [d,
  shift]` -> `auto [distance, shift]`.

- main.cpp: kp -> keyframe; ps -> pose_stamped (build_graph_nodes and
  build_loop_closure_deltas); a/b -> start/end and p1/p2 ->
  start_pose/end_pose in append_segment; n -> count for the loop bound;
  lc_msg -> loop_closure_msg at the publish site.

- tests: ps -> pose in the validate loop (test_pgo_loop_closure);
  c,s -> cos_yaw,sin_yaw in _yaw_rotation (test_pgo_synthetic_drift).

Names that intentionally stay short are the math-convention ones:
r/t for SE(3) rotation+translation, q for quaternion, i/j as loop
indices, idx as keyframe index, ts as timestamp, dt for time delta,
tx/ty/tz/qx/qy/qz/qw for component decomposition. The fix_nits rule
calls out mod/lc as the target pattern; expanding the math-notation
names would make the code less readable, not more.

Also drops one section-label comment ("# Log each event the moment it
arrives.") whose adjacent function name already conveys the same and
one in-loop "# node_type 1 = odom/robot" that repeats info already
stated in the function-level docstring.

Native binary rebuilt + slow test still passes (17 events, all valid).
Drops in the wiring for evaluating the PGO native module on KITTI-360.
Cannot run end-to-end yet — the dataset is gated behind a registered
login at cvlibs.net so the data download is a manual user step.

What's here:
- kitti360_loader.py: parses the KITTI-360 directory layout (data_3d_raw
  + data_poses + calibration); composes per-frame lidar→world pose by
  chaining cam0_to_world ⊕ inv(velo_to_cam). Exposes a frame iterator
  + scan_xyz(frame_id).
- loop_groundtruth.py: LCDNet/KITTI-convention groundtruth (≥50 frame
  gap, ≤4m radius), order-agnostic scoring of detected pairs.
- run_kitti360_benchmark.py: argparse CLI, spawns the native binary on
  private LCM topics, plays (registered_scan, odometry) from disk,
  subscribes to pgo_graph_edges to extract loop-closure pairs (via
  traversability ≈ 0.4 segments) and pgo_loop_closure for delta event
  counts. Writes JSON.
- README.md: download instructions for the official "Test SLAM 3D"
  12 GB package, published SOTA reference numbers from LCDNet + ISC
  papers (LCDNet 0.91-0.93 AP, Scan Context 0.62-0.78 AP), expected
  ballpark for our minimal SC port.
@jeff-hykin jeff-hykin marked this pull request as ready for review May 16, 2026 02:43
@greptile-apps
Copy link
Copy Markdown
Contributor

greptile-apps Bot commented May 16, 2026

Greptile Summary

This PR extends the PGO module with Scan Context (SC) place recognition, publishes a full pose graph (Graph3D) and per-loop-closure delta (GraphDelta3D) on every keyframe, adds the KITTI-360 benchmark scaffolding for evaluating loop-closure recall/precision, and refactors FarPlanner's output from separate graph_nodes/graph_edges ports to a unified Graph3D port.

  • SC integration: searchByScanContext does a two-stage retrieval (ring-key L₂ coarse filter → column-shifted cosine distance) and seeds ICP with a yaw-aligned initial guess rotated about the source keyframe position, validated by a new reverse-loop regression test.
  • Loop-closure events: build_loop_closure_event snapshots pre-smooth keyframe poses, calls smoothAndUpdate, then publishes per-node SE(3) deltas on loop_closure_event: Out[GraphDelta3D]; fixes from earlier reviews (typo loop_score_tresh, missing SC params in PGOConfig, dimension-inconsistent precision/recall, kitti360_loader empty-timestamps, try/finally guards) are all applied.
  • Benchmark scaffolding: runner.py, scoring.py, playback.py, and loop_groundtruth.py provide a clean query-level TP/FP/FN scorer against KITTI-360 groundtruth; the benchmark is gated on a manually-downloaded 12 GB dataset, so CI tests are skip-if-absent.

Confidence Score: 4/5

Safe to merge for the new publishing and benchmark scaffolding; the SC integration is solid but the position-based fallback is unreachable after a failed SC-ICP attempt, which can silently suppress loop corrections the robot needed.

The core C++ logic — SC descriptor computation, two-stage retrieval, yaw-aligned ICP init_guess, pose-graph snapshot, and GraphDelta3D publication — is correct and well-tested. Most issues flagged in earlier rounds (loop_score_tresh typo, PGOConfig SC params, metric dimension mismatch, kitti360_loader empty-timestamps, missing try/finally guards) are fixed here. The remaining gap is that when SC nominates a candidate but ICP rejects it, the code returns immediately without trying the position-based fallback, so a valid spatially-close loop may be missed silently; this is a recall regression relative to SC-disabled mode, not a crash.

dimos/navigation/nav_stack/modules/pgo/cpp/simple_pgo.cpp (searchForLoopPairs ICP-rejection return path) and dimos/navigation/nav_stack/main.py (orphaned world/graph_nodes and world/graph_edges visual override handlers).

Important Files Changed

Filename Overview
dimos/navigation/nav_stack/modules/pgo/cpp/simple_pgo.cpp Adds SC two-stage retrieval, yaw-aligned ICP init_guess, and splits searchForLoopPairs into searchByScanContext + searchByPosition; dead variables best_dist/best_idx_unfiltered remain in searchByScanContext.
dimos/navigation/nav_stack/modules/pgo/cpp/main.cpp Adds pose_graph (Graph3D) and loop_closure_event (GraphDelta3D) publishing; pre-smooth pose snapshot and had_loop check correctly bracketed around smoothAndUpdate; config field naming typo (loop_score_tresh→loop_score_thresh) fixed.
dimos/navigation/nav_stack/modules/pgo/pgo.py Adds SC parameters to PGOConfig, renames pgo_tf→corrected_tf, adds pose_graph and loop_closure_event Out ports with correct Graph3D/GraphDelta3D types, implements LoopClosure protocol.
dimos/navigation/nav_stack/benchmarks/pose_graph_kitti360/scoring.py Query-level TP/FP/FN scoring with proper set-based deduplication; uses pydantic.Field correctly; _timestamp_to_frame has ±1 ms slop for double round-trip; O(N) list lookup for _detected_pairs is the only remaining inefficiency.
dimos/navigation/nav_stack/benchmarks/pose_graph_kitti360/playback.py Correct try/except/finally guard in _run_playback; exposes playback_error @rpc; compute_send_timestamps ensures 1 ms minimum spacing to avoid timestamp collisions in scoring lookup.
dimos/navigation/nav_stack/benchmarks/pose_graph_kitti360/runner.py Correctly polls playback.is_finished() then checks playback.playback_error() before draining; no threading or error-propagation issues found.
dimos/navigation/nav_stack/benchmarks/pose_graph_kitti360/kitti360_loader.py Now raises ValueError on timestamp/scan count mismatch instead of silently returning empty timestamps; eliminates silent metric corruption from previous review.
dimos/navigation/nav_stack/modules/pgo/cpp/scan_context.cpp Clean SC descriptor/ring-key/sector-key implementation; best_distance correctly iterates all column shifts; lidar_height_m offset matches irapkaist reference convention.
dimos/navigation/nav_stack/main.py Adds pose_graph debug handler (to_rerun_multi) correctly; world/graph_nodes and world/graph_edges visual override entries are now orphaned after FarPlanner's port rename, leaving the new graph port without a debug visualization handler.
dimos/navigation/nav_stack/modules/pgo/test_pgo_synthetic_drift.py SyntheticDriftPlaybackModule has correct try/finally but does not expose playback_error via @rpc, so _run_pgo cannot detect timeout-induced aborts; test_position_search_misses_drifted_loop could silently pass on PGO startup failure.
dimos/navigation/nav_stack/modules/pgo/test_pgo_loop_closure.py Well-structured end-to-end test; correctly validates SE(3) delta shape (unit-norm quaternions, finite + bounded translations); skip logic correctly handles bags that don't trigger any loop.

Sequence Diagram

sequenceDiagram
    participant Playback as Kitti360Playback
    participant PGO as PGO (C++ binary)
    participant SC as ScanContext
    participant GTSAM as iSAM2 GTSAM
    participant Scoring as PoseGraphScoringModule

    Playback->>PGO: registered_scan (PointCloud2)
    Playback->>PGO: odometry (Odometry)
    PGO->>PGO: addKeyPose() build SC descriptor + ring-key
    PGO->>SC: searchByScanContext(ring-key coarse filter to cosine dist top-K)
    SC-->>PGO: loop_idx (or -1)
    alt SC returns -1
        PGO->>PGO: searchByPosition() kd-tree radius search
    end
    alt "loop_idx >= 0"
        PGO->>PGO: getSubMap(cur_idx), getSubMap(loop_idx)
        PGO->>PGO: "ICP.align(src, target, init_guess=yaw_from_shift)"
        alt ICP converged and score less than threshold
            PGO->>PGO: cache LoopPair, snapshot pre_poses
            PGO->>GTSAM: smoothAndUpdate()
            PGO-->>Scoring: loop_closure_event (GraphDelta3D)
        end
    end
    PGO-->>Scoring: pose_graph (Graph3D full snapshot every keyframe)
    PGO-->>Playback: corrected_odometry
    Scoring->>Scoring: _on_pose_graph decode loop edges map ts to frame_id
    Scoring->>Scoring: _score_pairs query-level TP/FP/FN
    Scoring-->>Scoring: get_results precision/recall/F1
Loading

Reviews (44): Last reviewed commit: "Merge remote-tracking branch 'origin/mai..." | Re-trigger Greptile

Comment thread dimos/navigation/nav_stack/modules/pgo/cpp/scan_context.h
- run_kitti360_benchmark: type the scipy Rotation.as_quat result to
  silence no-any-return.
- demo_better_pgo_viz: annotate build_blueprint() -> Blueprint.
Comment thread dimos/navigation/nav_stack/modules/pgo/benchmark/run_kitti360_benchmark.py Outdated
shift comes from best_distance, which scans [0, n_sectors-1], so the
raw yaw is in (-2pi, 0] and `yaw > M_PI` can never fire. Only the
negative-wrap guard is needed to normalize into [-pi, pi].
dimos/ disallows __init__.py files (test_no_init_files) — the empty
one in pgo/benchmark/ slipped in with c7fd631 and was tripping the
3.14 test job.
Comment thread dimos/navigation/nav_stack/modules/pgo/benchmark/run_kitti360_benchmark.py Outdated
mypy can't infer parameter types on a lambda subscribed to LCM; lift
the body into a tiny factory function with explicit
Callable[[str, bytes], None] signature so the lint job passes.
sklearn doesn't ship a py.typed marker; the new place_recognition_ap
benchmark is the only sklearn user in dimos, so a per-import ignore is
the smallest fix to unstick the lint job.
Comment thread dimos/navigation/nav_stack/modules/pgo/pgo.py Outdated
Naming sweep across dimos/navigation/nav_stack/modules/pgo per fix_nits
review conventions: expanded short locals (frac, true_pos, dt, ts, pos,
yaw, msg, sub, idx, fid, gt, cfg, desc, dots, sims, dists, pa/pb, …) to
full descriptive names in the benchmark scripts, the synthetic-drift
test, and the loop-closure test.

Greptile P1 fixes on PR #2099:
- c2: benchmark sender and the timestamp_ms→frame_id cache now share a
  single _compute_send_timestamps source of truth. Previously the cache
  was keyed by raw KITTI timestamps while the runner sent
  max(raw_ts, 1.0 + index*0.001), so early-frame endpoints in PGO loop
  edges never matched the cache and were silently dropped — deflating
  recall without any warning.
- c3: load_kitti360_sequence now raises on .bin/timestamps.txt length
  mismatch instead of silently leaving timestamps={}, which previously
  caused the benchmark to report recall=0 with no indication that the
  timestamp file was unusable.
- c1 follow-up: rename the misspelled C++ field loop_score_tresh →
  loop_score_thresh in simple_pgo.{h,cpp} and main.cpp. The CLI flag
  was always spelled correctly; this is cosmetic but removes the source
  of confusion greptile (correctly) flagged.

New regression test (test_pgo_synthetic_drift.py):
test_scan_context_catches_reverse_loop drives the synthetic robot out
8m facing east, turns 180°, and drives back facing west. Body-frame
scans on the return leg are rotated 180° relative to outbound, so this
exercises the init_guess fix in searchForLoopPairs (yaw rotated about
the source keyframe instead of the world origin). Reverting that fix
reproduces the failure.

New runners:
- benchmark/place_recognition_ap.py: apples-to-apples place-recognition
  AP eval against published Scan Context numbers. Reports AP=0.97-0.98
  on seq 02/04/08 of the Test SLAM split, with precision 1.000 at the
  Kim & Kim 0.13 threshold.
- benchmark/smoke_test.py: ~10s liveness probe that subscribes to all
  six PGO output topics, captures stderr, and prints per-topic message
  counts plus a one-line verdict — used to distinguish "PGO crashed"
  vs "no keyframes" vs "no loops" vs "alive" during debugging.

The benchmark runner also now captures PGO's stderr and dumps it
behind --print-stderr; previously its diagnostic prints (keyframes,
loop-closure events) were discarded.
@jeff-hykin jeff-hykin changed the title feat(pgo): pose-graph viz + Scan Context loop closure + KITTI-360 benchmark scaffolding Enable PGO topics, Optimize PGO, and add KITTI-360 benchmark scaffolding May 16, 2026
…p GraphNodes3D

Collapse PGO's two-stream nav_msgs/Path encoding into a single
pose_graph: Out[Graph3D] snapshot per keyframe cycle. Each node
carries a full SE(3) PoseStamped (previously rotation was zeroed),
a stable uint64 id (= keyframe index), and metadata_id = NODE_KEYFRAME.
Edges reference nodes by id and carry metadata_id = EDGE_ODOMETRY (0)
or EDGE_LOOP_CLOSURE (1) — replaces the orientation.w == 0.4
traversability tag previously used to mark loop closures.

Touches:

* pgo.py / specs.py: Out[NavPath] x 2 → Out[Graph3D] x 1.
* cpp/main.cpp: build_graph_nodes + build_graph_edges + append_segment
  helpers collapse into build_pose_graph() returning dimos::Graph3D.
* cpp/msgs/GraphNodes3D.hpp deleted (vendored copy no longer needed).
* scoring.py: filter loop edges via metadata_id == EDGE_LOOP_CLOSURE
  instead of orientation.w ≈ 0.4. Endpoint frame_id lookup goes
  through node_id → node.pose.ts → timestamp_to_frame, removing the
  loop_closure_traversability / traversability_tolerance config.
* nav_stack/main.py: _pose_graph_nodes_colors_debug +
  _pose_graph_edges_colors_debug → _pose_graph_colors_debug, calling
  Graph3D.to_rerun_multi to render nodes + edges under separate
  rerun sub-paths.
* runner.py / README.md docstring updates.

Deletes dimos/msgs/nav_msgs/GraphNodes3D.py — no longer has consumers
after this commit and the matching far_planner switch.

Validated by:

* test_Graph3D.py round-trip + wire-layout pin tests pass.
* test_far_planner_rosbag.py (uses the same Graph3D Python type for
  far_planner's graph stream) passes.
* benchmark_kitti360_smoke deterministically produces keyframes
  across 5 consecutive runs at publish_interval_sec=0.02 (50 Hz),
  including publish_interval_sec=0.0 (unbounded).
The smoke test isn't a demo (it runs PGO end-to-end with KITTI-360
playback and reports per-topic message counts as a liveness check),
and it's specific to KITTI-360 — the new name reflects both. Also
matches the sibling benchmark module names under
``dimos/navigation/nav_stack/benchmarks/pose_graph_kitti360/``.

Pure rename + topic count updates: the TopicCounterModule subscribes
to pose_graph (Graph3D) instead of pose_graph_nodes + pose_graph_edges
(matching the PGO output collapse in the previous commit), and the
verdict messages collapse accordingly.
Earlier rename to test_pgo_loop_correction_delta.py (29dfafe) was
out-of-sync with main, where the file went the opposite direction.
Restore the upstream filename to avoid a manual rename-direction
conflict on the next merge.

Internal symbols (LoopCorrectionDeltaRecorderModule, the
loop_correction_delta stream attribute, etc.) stay — those describe
what the stream actually carries (per-keyframe SE(3) deltas, not loop
closures themselves).
`topic-counter-module` path updated to reflect the
demo_benchmark_kitti_smoke → benchmark_kitti360_smoke rename
(commit f97e1bd).
New nav_msgs.GraphDelta3D: two aligned arrays — a list of nodes
(reusing Graph3D.Node3D byte-for-byte) and a list of SE(3) Transforms,
one per node. ``transforms[i]`` is the delta about to be applied to
``nodes[i].pose``: ``post = transforms[i] * nodes[i].pose``
(left-multiply).

Layout (big-endian, mirrors Graph3D conventions):

  u8 node_count
  f8 timestamp
  Node3D nodes[node_count]          // same wire bytes as Graph3D nodes
  Transform transforms[node_count]  // 7×f8 (translation xyz + quat xyzw)

Test pin (test_node_layout_matches_graph3d) asserts that a
GraphDelta3D.nodes[i] is bit-identical to a Graph3D.nodes[i] for the
same Node3D, so consumers can correlate ids across the two messages.

PGO wiring:

* pgo.py / specs.py: ``loop_correction_delta: Out[NavPath]`` →
  ``loop_closure_event: Out[GraphDelta3D]``. Renamed too — the stream
  carries a graph-mutation event, not just a delta payload.
* cpp/main.cpp: build_loop_correction_delta (returned nav_msgs::Path
  with position-encodes-delta hack) → build_loop_closure_event
  returning dimos::GraphDelta3D. Each (node, transform) pair carries
  the pre-smooth keyframe (id, pose, ts) and the iSAM2-applied delta.
* cpp/msgs/GraphDelta3D.hpp vendored.

Downstream consumers updated to subscribe ``loop_closure_event:
In[GraphDelta3D]``:

* PoseGraphScoringModule
* test_pgo_loop_closure recorder (full payload validation rewrite —
  unit-quaternion + finite-translation checks now read each
  transform.rotation / transform.translation instead of pose.orientation
  / pose.position)
* test_pgo_synthetic_drift counter
* benchmark_kitti360_smoke TopicCounter
* runner.py docstring

11/11 unit tests pass (5 GraphDelta3D layout, 5 Graph3D layout,
1 blueprints registry). PGO native rebuilt — new topic
``loop_closure_event`` confirmed in binary symbols.
Comment thread dimos/core/native_module.py
Comment thread dimos/navigation/nav_stack/modules/pgo/test_pgo_synthetic_drift.py
Copy link
Copy Markdown
Member Author

@jeff-hykin jeff-hykin left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

review2

@jeff-hykin jeff-hykin closed this May 17, 2026
auto-merge was automatically disabled May 17, 2026 11:23

Pull request was closed

@jeff-hykin jeff-hykin reopened this May 17, 2026
@jeff-hykin jeff-hykin enabled auto-merge (squash) May 17, 2026 11:24
@jeff-hykin jeff-hykin closed this May 17, 2026
auto-merge was automatically disabled May 17, 2026 12:02

Pull request was closed

@jeff-hykin jeff-hykin reopened this May 17, 2026
@jeff-hykin jeff-hykin closed this May 17, 2026
@jeff-hykin jeff-hykin reopened this May 17, 2026
@jeff-hykin jeff-hykin closed this May 17, 2026
@jeff-hykin jeff-hykin reopened this May 17, 2026
@jeff-hykin jeff-hykin enabled auto-merge (squash) May 17, 2026 14:51
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

Switch to PGO as Native Module

1 participant