Skip to content

Ivan/feat/markermerge#2114

Open
leshy wants to merge 9 commits into
mainfrom
ivan/feat/markermerge
Open

Ivan/feat/markermerge#2114
leshy wants to merge 9 commits into
mainfrom
ivan/feat/markermerge

Conversation

@leshy
Copy link
Copy Markdown
Contributor

@leshy leshy commented May 16, 2026

recording of real go2 looking at markers

dimos --replay --replay-db markers_go2 run unitree-go2

@greptile-apps
Copy link
Copy Markdown
Contributor

greptile-apps Bot commented May 16, 2026

Greptile Summary

This PR adds ArUco marker detection with TF pose publication (MarkerTfModule), a desk-camera blueprint (desk_marker_tf), a camera calibration CLI (cameracalibrate), a lidar on/off control for Go2, and fixes the LCM message-type resolution in the topic CLI.

  • MarkerTfModule detects ArUco/AprilTag markers from an image + CameraInfo stream, computes per-marker poses via solvePnP, chains them through the TF tree, and publishes world → markers → marker_{id} transforms.
  • Go2 lidar control adds set_lidar(enabled) to the connection layer and wires it into GO2Connection.start/stop; lidar_auto_off config flag gates the shutdown call.
  • tf.py get() gains a typed signature and an identity-transform short-circuit when parent_frame == child_frame.

Confidence Score: 3/5

Two bugs in memory2/module.py need fixing before merge: the logger warning silently drops every TF-miss event (wrong argument count), and all recorded messages now carry wall-clock time instead of the message's own timestamp, which corrupts replay.

The memory2 recorder has two regressions introduced in this PR: the logger format-string mismatch makes TF-failure diagnostics invisible, and unconditionally using time.time() instead of the message timestamp causes every replayed stream to carry wrong absolute times. Both affect the recording path that the PR explicitly exercises. The rest of the changes (MarkerTfModule, cameracalibrate, lidar control, TF identity shortcut) look correct in isolation.

dimos/memory2/module.py — both the logger format-string argument count and the ts=time.time() call need to be revisited.

Important Files Changed

Filename Overview
dimos/memory2/module.py Logger warning format string has 4 placeholders but only 3 args (pre-existing comment); stream.append now always uses wall-clock time, breaking replay timestamps.
dimos/perception/fiducial/marker_tf_module.py New module: ArUco detection + solvePnP + TF publish. Object point order, distortion handling, and frame chaining look correct. Only concern is deploy() calling mod.start() explicitly.
dimos/protocol/tf/tf.py Added typed signature and identity-transform shortcut; identity Transform returned without ts, which could propagate a None ts into composed transforms.
dimos/robot/unitree/go2/blueprints/smart/unitree_go2.py Adds MarkerTfModule to the smart blueprint with marker_length_m=0.1 (hardcoded, as previously noted).
dimos/robot/unitree/go2/connection.py Adds lidar_auto_off config flag, set_lidar RPC, and unconditional set_lidar(True) at start; stub added to ReplayConnection; all simulation connections also stubbed.
dimos/robot/unitree/connection.py Adds set_lidar() publishing to RTC_TOPIC["ULIDAR_SWITCH"] via call_soon_threadsafe; mirrors existing obstacle-avoidance pattern.
dimos/utils/cli/cameracalibrate/cameracalibrate.py New camera calibration tool: webcam/folder sources, multi-candidate chessboard detection, ROS CameraInfo YAML output, preview PNG; implementation looks correct.
dimos/perception/fiducial/blueprints/desk_marker_tf.py New desk webcam + static-TF + MarkerTfModule blueprint; republish thread lifecycle looks correct.
dimos/robot/cli/topic.py _resolve_type now imports per-class submodule (e.g. dimos.msgs.sensor_msgs.CameraInfo) rather than the package; new _decode_typed_lcm_message helper; both changes align with dimos message layout.

Sequence Diagram

sequenceDiagram
    participant Cam as Camera Stream
    participant MTM as MarkerTfModule
    participant TF as MultiTBuffer
    participant TFPub as TF Publisher

    Cam->>MTM: color_image (Image)
    Cam->>MTM: camera_info (CameraInfo)

    MTM->>TF: get(world, base_link, ts, tol)
    TF-->>MTM: t_world_base (Transform)

    MTM->>TF: get(base_link, optical, ts, tol)
    TF-->>MTM: t_base_optical (Transform)

    Note over MTM: ArucoDetector.detectMarkers(gray)
    Note over MTM: solvePnP → rvec, tvec per marker

    MTM->>MTM: "t_optical_marker = rvec_tvec_to_transform(...)"
    MTM->>MTM: "t_base_marker = t_base_optical + t_optical_marker"
    MTM->>MTM: "t_world_marker = t_world_base + t_base_marker"

    MTM->>TFPub: "publish(world→markers, markers→marker_{id}, ...)"
Loading

Reviews (2): Last reviewed commit: "recording" | Re-trigger Greptile

Comment thread dimos/memory2/module.py
getattr(msg, "ts", None),
)
stream.append(msg, ts=ts, pose=pose)
stream.append(msg, ts=time.time(), pose=pose)
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

P1 Using time.time() (wall-clock) instead of the message's own timestamp means that during replay, every stored message will carry the current real time rather than the replayed recording time. Downstream time-series queries against the stream will then see wrong absolute timestamps. The previous ts already fell back to time.time() when absent, so the old behaviour was safe for live use while preserving replay timestamps.

Suggested change
stream.append(msg, ts=time.time(), pose=pose)
stream.append(msg, ts=ts, pose=pose)

WavefrontFrontierExplorer.blueprint(),
PatrollingModule.blueprint(),
MovementManager.blueprint(),
MarkerTfModule.blueprint(marker_length_m=0.1),
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

P2 The marker size is hard-coded to 10 cm in the shared smart blueprint. If the physical markers on a particular deployment are a different size (e.g. the 5 cm desk markers used in desk_marker_tf or the 18 cm example in the module docstring), pose estimates will be off by the ratio of the expected vs. actual size. Consider surfacing this as a global-config knob or at least documenting the assumed physical size prominently.

Suggested change
MarkerTfModule.blueprint(marker_length_m=0.1),
MarkerTfModule.blueprint(marker_length_m=0.1), # physical marker edge length – update if markers differ

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.

1 participant