Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
227 changes: 227 additions & 0 deletions dimos/control/blueprints/_hardware.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,227 @@
# Copyright 2025-2026 Dimensional Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""Hardware component helpers for coordinator blueprints."""

from __future__ import annotations

from dimos.control.components import (
HardwareComponent,
HardwareType,
make_joints,
make_twist_base_joints,
)
from dimos.core.global_config import global_config
from dimos.utils.data import LfsPath

PIPER_FK_MODEL = LfsPath("piper_description/mujoco_model/piper_no_gripper_description.xml")
XARM6_FK_MODEL = LfsPath("xarm_description/urdf/xarm6/xarm6.urdf")
XARM7_FK_MODEL = LfsPath("xarm_description/urdf/xarm7/xarm7.urdf")
A750_FK_MODEL = LfsPath("a750_description/urdf/a750_rev1_no_gripper.urdf")

XARM7_SIM_PATH = LfsPath("xarm7/scene.xml")
XARM6_SIM_PATH = LfsPath("xarm6/scene.xml")
PIPER_SIM_PATH = LfsPath("piper/scene.xml")


def _adapter_kwargs(home_joints: list[float] | None = None) -> dict[str, object]:
if home_joints is None:
return {}
return {"initial_positions": home_joints}


def manipulator(
hw_id: str,
dof: int,
*,
adapter_type: str = "mock",
address: str | None = None,
gripper: bool = False,
gripper_suffix: str = "gripper",
auto_enable: bool = True,
adapter_kwargs: dict[str, object] | None = None,
home_joints: list[float] | None = None,
) -> HardwareComponent:
"""Create a manipulator hardware component with DimOS joint names."""
kwargs = _adapter_kwargs(home_joints)
if adapter_kwargs:
kwargs.update(adapter_kwargs)
return HardwareComponent(
hardware_id=hw_id,
hardware_type=HardwareType.MANIPULATOR,
joints=make_joints(hw_id, dof),
adapter_type=adapter_type,
address=address,
auto_enable=auto_enable,
gripper_joints=[f"{hw_id}/{gripper_suffix}"] if gripper else [],
adapter_kwargs=kwargs,
)


def mock_arm(
hw_id: str = "arm",
dof: int = 7,
*,
gripper: bool = False,
gripper_suffix: str = "gripper",
home_joints: list[float] | None = None,
) -> HardwareComponent:
"""Mock manipulator with no real hardware."""
return manipulator(
hw_id,
dof,
gripper=gripper,
gripper_suffix=gripper_suffix,
home_joints=home_joints,
)


def xarm7(
hw_id: str = "arm",
*,
gripper: bool = False,
mock_without_address: bool = False,
home_joints: list[float] | None = None,
) -> HardwareComponent:
"""xArm7 hardware, MuJoCo when --simulation is set, or mock if requested."""
if global_config.simulation:
return manipulator(
hw_id,
7,
adapter_type="sim_mujoco",
address=str(XARM7_SIM_PATH),
gripper=gripper,
home_joints=home_joints,
)
address = global_config.xarm7_ip
if mock_without_address and not address:
return mock_arm(hw_id, 7, gripper=gripper, home_joints=home_joints)
return manipulator(
hw_id,
7,
adapter_type="xarm",
address=address,
gripper=gripper,
home_joints=home_joints,
)


def xarm6(
hw_id: str = "arm",
*,
gripper: bool = False,
mock_without_address: bool = False,
home_joints: list[float] | None = None,
) -> HardwareComponent:
"""xArm6 hardware, MuJoCo when --simulation is set, or mock if requested."""
if global_config.simulation:
return manipulator(
hw_id,
6,
adapter_type="sim_mujoco",
address=str(XARM6_SIM_PATH),
gripper=gripper,
home_joints=home_joints,
)
address = global_config.xarm6_ip
if mock_without_address and not address:
return mock_arm(hw_id, 6, gripper=gripper, home_joints=home_joints)
return manipulator(
hw_id,
6,
adapter_type="xarm",
address=address,
gripper=gripper,
home_joints=home_joints,
)


def piper(
hw_id: str = "arm",
*,
gripper: bool = True,
mock_without_address: bool = False,
home_joints: list[float] | None = None,
) -> HardwareComponent:
"""Piper hardware, MuJoCo when --simulation is set, or mock if requested."""
if global_config.simulation:
return manipulator(
hw_id,
6,
adapter_type="sim_mujoco",
address=str(PIPER_SIM_PATH),
gripper=gripper,
home_joints=home_joints,
)
address = global_config.can_port or "can0"
if mock_without_address and not global_config.can_port:
return mock_arm(hw_id, 6, gripper=gripper, home_joints=home_joints)
return manipulator(
hw_id,
6,
adapter_type="piper",
address=address,
gripper=gripper,
home_joints=home_joints,
)


def a750(hw_id: str = "arm", *, mock_without_address: bool = False) -> HardwareComponent:
"""A-750 hardware or mock when no device path is configured."""
home_joints = [0.0, 0.0, -1.5707963267948966, 0.0, 0.0, 0.0]
if mock_without_address and not global_config.device_path:
return mock_arm(
hw_id,
6,
gripper=True,
gripper_suffix="finger",
home_joints=home_joints,
)
return manipulator(
hw_id,
6,
adapter_type="a750",
address=global_config.device_path or "/dev/ttyACM0",
gripper=True,
gripper_suffix="finger",
home_joints=home_joints,
)


def mock_twist_base(hw_id: str = "base") -> HardwareComponent:
"""Mock holonomic twist base (3-DOF: vx, vy, wz)."""
return HardwareComponent(
hardware_id=hw_id,
hardware_type=HardwareType.BASE,
joints=make_twist_base_joints(hw_id),
adapter_type="mock_twist_base",
)


__all__ = [
"A750_FK_MODEL",
"PIPER_FK_MODEL",
"PIPER_SIM_PATH",
"XARM6_FK_MODEL",
"XARM6_SIM_PATH",
"XARM7_FK_MODEL",
"XARM7_SIM_PATH",
"a750",
"manipulator",
"mock_arm",
"mock_twist_base",
"piper",
"xarm6",
"xarm7",
]
86 changes: 52 additions & 34 deletions dimos/control/blueprints/basic.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,16 +28,18 @@

from __future__ import annotations

from dimos.control.coordinator import ControlCoordinator
from dimos.core.coordination.blueprints import Blueprint, autoconnect
from dimos.core.global_config import global_config
from dimos.robot.catalog.piper import PIPER_SIM_PATH, piper as _catalog_piper
from dimos.robot.catalog.ufactory import (
from dimos.control.blueprints._hardware import (
PIPER_SIM_PATH,
XARM6_SIM_PATH,
XARM7_SIM_PATH,
xarm6 as _catalog_xarm6,
xarm7 as _catalog_xarm7,
mock_arm,
piper,
xarm6,
xarm7,
)
from dimos.control.coordinator import ControlCoordinator, TaskConfig
from dimos.core.coordination.blueprints import Blueprint, autoconnect
from dimos.core.global_config import global_config
from dimos.simulation.engines.mujoco_sim_module import MujocoSimModule

_is_sim = global_config.simulation
Expand All @@ -57,56 +59,72 @@ def _mujoco_if_sim(sim_path: str, dof: int) -> tuple[Blueprint, ...]:
)

# Mock 7-DOF arm (for testing)
_mock_cfg = _catalog_xarm7(name="arm")
_mock_hw = mock_arm("arm", 7)

coordinator_mock = ControlCoordinator.blueprint(
hardware=[_mock_cfg.to_hardware_component()],
tasks=[_mock_cfg.to_task_config()],
hardware=[_mock_hw],
tasks=[
TaskConfig(
name="traj_arm",
type="trajectory",
joint_names=_mock_hw.joints,
priority=10,
)
],
)

# XArm7 (real, or MuJoCo with --simulation)
_xarm7_cfg = _catalog_xarm7(
name="arm",
adapter_type="sim_mujoco" if _is_sim else "xarm",
address=str(XARM7_SIM_PATH) if _is_sim else global_config.xarm7_ip,
)
_xarm7_hw = xarm7("arm")

coordinator_xarm7 = autoconnect(
ControlCoordinator.blueprint(
hardware=[_xarm7_cfg.to_hardware_component()],
tasks=[_xarm7_cfg.to_task_config()],
hardware=[_xarm7_hw],
tasks=[
TaskConfig(
name="traj_arm",
type="trajectory",
joint_names=_xarm7_hw.joints,
priority=10,
)
],
),
*_mujoco_if_sim(str(XARM7_SIM_PATH), _xarm7_cfg.dof),
*_mujoco_if_sim(str(XARM7_SIM_PATH), len(_xarm7_hw.joints)),
)

# XArm6 (real, or MuJoCo with --simulation)
_xarm6_cfg = _catalog_xarm6(
name="arm",
adapter_type="sim_mujoco" if _is_sim else "xarm",
address=str(XARM6_SIM_PATH) if _is_sim else global_config.xarm6_ip,
)
_xarm6_hw = xarm6("arm", gripper=True)

coordinator_xarm6 = autoconnect(
ControlCoordinator.blueprint(
hardware=[_xarm6_cfg.to_hardware_component()],
tasks=[_xarm6_cfg.to_task_config(task_name="traj_xarm")],
hardware=[_xarm6_hw],
tasks=[
TaskConfig(
name="traj_xarm",
type="trajectory",
joint_names=_xarm6_hw.joints,
priority=10,
)
],
),
*_mujoco_if_sim(str(XARM6_SIM_PATH), _xarm6_cfg.dof),
*_mujoco_if_sim(str(XARM6_SIM_PATH), len(_xarm6_hw.joints)),
)

# Piper 6-DOF (CAN bus, or MuJoCo with --simulation)
_piper_cfg = _catalog_piper(
name="arm",
adapter_type="sim_mujoco" if _is_sim else "piper",
address=str(PIPER_SIM_PATH) if _is_sim else (global_config.can_port or "can0"),
)
_piper_hw = piper("arm")

coordinator_piper = autoconnect(
ControlCoordinator.blueprint(
hardware=[_piper_cfg.to_hardware_component()],
tasks=[_piper_cfg.to_task_config(task_name="traj_piper")],
hardware=[_piper_hw],
tasks=[
TaskConfig(
name="traj_piper",
type="trajectory",
joint_names=_piper_hw.joints,
priority=10,
)
],
),
*_mujoco_if_sim(str(PIPER_SIM_PATH), _piper_cfg.dof),
*_mujoco_if_sim(str(PIPER_SIM_PATH), len(_piper_hw.joints)),
)


Expand Down
Loading
Loading