Skip to content

feat(go2): low-level wholebody control#2361

Open
ruthwikdasyam wants to merge 49 commits into
mainfrom
ruthwik/go2sdk
Open

feat(go2): low-level wholebody control#2361
ruthwikdasyam wants to merge 49 commits into
mainfrom
ruthwik/go2sdk

Conversation

@ruthwikdasyam
Copy link
Copy Markdown
Contributor

@ruthwikdasyam ruthwikdasyam commented Jun 5, 2026

Problem

Feature: go2 low level controls

Closes DIM-753

Solution

Add Go2 wholebody (low-level) control:

  • New Go2WholeBodyConnection Module (unitree_go IDL, 12-motor, foot_force damped precondition)
  • unitree-go2-wholebody-coordinator blueprint (mirrors unitree-g1-coordinator)
  • make_quadruped_joints helper

How to Test

dimos run unitree_go2_wholebody_coordinator

Contributor License Agreement

  • I have read and approved the CLA.

@codecov
Copy link
Copy Markdown

codecov Bot commented Jun 5, 2026

Codecov Report

❌ Patch coverage is 33.03167% with 148 lines in your changes missing coverage. Please review.
✅ All tests successful. No failed tests found.

Files with missing lines Patch % Lines
dimos/robot/unitree/go2/wholebody_connection.py 26.73% 148 Missing ⚠️

📢 Thoughts on this report? Let us know!

@ruthwikdasyam ruthwikdasyam marked this pull request as ready for review June 5, 2026 01:15
@greptile-apps
Copy link
Copy Markdown
Contributor

greptile-apps Bot commented Jun 5, 2026

Greptile Summary

This PR adds low-level whole-body control for the Unitree Go2 quadruped: a new Go2WholeBodyConnection DDS module, a make_quadruped_joints helper, and a unitree-go2-wholebody-coordinator blueprint that mirrors the existing G1 humanoid coordinator. The motor-command write path correctly holds self._lock around the publisher.Write call, and the sport-mode release loop now enforces a 30-second deadline with a RuntimeError on timeout.

  • Go2WholeBodyConnection: 12-motor DDS subscriber/publisher using the unitree_go IDL, with polling-mode state reads, safe-stop on shutdown, and CRC-stamped command frames.
  • make_quadruped_joints: New helper in components.py encoding the canonical FR→FL→RR→RL hip/thigh/calf motor ordering.
  • unitree_go2_wholebody_coordinator: Blueprint wiring the new module to ControlCoordinator at 500 Hz via LCM transports, with per-joint KP=25/KD=0.5 defaults.

Confidence Score: 4/5

Safe to merge for single-robot deployments; the DDS initialization path can fail if another SDK module has already called ChannelFactoryInitialize in the same process.

The motor-command write and safe-stop paths are correctly guarded. The one gap is in start(): ChannelFactoryInitialize is called without any exception handling, unlike the G1 module which catches and silently continues on the already-initialized case. In a process that also runs G1WholeBodyConnection or any other SDK consumer, Go2 start() will throw an uncaught exception from the SDK rather than logging and continuing.

dimos/robot/unitree/go2/wholebody_connection.py — specifically the DDS initialization block in start().

Important Files Changed

Filename Overview
dimos/robot/unitree/go2/wholebody_connection.py New Go2 low-level DDS module (408 lines). Motor write is correctly inside the lock, and the sport-mode release loop now has a deadline. However, ChannelFactoryInitialize is called without any exception handling — unlike the G1 counterpart — so a second process-level DDS initialization attempt from a sibling module will crash start().
dimos/control/components.py Adds make_quadruped_joints helper and _QUADRUPED_12DOF_JOINTS constant, mirroring make_humanoid_joints. Ordering and all export look correct.
dimos/robot/unitree/go2/blueprints/basic/unitree_go2_wholebody_coordinator.py New blueprint wiring Go2WholeBodyConnection to ControlCoordinator via LCM transports. KP/KD gains, joint ordering, and channel names all look correct and consistent with the G1 coordinator pattern.
dimos/robot/all_blueprints.py Registers the new blueprint and module in the discovery maps. Entries are alphabetically ordered and correctly formatted.

Sequence Diagram

sequenceDiagram
    participant Op as Operator
    participant Blueprint as unitree_go2_wholebody_coordinator
    participant Conn as Go2WholeBodyConnection
    participant DDS as Unitree DDS (rt/lowstate / rt/lowcmd)
    participant Coord as ControlCoordinator
    participant LCM as LCM Transport

    Op->>Blueprint: dimos run
    Blueprint->>Conn: start()
    Conn->>DDS: ChannelFactoryInitialize
    Conn->>DDS: ChannelPublisher("rt/lowcmd").Init()
    Conn->>DDS: ChannelSubscriber("rt/lowstate").Init(None,0)
    Conn->>Conn: _release_sport_mode() [up to 30s]
    Conn->>DDS: Read() — wait for first LowState
    DDS-->>Conn: LowState frame
    Conn->>Conn: start publish_loop thread (500 Hz)
    loop 500 Hz publish loop
        Conn->>DDS: Read() → _low_state
        Conn->>LCM: motor_states (JointState)
        Conn->>LCM: imu (Imu)
    end
    LCM->>Coord: joint_state
    Coord->>LCM: joint_command (JointState)
    LCM->>Conn: motor_command (MotorCommandArray)
    Conn->>Conn: _on_motor_command [inside _lock]
    Conn->>DDS: publisher.Write(LowCmd_) [inside _lock]
    Op->>Blueprint: stop()
    Blueprint->>Conn: stop()
    Conn->>DDS: "Write safe-stop LowCmd_ (mode=0x00)"
    Conn->>DDS: subscriber.Close() / publisher.Close()
Loading

Reviews (3): Last reviewed commit: "fix: write low_cmd inside the lock" | Re-trigger Greptile

Comment thread dimos/robot/unitree/go2/wholebody_connection.py Outdated
Comment thread dimos/robot/unitree/go2/wholebody_connection.py
Comment thread dimos/robot/unitree/go2/wholebody_connection.py Outdated
Comment on lines +98 to +100
motor_command: In[MotorCommandArray]
motor_states: Out[JointState]
imu: Out[Imu]
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.

We should also get Camera and Lidar streams as out using the Connection Module.

Comment on lines +153 to +158
self._low_cmd = unitree_go_msg_dds__LowCmd_()
self._low_cmd.head[0] = 0xFE
self._low_cmd.head[1] = 0xEF
self._low_cmd.level_flag = 0xFF
self._low_cmd.gpio = 0
self._reset_motor_cmd_slots(_MOTOR_MODE_ENABLE)
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.

We should codify these magic bytes in docstrings for better dev experience

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.

2 participants