Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
40 commits
Select commit Hold shift + click to select a range
7c46afc
Added robot config factory as single source of truth of robot descrip…
mustafab0 Mar 28, 2026
cbd487f
trigger CI
mustafab0 Mar 28, 2026
f25f5b2
added a threading lock for xacro files processing also cehcks for roo…
mustafab0 Mar 28, 2026
cf1c485
CI code cleanup
mustafab0 Mar 28, 2026
3e41d1e
trigger CI
mustafab0 Mar 28, 2026
534c890
removed the init files for robot catalog
mustafab0 Mar 28, 2026
b192983
Created a fake ament index with symlinks so ament_index_python resolv…
mustafab0 Mar 29, 2026
0d3aad5
trigger CI
mustafab0 Mar 28, 2026
b7c175f
trigger CI
mustafab0 Mar 28, 2026
9617506
updated mobile base blueprint and cleaned up older files
mustafab0 Apr 1, 2026
5cd8f47
CI code cleanup
mustafab0 Apr 1, 2026
302a1c3
trigger CI
mustafab0 Apr 1, 2026
f774c99
trigger CI
mustafab0 Apr 2, 2026
93252dc
trigger CI
mustafab0 Mar 28, 2026
379440b
trigger CI
mustafab0 Mar 28, 2026
8a47328
trigger CI
mustafab0 Mar 28, 2026
55f180c
trigger CI
mustafab0 Mar 28, 2026
b198567
trigger CI
mustafab0 Apr 1, 2026
fc1b60d
trigger CI
mustafab0 Apr 2, 2026
e00ddeb
trigger CI
mustafab0 Mar 28, 2026
fabb06a
trigger CI
mustafab0 Mar 28, 2026
607edfa
trigger CI
mustafab0 Mar 28, 2026
ef4d786
trigger CI
mustafab0 Mar 28, 2026
e078a52
trigger CI
mustafab0 Apr 1, 2026
cfccff2
renamed WorldStateMonitor to RobotStateMonitor
mustafab0 Apr 1, 2026
19cb373
added a split joint name utility using "/" as seperator
mustafab0 Apr 1, 2026
52255d5
updated all joint mapping reference to use "/" seperator
mustafab0 Apr 1, 2026
85db7f3
updated seperator after rebase
mustafab0 Apr 1, 2026
a63e4d6
addded gripper control to catalog
mustafab0 Apr 2, 2026
620a837
updated blueprints to use global ip config
mustafab0 Apr 2, 2026
354384d
added 1 urdf, 2 arm support to drake world add robot method
mustafab0 Apr 2, 2026
bd5d5d8
CI code cleanup
mustafab0 Apr 2, 2026
ecf45ef
trigger CI
mustafab0 Apr 2, 2026
6b520eb
fixed piper global config
mustafab0 Apr 2, 2026
82ed892
velocity data is now forwarded with the same index slicing as positions
mustafab0 Apr 2, 2026
081d38d
code logs which joints are missing instead of silently skipping
mustafab0 Apr 3, 2026
3862710
CI cleanup issue
mustafab0 Apr 7, 2026
0ead24d
add_robot() call now always loads a fresh model instance no shared st…
mustafab0 Apr 7, 2026
b817a65
CI code cleanup
mustafab0 Apr 7, 2026
2377119
trigger CI
mustafab0 Apr 7, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion dimos/control/blueprints/basic.py
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,9 @@
)

# Piper arm (6-DOF, CAN bus)
_piper_cfg = _catalog_piper(name="arm", adapter_type="piper", address=global_config.can_port)
_piper_cfg = _catalog_piper(
name="arm", adapter_type="piper", address=global_config.can_port or "can0"
)

coordinator_piper = ControlCoordinator.blueprint(
hardware=[_piper_cfg.to_hardware_component()],
Expand Down
4 changes: 3 additions & 1 deletion dimos/control/blueprints/dual.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,9 @@
_xarm6_dual = _catalog_xarm6(
name="xarm_arm", adapter_type="xarm", address=global_config.xarm6_ip, add_gripper=False
)
_piper_dual = _catalog_piper(name="piper_arm", adapter_type="piper", address=global_config.can_port)
_piper_dual = _catalog_piper(
name="piper_arm", adapter_type="piper", address=global_config.can_port or "can0"
)

coordinator_piper_xarm = ControlCoordinator.blueprint(
hardware=[_xarm6_dual.to_hardware_component(), _piper_dual.to_hardware_component()],
Expand Down
4 changes: 3 additions & 1 deletion dimos/control/blueprints/teleop.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,9 @@
_xarm7_cfg = _catalog_xarm7(
name="arm", adapter_type="xarm", address=global_config.xarm7_ip, add_gripper=True
)
_piper_cfg = _catalog_piper(name="arm", adapter_type="piper", address=global_config.can_port)
_piper_cfg = _catalog_piper(
name="arm", adapter_type="piper", address=global_config.can_port or "can0"
)

# -- Servo / velocity ---------------------------------------------------------

Expand Down
26 changes: 19 additions & 7 deletions dimos/control/components.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,17 @@
TaskName = str


def split_joint_name(joint_name: str) -> tuple[str, str]:
"""Split a coordinator joint name into (hardware_id, suffix).

Example: "left_arm/joint1" -> ("left_arm", "joint1")
"""
parts = joint_name.split("/", 1)
if len(parts) != 2:
raise ValueError(f"Joint name '{joint_name}' missing separator '/'")
return parts[0], parts[1]


class HardwareType(Enum):
MANIPULATOR = "manipulator"
BASE = "base"
Expand All @@ -44,7 +55,7 @@ class HardwareComponent:
Attributes:
hardware_id: Unique identifier, also used as joint name prefix
hardware_type: Type of hardware (MANIPULATOR, BASE)
joints: List of joint names (e.g., ["arm_joint1", "arm_joint2", ...])
joints: List of joint names (e.g., ["arm/joint1", "arm/joint2", ...])
adapter_type: Adapter type ("mock", "xarm", "piper")
address: Connection address - IP for TCP, port for CAN
auto_enable: Whether to auto-enable servos
Expand Down Expand Up @@ -73,9 +84,9 @@ def make_gripper_joints(hardware_id: HardwareId) -> list[JointName]:
hardware_id: The hardware identifier (e.g., "arm")

Returns:
List of joint names like ["arm_gripper"]
List of joint names like ["arm/gripper"]
"""
return [f"{hardware_id}_gripper"]
return [f"{hardware_id}/gripper"]


def make_joints(hardware_id: HardwareId, dof: int) -> list[JointName]:
Expand All @@ -86,9 +97,9 @@ def make_joints(hardware_id: HardwareId, dof: int) -> list[JointName]:
dof: Degrees of freedom

Returns:
List of joint names like ["left_arm_joint1", "left_arm_joint2", ...]
List of joint names like ["left_arm/joint1", "left_arm/joint2", ...]
"""
return [f"{hardware_id}_joint{i + 1}" for i in range(dof)]
return [f"{hardware_id}/joint{i + 1}" for i in range(dof)]


# Maps virtual joint suffix → (Twist group, Twist field)
Expand All @@ -115,13 +126,13 @@ def make_twist_base_joints(
suffixes: Velocity DOF suffixes. Defaults to ["vx", "vy", "wz"] (holonomic).

Returns:
List of joint names like ["base_vx", "base_vy", "base_wz"]
List of joint names like ["base/vx", "base/vy", "base/wz"]
"""
suffixes = suffixes or _DEFAULT_TWIST_SUFFIXES
for s in suffixes:
if s not in TWIST_SUFFIX_MAP:
raise ValueError(f"Unknown twist suffix '{s}'. Valid: {list(TWIST_SUFFIX_MAP)}")
return [f"{hardware_id}_{s}" for s in suffixes]
return [f"{hardware_id}/{s}" for s in suffixes]


__all__ = [
Expand All @@ -135,4 +146,5 @@ def make_twist_base_joints(
"make_gripper_joints",
"make_joints",
"make_twist_base_joints",
"split_joint_name",
]
5 changes: 3 additions & 2 deletions dimos/control/coordinator.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
HardwareType,
JointName,
TaskName,
split_joint_name,
)
from dimos.control.hardware_interface import ConnectedHardware, ConnectedTwistBase
from dimos.control.task import ControlTask
Expand Down Expand Up @@ -536,8 +537,8 @@ def _on_twist_command(self, msg: Twist) -> None:
if hw.component.hardware_type != HardwareType.BASE:
continue
for joint_name in hw.joint_names:
# Extract suffix (e.g., "base_vx" → "vx")
suffix = joint_name.rsplit("_", 1)[-1]
# Extract suffix (e.g., "base/vx" → "vx")
_, suffix = split_joint_name(joint_name)
mapping = TWIST_SUFFIX_MAP.get(suffix)
if mapping is None:
continue
Expand Down
6 changes: 3 additions & 3 deletions dimos/control/task.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class ResourceClaim:

Attributes:
joints: Set of joint names this task wants to control.
Example: frozenset({"left_joint1", "left_joint2"})
Example: frozenset({"left/joint1", "left/joint2"})
priority: Priority level for conflict resolution. Higher wins.
Typical values: 10 (trajectory), 50 (WBC), 100 (safety)
mode: Control mode (POSITION, VELOCITY, TORQUE)
Expand Down Expand Up @@ -189,7 +189,7 @@ class ControlTask(Protocol):
...
... def claim(self) -> ResourceClaim:
... return ResourceClaim(
... joints=frozenset(["left_joint1", "left_joint2"]),
... joints=frozenset(["left/joint1", "left/joint2"]),
... priority=10,
... )
...
Expand All @@ -201,7 +201,7 @@ class ControlTask(Protocol):
... t_elapsed = state.t_now - self._start_time
... positions = self._trajectory.sample(t_elapsed)
... return JointCommandOutput(
... joint_names=["left_joint1", "left_joint2"],
... joint_names=["left/joint1", "left/joint2"],
... positions=positions,
... )
...
Expand Down
2 changes: 1 addition & 1 deletion dimos/control/tasks/servo_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ class JointServoTask(BaseControlTask):
>>> task = JointServoTask(
... name="servo_arm",
... config=JointServoTaskConfig(
... joint_names=["arm_joint1", "arm_joint2", "arm_joint3"],
... joint_names=["arm/joint1", "arm/joint2", "arm/joint3"],
... priority=10,
... timeout=0.5,
... ),
Expand Down
2 changes: 1 addition & 1 deletion dimos/control/tasks/teleop_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class TeleopIKTaskConfig:
timeout: If no command received for this many seconds, go inactive (0 = never)
max_joint_delta_deg: Maximum allowed joint change per tick (safety limit)
hand: "left" or "right" — which controller's primary button to listen to
gripper_joint: Optional joint name for the gripper (e.g. "arm_gripper").
gripper_joint: Optional joint name for the gripper (e.g. "arm/gripper").
gripper_open_pos: Gripper position (adapter units) at trigger value 0.0 (no press).
gripper_closed_pos: Gripper position (adapter units) at trigger value 1.0 (full press).
"""
Expand Down
2 changes: 1 addition & 1 deletion dimos/control/tasks/trajectory_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class JointTrajectoryTask(BaseControlTask):
>>> task = JointTrajectoryTask(
... name="traj_left",
... config=JointTrajectoryTaskConfig(
... joint_names=["left_joint1", "left_joint2"],
... joint_names=["left/joint1", "left/joint2"],
... priority=10,
... ),
... )
Expand Down
2 changes: 1 addition & 1 deletion dimos/control/tasks/velocity_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class JointVelocityTask(BaseControlTask):
>>> task = JointVelocityTask(
... name="velocity_arm",
... config=JointVelocityTaskConfig(
... joint_names=["arm_joint1", "arm_joint2", "arm_joint3"],
... joint_names=["arm/joint1", "arm/joint2", "arm/joint3"],
... priority=10,
... timeout=0.2,
... zero_on_timeout=True,
Expand Down
52 changes: 26 additions & 26 deletions dimos/control/test_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ def connected_hardware(mock_adapter):
def trajectory_task():
"""Create a JointTrajectoryTask for testing."""
config = JointTrajectoryTaskConfig(
joint_names=["arm_joint1", "arm_joint2", "arm_joint3"],
joint_names=["arm/joint1", "arm/joint2", "arm/joint3"],
priority=10,
)
return JointTrajectoryTask(name="test_traj", config=config)
Expand All @@ -81,7 +81,7 @@ def trajectory_task():
def simple_trajectory():
"""Create a simple 2-point trajectory."""
return JointTrajectory(
joint_names=["arm_joint1", "arm_joint2", "arm_joint3"],
joint_names=["arm/joint1", "arm/joint2", "arm/joint3"],
points=[
TrajectoryPoint(
positions=[0.0, 0.0, 0.0],
Expand All @@ -101,9 +101,9 @@ def simple_trajectory():
def coordinator_state():
"""Create a sample CoordinatorState."""
joints = JointStateSnapshot(
joint_positions={"arm_joint1": 0.0, "arm_joint2": 0.0, "arm_joint3": 0.0},
joint_velocities={"arm_joint1": 0.0, "arm_joint2": 0.0, "arm_joint3": 0.0},
joint_efforts={"arm_joint1": 0.0, "arm_joint2": 0.0, "arm_joint3": 0.0},
joint_positions={"arm/joint1": 0.0, "arm/joint2": 0.0, "arm/joint3": 0.0},
joint_velocities={"arm/joint1": 0.0, "arm/joint2": 0.0, "arm/joint3": 0.0},
joint_efforts={"arm/joint1": 0.0, "arm/joint2": 0.0, "arm/joint3": 0.0},
timestamp=time.perf_counter(),
)
return CoordinatorState(joints=joints, t_now=time.perf_counter(), dt=0.01)
Expand Down Expand Up @@ -162,27 +162,27 @@ class TestConnectedHardware:
def test_joint_names_prefixed(self, connected_hardware):
names = connected_hardware.joint_names
assert names == [
"arm_joint1",
"arm_joint2",
"arm_joint3",
"arm_joint4",
"arm_joint5",
"arm_joint6",
"arm/joint1",
"arm/joint2",
"arm/joint3",
"arm/joint4",
"arm/joint5",
"arm/joint6",
]

def test_read_state(self, connected_hardware):
state = connected_hardware.read_state()
assert "arm_joint1" in state
assert "arm/joint1" in state
assert len(state) == 6
joint_state = state["arm_joint1"]
joint_state = state["arm/joint1"]
assert joint_state.position == 0.0
assert joint_state.velocity == 0.0
assert joint_state.effort == 0.0

def test_write_command(self, connected_hardware, mock_adapter):
commands = {
"arm_joint1": 0.5,
"arm_joint2": 1.0,
"arm/joint1": 0.5,
"arm/joint2": 1.0,
}
connected_hardware.write_command(commands, ControlMode.POSITION)
mock_adapter.write_joint_positions.assert_called()
Expand All @@ -197,9 +197,9 @@ def test_initial_state(self, trajectory_task):
def test_claim(self, trajectory_task):
claim = trajectory_task.claim()
assert claim.priority == 10
assert "arm_joint1" in claim.joints
assert "arm_joint2" in claim.joints
assert "arm_joint3" in claim.joints
assert "arm/joint1" in claim.joints
assert "arm/joint2" in claim.joints
assert "arm/joint3" in claim.joints

def test_execute_trajectory(self, trajectory_task, simple_trajectory):
time.perf_counter()
Expand Down Expand Up @@ -270,7 +270,7 @@ def test_cancel_trajectory(self, trajectory_task, simple_trajectory):
def test_preemption(self, trajectory_task, simple_trajectory):
trajectory_task.execute(simple_trajectory)

trajectory_task.on_preempted("safety_task", frozenset({"arm_joint1"}))
trajectory_task.on_preempted("safety_task", frozenset({"arm/joint1"}))
assert trajectory_task.get_state() == TrajectoryState.ABORTED
assert not trajectory_task.is_active()

Expand Down Expand Up @@ -404,7 +404,7 @@ def test_tick_loop_starts_and_stops(self, mock_adapter):
hw = ConnectedHardware(mock_adapter, component)
hardware = {"arm": hw}
tasks: dict = {}
joint_to_hardware = {f"arm_joint{i + 1}": "arm" for i in range(6)}
joint_to_hardware = {f"arm/joint{i + 1}": "arm" for i in range(6)}

tick_loop = TickLoop(
tick_rate=100.0,
Expand Down Expand Up @@ -437,17 +437,17 @@ def test_tick_loop_calls_compute(self, mock_adapter):
mock_task.name = "test_task"
mock_task.is_active.return_value = True
mock_task.claim.return_value = ResourceClaim(
joints=frozenset({"arm_joint1"}),
joints=frozenset({"arm/joint1"}),
priority=10,
)
mock_task.compute.return_value = JointCommandOutput(
joint_names=["arm_joint1"],
joint_names=["arm/joint1"],
positions=[0.5],
mode=ControlMode.POSITION,
)

tasks = {"test_task": mock_task}
joint_to_hardware = {f"arm_joint{i + 1}": "arm" for i in range(6)}
joint_to_hardware = {f"arm/joint{i + 1}": "arm" for i in range(6)}

tick_loop = TickLoop(
tick_rate=100.0,
Expand Down Expand Up @@ -476,13 +476,13 @@ def test_full_trajectory_execution(self, mock_adapter):
hardware = {"arm": hw}

config = JointTrajectoryTaskConfig(
joint_names=[f"arm_joint{i + 1}" for i in range(6)],
joint_names=[f"arm/joint{i + 1}" for i in range(6)],
priority=10,
)
traj_task = JointTrajectoryTask(name="traj_arm", config=config)
tasks = {"traj_arm": traj_task}

joint_to_hardware = {f"arm_joint{i + 1}": "arm" for i in range(6)}
joint_to_hardware = {f"arm/joint{i + 1}": "arm" for i in range(6)}

tick_loop = TickLoop(
tick_rate=100.0,
Expand All @@ -494,7 +494,7 @@ def test_full_trajectory_execution(self, mock_adapter):
)

trajectory = JointTrajectory(
joint_names=[f"arm_joint{i + 1}" for i in range(6)],
joint_names=[f"arm/joint{i + 1}" for i in range(6)],
points=[
TrajectoryPoint(
positions=[0.0] * 6,
Expand Down
2 changes: 1 addition & 1 deletion dimos/core/global_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class GlobalConfig(BaseSettings):
robot_ips: str | None = None
xarm7_ip: str | None = None
xarm6_ip: str | None = None
can_port: str = "can0"
can_port: str | None = None
simulation: bool = False
replay: bool = False
replay_dir: str = "go2_sf_office"
Expand Down
Loading
Loading