From 2b5abb5fe5a89156296cbfbbb944fdd3351ffc15 Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Tue, 24 Feb 2026 16:06:13 -0800 Subject: [PATCH 01/18] Feat: modified buttons to publish absolute trigger values --- dimos/teleop/quest/quest_types.py | 39 ++++++++++++++++++++++++++----- 1 file changed, 33 insertions(+), 6 deletions(-) diff --git a/dimos/teleop/quest/quest_types.py b/dimos/teleop/quest/quest_types.py index 9e5616101d..1882f23531 100644 --- a/dimos/teleop/quest/quest_types.py +++ b/dimos/teleop/quest/quest_types.py @@ -94,16 +94,18 @@ def from_joy(cls, joy: Joy, is_left: bool = True) -> "QuestControllerState": class Buttons(UInt32): """Packed button states for both controllers in a single UInt32. - All values are collapsed to bools for lightweight transport. Analog values - (trigger, grip) are thresholded at 0.5. If you need the original float - values, access them from QuestControllerState and publish them in a subclass. + Digital buttons are collapsed to bools. Analog trigger values are packed + as uint8 in the upper 16 bits for proportional gripper control. Bit layout: - Left (bits 0-6): trigger, grip, touchpad, thumbstick, primary, secondary, menu - Right (bits 8-14): trigger, grip, touchpad, thumbstick, primary, secondary, menu + Left (bits 0-6): trigger, grip, touchpad, thumbstick, primary, secondary, menu + Right (bits 8-14): trigger, grip, touchpad, thumbstick, primary, secondary, menu + Bit 7, 15: reserved + Bits 16-23: left trigger analog (uint8, 0=0.0 … 255=1.0) + Bits 24-31: right trigger analog (uint8, 0=0.0 … 255=1.0) """ - # Bit positions + # Bit positions for digital buttons BITS = { "left_trigger": 0, "left_grip": 1, @@ -121,6 +123,31 @@ class Buttons(UInt32): "right_menu": 14, } + # Analog trigger packing constants + _LEFT_TRIGGER_SHIFT: int = 16 + _RIGHT_TRIGGER_SHIFT: int = 24 + _ANALOG_MASK: int = 0xFF + + @property + def left_trigger_analog(self) -> float: + """Left trigger analog value [0.0, 1.0], decoded from bits 16-23.""" + return ((self.data & 0xFFFFFFFF) >> self._LEFT_TRIGGER_SHIFT & self._ANALOG_MASK) / 255.0 + + @property + def right_trigger_analog(self) -> float: + """Right trigger analog value [0.0, 1.0], decoded from bits 24-31.""" + return ((self.data & 0xFFFFFFFF) >> self._RIGHT_TRIGGER_SHIFT & self._ANALOG_MASK) / 255.0 + + def pack_analog_triggers(self, left: float, right: float) -> None: + """Pack analog trigger values [0.0, 1.0] into bits 16-23 and 24-31.""" + left_u8 = round(max(0.0, min(1.0, left)) * 255) + right_u8 = round(max(0.0, min(1.0, right)) * 255) + unsigned = (self.data & 0x0000FFFF) | (left_u8 << self._LEFT_TRIGGER_SHIFT) | (right_u8 << self._RIGHT_TRIGGER_SHIFT) + # LCM encodes UInt32 as signed int32 — convert to avoid overflow + if unsigned >= 0x80000000: + unsigned -= 0x100000000 + self.data = unsigned + def __getattr__(self, name: str) -> bool: if name in Buttons.BITS: return bool(self.data & (1 << Buttons.BITS[name])) From 7a82f0ff9b42a62c705e0ed2f63db5ce41844e9b Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Tue, 24 Feb 2026 16:14:59 -0800 Subject: [PATCH 02/18] Fix: control loop start must be in start --- dimos/teleop/quest/quest_teleop_module.py | 1 + 1 file changed, 1 insertion(+) diff --git a/dimos/teleop/quest/quest_teleop_module.py b/dimos/teleop/quest/quest_teleop_module.py index ea77bb5fc0..3e71e3573c 100644 --- a/dimos/teleop/quest/quest_teleop_module.py +++ b/dimos/teleop/quest/quest_teleop_module.py @@ -144,6 +144,7 @@ def start(self) -> None: logger.info(f"Subscribed to: {', '.join(connected)}") self._start_server() + self._start_control_loop() logger.info("Quest Teleoperation Module started") @rpc From 4e39bbe3ee6231cf55ff8e0f0f3a6bc67130db72 Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Tue, 24 Feb 2026 16:15:35 -0800 Subject: [PATCH 03/18] feat: packing analog triggers iwith buttons in UInt32 --- dimos/teleop/quest/quest_extensions.py | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/dimos/teleop/quest/quest_extensions.py b/dimos/teleop/quest/quest_extensions.py index b4e38de546..4f15d7108b 100644 --- a/dimos/teleop/quest/quest_extensions.py +++ b/dimos/teleop/quest/quest_extensions.py @@ -28,6 +28,7 @@ from dimos.msgs.geometry_msgs import PoseStamped, TwistStamped from dimos.teleop.quest.quest_teleop_module import Hand, QuestTeleopConfig, QuestTeleopModule +from dimos.teleop.quest.quest_types import Buttons, QuestControllerState from dimos.teleop.utils.teleop_visualization import ( visualize_buttons, visualize_pose, @@ -130,6 +131,25 @@ def _publish_msg(self, hand: Hand, output_msg: PoseStamped) -> None: ) super()._publish_msg(hand, output_msg) + def _publish_button_state( + self, + left: QuestControllerState | None, + right: QuestControllerState | None, + ) -> None: + """Publish Buttons with analog triggers packed into bits 16-31. + + Builds the standard digital Buttons, then packs raw analog trigger + floats from QuestControllerState into bits 16-23 (left) and 24-31 + (right) so the downstream TeleopIKTask can drive proportional gripper + control via on_buttons(). + """ + buttons = Buttons.from_controllers(left, right) + buttons.pack_analog_triggers( + left=left.trigger if left is not None else 0.0, + right=right.trigger if right is not None else 0.0, + ) + self.buttons.publish(buttons) + class VisualizingTeleopModule(ArmTeleopModule): """Quest teleop with Rerun visualization. From 279e024b464bb20a7360898c0fdcb3d52f6d9dbc Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Tue, 24 Feb 2026 16:16:13 -0800 Subject: [PATCH 04/18] for xarm7 --- dimos/robot/all_blueprints.py | 4 ++-- dimos/teleop/quest/blueprints.py | 12 ++++++------ 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index ed90982801..c9f9e8a1c7 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -20,7 +20,7 @@ "arm-teleop-dual": "dimos.teleop.quest.blueprints:arm_teleop_dual", "arm-teleop-piper": "dimos.teleop.quest.blueprints:arm_teleop_piper", "arm-teleop-visualizing": "dimos.teleop.quest.blueprints:arm_teleop_visualizing", - "arm-teleop-xarm6": "dimos.teleop.quest.blueprints:arm_teleop_xarm6", + "arm-teleop-xarm7": "dimos.teleop.quest.blueprints:arm_teleop_xarm7", "coordinator-basic": "dimos.control.blueprints:coordinator_basic", "coordinator-cartesian-ik-mock": "dimos.control.blueprints:coordinator_cartesian_ik_mock", "coordinator-cartesian-ik-piper": "dimos.control.blueprints:coordinator_cartesian_ik_piper", @@ -34,7 +34,7 @@ "coordinator-piper-xarm": "dimos.control.blueprints:coordinator_piper_xarm", "coordinator-teleop-dual": "dimos.control.blueprints:coordinator_teleop_dual", "coordinator-teleop-piper": "dimos.control.blueprints:coordinator_teleop_piper", - "coordinator-teleop-xarm6": "dimos.control.blueprints:coordinator_teleop_xarm6", + "coordinator-teleop-xarm7": "dimos.control.blueprints:coordinator_teleop_xarm7", "coordinator-velocity-xarm6": "dimos.control.blueprints:coordinator_velocity_xarm6", "coordinator-xarm6": "dimos.control.blueprints:coordinator_xarm6", "coordinator-xarm7": "dimos.control.blueprints:coordinator_xarm7", diff --git a/dimos/teleop/quest/blueprints.py b/dimos/teleop/quest/blueprints.py index c46bf657ff..5672a2bea0 100644 --- a/dimos/teleop/quest/blueprints.py +++ b/dimos/teleop/quest/blueprints.py @@ -18,7 +18,7 @@ from dimos.control.blueprints import ( coordinator_teleop_dual, coordinator_teleop_piper, - coordinator_teleop_xarm6, + coordinator_teleop_xarm7, ) from dimos.core.blueprints import autoconnect from dimos.core.transport import LCMTransport @@ -57,12 +57,12 @@ # Teleop wired to Coordinator (TeleopIK) # ----------------------------------------------------------------------------- -# Single XArm6 teleop: right controller -> xarm6 -# Usage: dimos run arm-teleop-xarm6 +# Single XArm7 teleop: right controller -> xarm7 +# Usage: dimos run arm-teleop-xarm7 -arm_teleop_xarm6 = autoconnect( +arm_teleop_xarm7 = autoconnect( arm_teleop_module(task_names={"right": "teleop_xarm"}), - coordinator_teleop_xarm6, + coordinator_teleop_xarm7, ).transports( { ("right_controller_output", PoseStamped): LCMTransport( @@ -110,5 +110,5 @@ "arm_teleop_dual", "arm_teleop_piper", "arm_teleop_visualizing", - "arm_teleop_xarm6", + "arm_teleop_xarm7", ] From 7b823e2a77aa019af8e0657a43b2c013376b1ef7 Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Tue, 24 Feb 2026 16:17:36 -0800 Subject: [PATCH 05/18] Feat: added gripper as hardware_component --- dimos/control/__init__.py | 3 +- dimos/control/blueprints.py | 46 ++++++++++++++--- dimos/control/components.py | 17 +++++++ dimos/control/coordinator.py | 54 ++++++++++++++++++-- dimos/control/hardware_interface.py | 55 +++++++++++++++++++++ dimos/hardware/manipulators/xarm/adapter.py | 7 ++- 6 files changed, 168 insertions(+), 14 deletions(-) diff --git a/dimos/control/__init__.py b/dimos/control/__init__.py index 23ac02836b..9831abe0cc 100644 --- a/dimos/control/__init__.py +++ b/dimos/control/__init__.py @@ -60,6 +60,7 @@ "HardwareType", "JointName", "JointState", + "make_gripper_joint", "make_joints", ], "coordinator": [ @@ -68,7 +69,7 @@ "TaskConfig", "control_coordinator", ], - "hardware_interface": ["ConnectedHardware"], + "hardware_interface": ["ConnectedGripper", "ConnectedHardware"], "task": [ "ControlMode", "ControlTask", diff --git a/dimos/control/blueprints.py b/dimos/control/blueprints.py index 5c33928e79..0f567bfaf6 100644 --- a/dimos/control/blueprints.py +++ b/dimos/control/blueprints.py @@ -33,6 +33,7 @@ from dimos.control.components import ( HardwareComponent, HardwareType, + make_gripper_joint, make_joints, make_twist_base_joints, ) @@ -45,6 +46,7 @@ _PIPER_MODEL_PATH = LfsPath("piper_description/mujoco_model/piper_no_gripper_description.xml") _XARM6_MODEL_PATH = LfsPath("xarm_description/urdf/xarm6/xarm6.urdf") +_XARM7_MODEL_PATH = LfsPath("xarm_description/urdf/xarm7/xarm7.urdf") # ============================================================================= @@ -473,8 +475,8 @@ # Teleop IK Blueprints (VR teleoperation with internal Pinocchio IK) # ============================================================================= -# Single XArm6 with TeleopIK -coordinator_teleop_xarm6 = control_coordinator( +# Single XArm7 with TeleopIK +coordinator_teleop_xarm7 = control_coordinator( tick_rate=100.0, publish_joint_state=True, joint_state_frame_id="coordinator", @@ -482,21 +484,28 @@ HardwareComponent( hardware_id="arm", hardware_type=HardwareType.MANIPULATOR, - joints=make_joints("arm", 6), + joints=make_joints("arm", 7), adapter_type="xarm", - address="192.168.1.210", + address="192.168.2.235", auto_enable=True, ), + HardwareComponent( + hardware_id=make_gripper_joint("arm"), + hardware_type=HardwareType.GRIPPER, + joints=[make_gripper_joint("arm")], + parent_hardware_id="arm", + ), ], tasks=[ TaskConfig( name="teleop_xarm", type="teleop_ik", - joint_names=[f"arm_joint{i + 1}" for i in range(6)], + joint_names=[f"arm_joint{i + 1}" for i in range(7)], priority=10, - model_path=_XARM6_MODEL_PATH, - ee_joint_id=6, + model_path=_XARM7_MODEL_PATH, + ee_joint_id=7, hand="right", + gripper_joint=make_gripper_joint("arm"), ), ], ).transports( @@ -523,6 +532,12 @@ address="can0", auto_enable=True, ), + HardwareComponent( + hardware_id=make_gripper_joint("arm"), + hardware_type=HardwareType.GRIPPER, + joints=[make_gripper_joint("arm")], + parent_hardware_id="arm", + ), ], tasks=[ TaskConfig( @@ -533,6 +548,7 @@ model_path=_PIPER_MODEL_PATH, ee_joint_id=6, hand="left", + gripper_joint=make_gripper_joint("arm"), ), ], ).transports( @@ -559,6 +575,12 @@ address="192.168.1.210", auto_enable=True, ), + HardwareComponent( + hardware_id=make_gripper_joint("xarm_arm"), + hardware_type=HardwareType.GRIPPER, + joints=[make_gripper_joint("xarm_arm")], + parent_hardware_id="xarm_arm", + ), HardwareComponent( hardware_id="piper_arm", hardware_type=HardwareType.MANIPULATOR, @@ -567,6 +589,12 @@ address="can0", auto_enable=True, ), + HardwareComponent( + hardware_id=make_gripper_joint("piper_arm"), + hardware_type=HardwareType.GRIPPER, + joints=[make_gripper_joint("piper_arm")], + parent_hardware_id="piper_arm", + ), ], tasks=[ TaskConfig( @@ -577,6 +605,7 @@ model_path=_XARM6_MODEL_PATH, ee_joint_id=6, hand="left", + gripper_joint=make_gripper_joint("xarm_arm"), ), TaskConfig( name="teleop_piper", @@ -586,6 +615,7 @@ model_path=_PIPER_MODEL_PATH, ee_joint_id=6, hand="right", + gripper_joint=make_gripper_joint("piper_arm"), ), ], ).transports( @@ -714,7 +744,7 @@ # Teleop IK "coordinator_teleop_dual", "coordinator_teleop_piper", - "coordinator_teleop_xarm6", + "coordinator_teleop_xarm7", "coordinator_velocity_xarm6", "coordinator_xarm6", "coordinator_xarm7", diff --git a/dimos/control/components.py b/dimos/control/components.py index 8157a288d2..cc327eb623 100644 --- a/dimos/control/components.py +++ b/dimos/control/components.py @@ -48,6 +48,9 @@ class HardwareComponent: adapter_type: Adapter type ("mock", "xarm", "piper") address: Connection address - IP for TCP, port for CAN auto_enable: Whether to auto-enable servos + parent_hardware_id: For GRIPPER type only — the hardware_id of the + manipulator whose adapter provides the gripper interface. + The gripper shares the parent's already-connected adapter. """ hardware_id: HardwareId @@ -56,6 +59,19 @@ class HardwareComponent: adapter_type: str = "mock" address: str | None = None auto_enable: bool = True + parent_hardware_id: HardwareId | None = None + + +def make_gripper_joint(hardware_id: HardwareId) -> str: + """Create the gripper joint name for a hardware device. + + Args: + hardware_id: The hardware identifier (e.g., "arm") + + Returns: + Joint name like "arm_gripper" + """ + return f"{hardware_id}_gripper" def make_joints(hardware_id: HardwareId, dof: int) -> list[JointName]: @@ -112,6 +128,7 @@ def make_twist_base_joints( "JointName", "JointState", "TaskName", + "make_gripper_joint", "make_joints", "make_twist_base_joints", ] diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index c9182e6aa8..9f477a9c62 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -85,6 +85,10 @@ class TaskConfig: priority: Task priority (higher wins arbitration) model_path: Path to URDF/MJCF for IK solver (cartesian_ik/teleop_ik only) ee_joint_id: End-effector joint ID in model (cartesian_ik/teleop_ik only) + hand: "left" or "right" controller hand (teleop_ik only) + gripper_joint: Joint name for gripper virtual joint (teleop_ik only) + gripper_open_pos: Gripper position at trigger 0.0 (teleop_ik only) + gripper_closed_pos: Gripper position at trigger 1.0 (teleop_ik only) """ name: str @@ -95,6 +99,10 @@ class TaskConfig: model_path: str | Path | None = None ee_joint_id: int = 6 hand: str = "" # teleop_ik only: "left" or "right" controller + # Teleop IK gripper specific + gripper_joint: str | None = None + gripper_open_pos: float = 0.85 + gripper_closed_pos: float = 0.0 @dataclass @@ -223,6 +231,10 @@ def _setup_from_config(self) -> None: def _setup_hardware(self, component: HardwareComponent) -> None: """Connect and add a single hardware adapter.""" + if component.hardware_type == HardwareType.GRIPPER: + self._setup_gripper_hardware(component) + return + adapter: ManipulatorAdapter | TwistBaseAdapter if component.hardware_type == HardwareType.BASE: adapter = self._create_twist_base_adapter(component) @@ -241,6 +253,29 @@ def _setup_hardware(self, component: HardwareComponent) -> None: adapter.disconnect() raise + def _setup_gripper_hardware(self, component: HardwareComponent) -> None: + """Register a gripper by borrowing the parent arm's adapter. + + The gripper shares the parent manipulator's already-connected adapter. + No new connection is made; disconnect() on ConnectedGripper is a no-op. + """ + if not component.parent_hardware_id: + raise ValueError( + f"Gripper component '{component.hardware_id}' requires parent_hardware_id" + ) + + with self._hardware_lock: + parent = self._hardware.get(component.parent_hardware_id) + + if parent is None: + raise ValueError( + f"Parent hardware '{component.parent_hardware_id}' not found " + f"for gripper '{component.hardware_id}'. " + f"Add the parent arm before the gripper." + ) + + self.add_hardware(parent.adapter, component) + def _create_adapter(self, component: HardwareComponent) -> ManipulatorAdapter: """Create a manipulator adapter from component config.""" from dimos.hardware.manipulators.registry import adapter_registry @@ -328,6 +363,9 @@ def _create_task_from_config(self, cfg: TaskConfig) -> ControlTask: ee_joint_id=cfg.ee_joint_id, priority=cfg.priority, hand=cfg.hand, + gripper_joint=cfg.gripper_joint, + gripper_open_pos=cfg.gripper_open_pos, + gripper_closed_pos=cfg.gripper_closed_pos, ), ) @@ -345,8 +383,11 @@ def add_hardware( component: HardwareComponent, ) -> bool: """Register a hardware adapter with the coordinator.""" + is_gripper = component.hardware_type == HardwareType.GRIPPER is_base = component.hardware_type == HardwareType.BASE - if is_base != isinstance(adapter, TwistBaseAdapter): + + # Grippers reuse their parent arm's ManipulatorAdapter — skip the base/adapter check + if not is_gripper and (is_base != isinstance(adapter, TwistBaseAdapter)): raise TypeError( f"Hardware type / adapter mismatch for '{component.hardware_id}': " f"hardware_type={component.hardware_type.value} but got " @@ -358,8 +399,15 @@ def add_hardware( logger.warning(f"Hardware {component.hardware_id} already registered") return False - if isinstance(adapter, TwistBaseAdapter): - connected: ConnectedHardware = ConnectedTwistBase( + if is_gripper: + from dimos.control.hardware_interface import ConnectedGripper + + connected: ConnectedHardware = ConnectedGripper( + adapter=adapter, # type: ignore[arg-type] + component=component, + ) + elif isinstance(adapter, TwistBaseAdapter): + connected = ConnectedTwistBase( adapter=adapter, component=component, ) diff --git a/dimos/control/hardware_interface.py b/dimos/control/hardware_interface.py index 4e5d1d634c..75f3198ee2 100644 --- a/dimos/control/hardware_interface.py +++ b/dimos/control/hardware_interface.py @@ -287,7 +287,62 @@ def write_command(self, commands: dict[str, float], _mode: ControlMode) -> bool: return self._twist_adapter.write_velocities(ordered) +class ConnectedGripper(ConnectedHardware): + """Runtime wrapper for a gripper attached to a manipulator. + + Shares the parent manipulator's adapter but routes read/write + through gripper-specific adapter methods (read_gripper_position / + write_gripper_position). Lifecycle (connect / disconnect) is owned + by the parent ConnectedHardware — disconnect() is a no-op here. + + Registered as a separate HardwareComponent with hardware_type=GRIPPER + so the tick loop treats it uniformly alongside arm joints. + """ + + def __init__( + self, + adapter: ManipulatorAdapter, + component: HardwareComponent, + ) -> None: + super().__init__(adapter, component) + # Gripper starts at 0 — no need to read current position on init + self._last_commanded = {name: 0.0 for name in self._joint_names} + self._initialized = True + + def disconnect(self) -> None: + """No-op: lifecycle is owned by the parent ConnectedHardware.""" + + def read_state(self) -> dict[JointName, JointState]: + """Read gripper position via adapter.read_gripper_position().""" + from dimos.control.components import JointState + + pos = self._adapter.read_gripper_position() + joint_name = self._joint_names[0] + return { + joint_name: JointState( + position=pos if pos is not None else 0.0, + velocity=0.0, + effort=0.0, + ) + } + + def write_command(self, commands: dict[str, float], _mode: ControlMode) -> bool: + """Write gripper position via adapter.write_gripper_position(). + + Mode is ignored — gripper is always position-controlled. + """ + joint_name = self._joint_names[0] + if joint_name not in commands: + return True # nothing commanded this tick, hold current + return self._adapter.write_gripper_position(commands[joint_name]) + + def _initialize_last_commanded(self) -> None: + """No-op: already initialized in __init__.""" + self._initialized = True + + __all__ = [ + "ConnectedGripper", "ConnectedHardware", "ConnectedTwistBase", ] diff --git a/dimos/hardware/manipulators/xarm/adapter.py b/dimos/hardware/manipulators/xarm/adapter.py index dd9f764031..80cc8edb38 100644 --- a/dimos/hardware/manipulators/xarm/adapter.py +++ b/dimos/hardware/manipulators/xarm/adapter.py @@ -62,6 +62,7 @@ def __init__(self, address: str, dof: int = 6, **_: object) -> None: self._dof = dof self._arm: XArmAPI | None = None self._control_mode: ControlMode = ControlMode.POSITION + self._gripper_enabled: bool = False # ========================================================================= # Connection @@ -351,9 +352,11 @@ def write_gripper_position(self, position: float) -> bool: if not self._arm: return False - self._arm.set_gripper_enable(True) + if not self._gripper_enabled: + self._arm.set_gripper_enable(True) + self._gripper_enabled = True pos_mm = position * M_TO_MM - code: int = self._arm.set_gripper_position(pos_mm, wait=True) + code: int = self._arm.set_gripper_position(pos_mm, wait=False) return code == 0 # ========================================================================= From 3024b5508599e49c6c873de743df7723278d36d0 Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Tue, 24 Feb 2026 16:18:23 -0800 Subject: [PATCH 06/18] Feat: gripper trigger decode --- dimos/control/tasks/teleop_task.py | 70 ++++++++++++++++++++++++++++-- 1 file changed, 67 insertions(+), 3 deletions(-) diff --git a/dimos/control/tasks/teleop_task.py b/dimos/control/tasks/teleop_task.py index d1a90eb6d0..3574f660a1 100644 --- a/dimos/control/tasks/teleop_task.py +++ b/dimos/control/tasks/teleop_task.py @@ -69,6 +69,12 @@ 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"). + When set, on_gripper_trigger() maps a 0-1 analog trigger to gripper + position and includes it in JointCommandOutput each tick alongside + the arm joints. Requires a ConnectedGripper registered under this name. + gripper_open_pos: Gripper position (meters) at trigger value 0.0 (no press). + gripper_closed_pos: Gripper position (meters) at trigger value 1.0 (full press). """ joint_names: list[str] @@ -76,8 +82,11 @@ class TeleopIKTaskConfig: ee_joint_id: int priority: int = 10 timeout: float = 0.5 - max_joint_delta_deg: float = 5.0 # ~500°/s at 100Hz + max_joint_delta_deg: float = 20.0 # loosened; tighten once IK null-space regularization is added hand: str = "" + gripper_joint: str | None = None + gripper_open_pos: float = 0.85 + gripper_closed_pos: float = 0.0 class TeleopIKTask(BaseControlTask): @@ -148,6 +157,10 @@ def __init__(self, name: str, config: TeleopIKTaskConfig) -> None: self._initial_ee_pose: pinocchio.SE3 | None = None self._prev_primary: bool = False + # Gripper state — only active when config.gripper_joint is set. + # Starts at open position so the gripper doesn't unexpectedly close on engage. + self._gripper_target: float = config.gripper_open_pos + logger.info( f"TeleopIKTask {name} initialized with model: {config.model_path}, " f"ee_joint_id={config.ee_joint_id}, joints={config.joint_names}" @@ -160,8 +173,11 @@ def name(self) -> str: def claim(self) -> ResourceClaim: """Declare resource requirements.""" + joints = self._joint_names + if self._config.gripper_joint: + joints = joints | frozenset([self._config.gripper_joint]) return ResourceClaim( - joints=self._joint_names, + joints=joints, priority=self._config.priority, mode=ControlMode.SERVO_POSITION, ) @@ -245,9 +261,18 @@ def compute(self, state: CoordinatorState) -> JointCommandOutput | None: ) return None + joint_names = list(self._joint_names_list) positions = q_solution.flatten().tolist() + + # Append gripper joint if configured — routed to ConnectedGripper by tick loop + if self._config.gripper_joint: + with self._lock: + gripper_pos = self._gripper_target + joint_names.append(self._config.gripper_joint) + positions.append(gripper_pos) + return JointCommandOutput( - joint_names=self._joint_names_list, + joint_names=joint_names, positions=positions, mode=ControlMode.SERVO_POSITION, ) @@ -302,6 +327,19 @@ def on_buttons(self, msg: Buttons) -> bool: self._target_pose = None self._initial_ee_pose = None self._prev_primary = primary + + # Gripper: decode analog trigger from bits 16-31 of Buttons and update target + if self._config.gripper_joint: + if hand == "left": + self.on_gripper_trigger(msg.left_trigger_analog, 0.0) + elif hand == "right": + self.on_gripper_trigger(msg.right_trigger_analog, 0.0) + else: + logger.warning( + f"TeleopIKTask {self._name}: gripper_joint is set but hand is not " + f"'left' or 'right' — cannot determine which trigger to use" + ) + return True def on_cartesian_command(self, pose: Pose | PoseStamped, t_now: float) -> bool: @@ -313,6 +351,32 @@ def on_cartesian_command(self, pose: Pose | PoseStamped, t_now: float) -> bool: return True + def on_gripper_trigger(self, value: float, _t_now: float) -> bool: + """Map analog trigger (0-1) to gripper position. + + Called each tick by the coordinator when a trigger stream is wired in. + Linearly interpolates: 0.0 → gripper_open_pos, 1.0 → gripper_closed_pos. + + Args: + value: Trigger value in [0.0, 1.0] (0 = no press, 1 = full press) + t_now: Current time (unused — gripper holds position indefinitely) + + Returns: + True if gripper_joint is configured, False otherwise + """ + if not self._config.gripper_joint: + return False + + clamped = max(0.0, min(1.0, value)) + pos = self._config.gripper_open_pos + ( + self._config.gripper_closed_pos - self._config.gripper_open_pos + ) * clamped + + with self._lock: + self._gripper_target = pos + + return True + def start(self) -> None: """Activate the task (start accepting and outputting commands).""" with self._lock: From 5617a628d3121404f3ff64b9a6508a3a3df6bad1 Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Tue, 24 Feb 2026 16:19:52 -0800 Subject: [PATCH 07/18] Fix: pre-commit fixes --- dimos/control/tasks/teleop_task.py | 11 +++++++---- dimos/teleop/quest/quest_types.py | 6 +++++- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/dimos/control/tasks/teleop_task.py b/dimos/control/tasks/teleop_task.py index 3574f660a1..9e5d352530 100644 --- a/dimos/control/tasks/teleop_task.py +++ b/dimos/control/tasks/teleop_task.py @@ -82,7 +82,9 @@ class TeleopIKTaskConfig: ee_joint_id: int priority: int = 10 timeout: float = 0.5 - max_joint_delta_deg: float = 20.0 # loosened; tighten once IK null-space regularization is added + max_joint_delta_deg: float = ( + 20.0 # loosened; tighten once IK null-space regularization is added + ) hand: str = "" gripper_joint: str | None = None gripper_open_pos: float = 0.85 @@ -368,9 +370,10 @@ def on_gripper_trigger(self, value: float, _t_now: float) -> bool: return False clamped = max(0.0, min(1.0, value)) - pos = self._config.gripper_open_pos + ( - self._config.gripper_closed_pos - self._config.gripper_open_pos - ) * clamped + pos = ( + self._config.gripper_open_pos + + (self._config.gripper_closed_pos - self._config.gripper_open_pos) * clamped + ) with self._lock: self._gripper_target = pos diff --git a/dimos/teleop/quest/quest_types.py b/dimos/teleop/quest/quest_types.py index 1882f23531..67fc27587c 100644 --- a/dimos/teleop/quest/quest_types.py +++ b/dimos/teleop/quest/quest_types.py @@ -142,7 +142,11 @@ def pack_analog_triggers(self, left: float, right: float) -> None: """Pack analog trigger values [0.0, 1.0] into bits 16-23 and 24-31.""" left_u8 = round(max(0.0, min(1.0, left)) * 255) right_u8 = round(max(0.0, min(1.0, right)) * 255) - unsigned = (self.data & 0x0000FFFF) | (left_u8 << self._LEFT_TRIGGER_SHIFT) | (right_u8 << self._RIGHT_TRIGGER_SHIFT) + unsigned = ( + (self.data & 0x0000FFFF) + | (left_u8 << self._LEFT_TRIGGER_SHIFT) + | (right_u8 << self._RIGHT_TRIGGER_SHIFT) + ) # LCM encodes UInt32 as signed int32 — convert to avoid overflow if unsigned >= 0x80000000: unsigned -= 0x100000000 From 32349c92e80cb922b0a6392b09956225baa00d6c Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Wed, 25 Feb 2026 15:14:41 -0800 Subject: [PATCH 08/18] comments update --- dimos/control/components.py | 4 +--- dimos/control/coordinator.py | 6 +++--- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/dimos/control/components.py b/dimos/control/components.py index cc327eb623..dd2e6a8d98 100644 --- a/dimos/control/components.py +++ b/dimos/control/components.py @@ -48,9 +48,7 @@ class HardwareComponent: adapter_type: Adapter type ("mock", "xarm", "piper") address: Connection address - IP for TCP, port for CAN auto_enable: Whether to auto-enable servos - parent_hardware_id: For GRIPPER type only — the hardware_id of the - manipulator whose adapter provides the gripper interface. - The gripper shares the parent's already-connected adapter. + parent_hardware_id: For GRIPPER type only — gripper shares the parent's already-connected adapter. """ hardware_id: HardwareId diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index 9f477a9c62..c39ffeba7a 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -86,9 +86,9 @@ class TaskConfig: model_path: Path to URDF/MJCF for IK solver (cartesian_ik/teleop_ik only) ee_joint_id: End-effector joint ID in model (cartesian_ik/teleop_ik only) hand: "left" or "right" controller hand (teleop_ik only) - gripper_joint: Joint name for gripper virtual joint (teleop_ik only) - gripper_open_pos: Gripper position at trigger 0.0 (teleop_ik only) - gripper_closed_pos: Gripper position at trigger 1.0 (teleop_ik only) + gripper_joint: Joint name for gripper virtual joint + gripper_open_pos: Gripper position at trigger 0.0 + gripper_closed_pos: Gripper position at trigger 1.0 """ name: str From 269be7d9837805b3d424b967f6caa06aa910fcf0 Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Wed, 25 Feb 2026 17:02:42 -0800 Subject: [PATCH 09/18] fix: bit conversion amth + comments --- dimos/control/blueprints.py | 16 ++--------- dimos/control/coordinator.py | 9 ++---- dimos/control/hardware_interface.py | 5 ---- dimos/control/tasks/teleop_task.py | 22 ++------------- dimos/teleop/quest/quest_extensions.py | 8 +----- dimos/teleop/quest/quest_types.py | 38 ++++++++++++-------------- 6 files changed, 26 insertions(+), 72 deletions(-) diff --git a/dimos/control/blueprints.py b/dimos/control/blueprints.py index 0f567bfaf6..125a379860 100644 --- a/dimos/control/blueprints.py +++ b/dimos/control/blueprints.py @@ -506,6 +506,8 @@ ee_joint_id=7, hand="right", gripper_joint=make_gripper_joint("arm"), + gripper_open_pos=0.85, # xArm gripper range + gripper_closed_pos=0.0, ), ], ).transports( @@ -575,12 +577,6 @@ address="192.168.1.210", auto_enable=True, ), - HardwareComponent( - hardware_id=make_gripper_joint("xarm_arm"), - hardware_type=HardwareType.GRIPPER, - joints=[make_gripper_joint("xarm_arm")], - parent_hardware_id="xarm_arm", - ), HardwareComponent( hardware_id="piper_arm", hardware_type=HardwareType.MANIPULATOR, @@ -589,12 +585,6 @@ address="can0", auto_enable=True, ), - HardwareComponent( - hardware_id=make_gripper_joint("piper_arm"), - hardware_type=HardwareType.GRIPPER, - joints=[make_gripper_joint("piper_arm")], - parent_hardware_id="piper_arm", - ), ], tasks=[ TaskConfig( @@ -605,7 +595,6 @@ model_path=_XARM6_MODEL_PATH, ee_joint_id=6, hand="left", - gripper_joint=make_gripper_joint("xarm_arm"), ), TaskConfig( name="teleop_piper", @@ -615,7 +604,6 @@ model_path=_PIPER_MODEL_PATH, ee_joint_id=6, hand="right", - gripper_joint=make_gripper_joint("piper_arm"), ), ], ).transports( diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index c39ffeba7a..f330f296ea 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -254,11 +254,7 @@ def _setup_hardware(self, component: HardwareComponent) -> None: raise def _setup_gripper_hardware(self, component: HardwareComponent) -> None: - """Register a gripper by borrowing the parent arm's adapter. - - The gripper shares the parent manipulator's already-connected adapter. - No new connection is made; disconnect() on ConnectedGripper is a no-op. - """ + """Register a gripper by borrowing the parent arm's adapter""" if not component.parent_hardware_id: raise ValueError( f"Gripper component '{component.hardware_id}' requires parent_hardware_id" @@ -269,8 +265,7 @@ def _setup_gripper_hardware(self, component: HardwareComponent) -> None: if parent is None: raise ValueError( - f"Parent hardware '{component.parent_hardware_id}' not found " - f"for gripper '{component.hardware_id}'. " + f"Parent hardware '{component.parent_hardware_id}' not found for gripper '{component.hardware_id}'" f"Add the parent arm before the gripper." ) diff --git a/dimos/control/hardware_interface.py b/dimos/control/hardware_interface.py index 75f3198ee2..a3ccbcc5da 100644 --- a/dimos/control/hardware_interface.py +++ b/dimos/control/hardware_interface.py @@ -305,7 +305,6 @@ def __init__( component: HardwareComponent, ) -> None: super().__init__(adapter, component) - # Gripper starts at 0 — no need to read current position on init self._last_commanded = {name: 0.0 for name in self._joint_names} self._initialized = True @@ -336,10 +335,6 @@ def write_command(self, commands: dict[str, float], _mode: ControlMode) -> bool: return True # nothing commanded this tick, hold current return self._adapter.write_gripper_position(commands[joint_name]) - def _initialize_last_commanded(self) -> None: - """No-op: already initialized in __init__.""" - self._initialized = True - __all__ = [ "ConnectedGripper", diff --git a/dimos/control/tasks/teleop_task.py b/dimos/control/tasks/teleop_task.py index 9e5d352530..b30e6043d2 100644 --- a/dimos/control/tasks/teleop_task.py +++ b/dimos/control/tasks/teleop_task.py @@ -70,9 +70,6 @@ class TeleopIKTaskConfig: 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"). - When set, on_gripper_trigger() maps a 0-1 analog trigger to gripper - position and includes it in JointCommandOutput each tick alongside - the arm joints. Requires a ConnectedGripper registered under this name. gripper_open_pos: Gripper position (meters) at trigger value 0.0 (no press). gripper_closed_pos: Gripper position (meters) at trigger value 1.0 (full press). """ @@ -82,12 +79,10 @@ class TeleopIKTaskConfig: ee_joint_id: int priority: int = 10 timeout: float = 0.5 - max_joint_delta_deg: float = ( - 20.0 # loosened; tighten once IK null-space regularization is added - ) + max_joint_delta_deg: float = 20.0 hand: str = "" gripper_joint: str | None = None - gripper_open_pos: float = 0.85 + gripper_open_pos: float = 0.0 gripper_closed_pos: float = 0.0 @@ -354,18 +349,7 @@ def on_cartesian_command(self, pose: Pose | PoseStamped, t_now: float) -> bool: return True def on_gripper_trigger(self, value: float, _t_now: float) -> bool: - """Map analog trigger (0-1) to gripper position. - - Called each tick by the coordinator when a trigger stream is wired in. - Linearly interpolates: 0.0 → gripper_open_pos, 1.0 → gripper_closed_pos. - - Args: - value: Trigger value in [0.0, 1.0] (0 = no press, 1 = full press) - t_now: Current time (unused — gripper holds position indefinitely) - - Returns: - True if gripper_joint is configured, False otherwise - """ + """Map analog trigger (0-1) to gripper position""" if not self._config.gripper_joint: return False diff --git a/dimos/teleop/quest/quest_extensions.py b/dimos/teleop/quest/quest_extensions.py index 4f15d7108b..ce6fdba38e 100644 --- a/dimos/teleop/quest/quest_extensions.py +++ b/dimos/teleop/quest/quest_extensions.py @@ -136,13 +136,7 @@ def _publish_button_state( left: QuestControllerState | None, right: QuestControllerState | None, ) -> None: - """Publish Buttons with analog triggers packed into bits 16-31. - - Builds the standard digital Buttons, then packs raw analog trigger - floats from QuestControllerState into bits 16-23 (left) and 24-31 - (right) so the downstream TeleopIKTask can drive proportional gripper - control via on_buttons(). - """ + """Publish Buttons with analog triggers packed into bits 16-31""" buttons = Buttons.from_controllers(left, right) buttons.pack_analog_triggers( left=left.trigger if left is not None else 0.0, diff --git a/dimos/teleop/quest/quest_types.py b/dimos/teleop/quest/quest_types.py index 67fc27587c..7fd991a76c 100644 --- a/dimos/teleop/quest/quest_types.py +++ b/dimos/teleop/quest/quest_types.py @@ -95,14 +95,15 @@ class Buttons(UInt32): """Packed button states for both controllers in a single UInt32. Digital buttons are collapsed to bools. Analog trigger values are packed - as uint8 in the upper 16 bits for proportional gripper control. + as 7-bit integers in the upper 16 bits for proportional gripper control. Bit layout: Left (bits 0-6): trigger, grip, touchpad, thumbstick, primary, secondary, menu Right (bits 8-14): trigger, grip, touchpad, thumbstick, primary, secondary, menu Bit 7, 15: reserved - Bits 16-23: left trigger analog (uint8, 0=0.0 … 255=1.0) - Bits 24-31: right trigger analog (uint8, 0=0.0 … 255=1.0) + Bits 16-22: left trigger analog (7-bit, 0=0.0 … 127=1.0) + Bits 23-29: right trigger analog (7-bit, 0=0.0 … 127=1.0) + Bits 30-31: unused (kept clear so LCM signed int32 never overflows) """ # Bit positions for digital buttons @@ -125,32 +126,29 @@ class Buttons(UInt32): # Analog trigger packing constants _LEFT_TRIGGER_SHIFT: int = 16 - _RIGHT_TRIGGER_SHIFT: int = 24 - _ANALOG_MASK: int = 0xFF + _RIGHT_TRIGGER_SHIFT: int = 23 + _ANALOG_MASK: int = 0x7F + _ANALOG_MAX: int = 127 @property def left_trigger_analog(self) -> float: - """Left trigger analog value [0.0, 1.0], decoded from bits 16-23.""" - return ((self.data & 0xFFFFFFFF) >> self._LEFT_TRIGGER_SHIFT & self._ANALOG_MASK) / 255.0 + """Left trigger analog value [0.0, 1.0], decoded from bits 16-22.""" + return ((self.data >> self._LEFT_TRIGGER_SHIFT) & self._ANALOG_MASK) / self._ANALOG_MAX @property def right_trigger_analog(self) -> float: - """Right trigger analog value [0.0, 1.0], decoded from bits 24-31.""" - return ((self.data & 0xFFFFFFFF) >> self._RIGHT_TRIGGER_SHIFT & self._ANALOG_MASK) / 255.0 + """Right trigger analog value [0.0, 1.0], decoded from bits 23-29.""" + return ((self.data >> self._RIGHT_TRIGGER_SHIFT) & self._ANALOG_MASK) / self._ANALOG_MAX def pack_analog_triggers(self, left: float, right: float) -> None: - """Pack analog trigger values [0.0, 1.0] into bits 16-23 and 24-31.""" - left_u8 = round(max(0.0, min(1.0, left)) * 255) - right_u8 = round(max(0.0, min(1.0, right)) * 255) - unsigned = ( - (self.data & 0x0000FFFF) - | (left_u8 << self._LEFT_TRIGGER_SHIFT) - | (right_u8 << self._RIGHT_TRIGGER_SHIFT) + """Pack analog trigger values [0.0, 1.0] into bits 16-22 and 23-29.""" + left_u7 = round(max(0.0, min(1.0, left)) * self._ANALOG_MAX) + right_u7 = round(max(0.0, min(1.0, right)) * self._ANALOG_MAX) + self.data = ( + (self.data & 0x0000FFFF) # clear bits 16-31 + | (left_u7 << self._LEFT_TRIGGER_SHIFT) + | (right_u7 << self._RIGHT_TRIGGER_SHIFT) ) - # LCM encodes UInt32 as signed int32 — convert to avoid overflow - if unsigned >= 0x80000000: - unsigned -= 0x100000000 - self.data = unsigned def __getattr__(self, name: str) -> bool: if name in Buttons.BITS: From 3788d41a31dd7f9c4850847d8597af0b32b677d0 Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Thu, 26 Feb 2026 11:05:18 -0800 Subject: [PATCH 10/18] fix: comments and errors --- dimos/control/blueprints.py | 7 ------- dimos/control/hardware_interface.py | 5 ----- dimos/control/tasks/teleop_task.py | 2 -- dimos/teleop/quest/quest_extensions.py | 2 +- 4 files changed, 1 insertion(+), 15 deletions(-) diff --git a/dimos/control/blueprints.py b/dimos/control/blueprints.py index 125a379860..98cadc2d20 100644 --- a/dimos/control/blueprints.py +++ b/dimos/control/blueprints.py @@ -534,12 +534,6 @@ address="can0", auto_enable=True, ), - HardwareComponent( - hardware_id=make_gripper_joint("arm"), - hardware_type=HardwareType.GRIPPER, - joints=[make_gripper_joint("arm")], - parent_hardware_id="arm", - ), ], tasks=[ TaskConfig( @@ -550,7 +544,6 @@ model_path=_PIPER_MODEL_PATH, ee_joint_id=6, hand="left", - gripper_joint=make_gripper_joint("arm"), ), ], ).transports( diff --git a/dimos/control/hardware_interface.py b/dimos/control/hardware_interface.py index a3ccbcc5da..75bcbfec39 100644 --- a/dimos/control/hardware_interface.py +++ b/dimos/control/hardware_interface.py @@ -290,11 +290,6 @@ def write_command(self, commands: dict[str, float], _mode: ControlMode) -> bool: class ConnectedGripper(ConnectedHardware): """Runtime wrapper for a gripper attached to a manipulator. - Shares the parent manipulator's adapter but routes read/write - through gripper-specific adapter methods (read_gripper_position / - write_gripper_position). Lifecycle (connect / disconnect) is owned - by the parent ConnectedHardware — disconnect() is a no-op here. - Registered as a separate HardwareComponent with hardware_type=GRIPPER so the tick loop treats it uniformly alongside arm joints. """ diff --git a/dimos/control/tasks/teleop_task.py b/dimos/control/tasks/teleop_task.py index b30e6043d2..028ed649bc 100644 --- a/dimos/control/tasks/teleop_task.py +++ b/dimos/control/tasks/teleop_task.py @@ -154,8 +154,6 @@ def __init__(self, name: str, config: TeleopIKTaskConfig) -> None: self._initial_ee_pose: pinocchio.SE3 | None = None self._prev_primary: bool = False - # Gripper state — only active when config.gripper_joint is set. - # Starts at open position so the gripper doesn't unexpectedly close on engage. self._gripper_target: float = config.gripper_open_pos logger.info( diff --git a/dimos/teleop/quest/quest_extensions.py b/dimos/teleop/quest/quest_extensions.py index ce6fdba38e..ce152639c4 100644 --- a/dimos/teleop/quest/quest_extensions.py +++ b/dimos/teleop/quest/quest_extensions.py @@ -136,7 +136,7 @@ def _publish_button_state( left: QuestControllerState | None, right: QuestControllerState | None, ) -> None: - """Publish Buttons with analog triggers packed into bits 16-31""" + """Publish Buttons with analog triggers packed into bits 16-29.""" buttons = Buttons.from_controllers(left, right) buttons.pack_analog_triggers( left=left.trigger if left is not None else 0.0, From b3a0e9831472f7df1afee0ef076f77f94aa63263 Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Thu, 26 Feb 2026 12:06:27 -0800 Subject: [PATCH 11/18] fix comments + pre-commit errors --- dimos/control/blueprints.py | 1 + dimos/control/coordinator.py | 8 ++++---- dimos/control/hardware_interface.py | 7 ++++--- 3 files changed, 9 insertions(+), 7 deletions(-) diff --git a/dimos/control/blueprints.py b/dimos/control/blueprints.py index 98cadc2d20..c80095e066 100644 --- a/dimos/control/blueprints.py +++ b/dimos/control/blueprints.py @@ -725,6 +725,7 @@ # Teleop IK "coordinator_teleop_dual", "coordinator_teleop_piper", + "coordinator_teleop_xarm6", "coordinator_teleop_xarm7", "coordinator_velocity_xarm6", "coordinator_xarm6", diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index f330f296ea..ba13fbd1af 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -101,7 +101,7 @@ class TaskConfig: hand: str = "" # teleop_ik only: "left" or "right" controller # Teleop IK gripper specific gripper_joint: str | None = None - gripper_open_pos: float = 0.85 + gripper_open_pos: float = 0.0 gripper_closed_pos: float = 0.0 @@ -254,7 +254,7 @@ def _setup_hardware(self, component: HardwareComponent) -> None: raise def _setup_gripper_hardware(self, component: HardwareComponent) -> None: - """Register a gripper by borrowing the parent arm's adapter""" + """Register a gripper by borrowing the parent arm's adapter.""" if not component.parent_hardware_id: raise ValueError( f"Gripper component '{component.hardware_id}' requires parent_hardware_id" @@ -265,8 +265,8 @@ def _setup_gripper_hardware(self, component: HardwareComponent) -> None: if parent is None: raise ValueError( - f"Parent hardware '{component.parent_hardware_id}' not found for gripper '{component.hardware_id}'" - f"Add the parent arm before the gripper." + f"Parent hardware '{component.parent_hardware_id}' not found for gripper " + f"'{component.hardware_id}'. Add the parent arm before the gripper." ) self.add_hardware(parent.adapter, component) diff --git a/dimos/control/hardware_interface.py b/dimos/control/hardware_interface.py index 75bcbfec39..20e2de34ce 100644 --- a/dimos/control/hardware_interface.py +++ b/dimos/control/hardware_interface.py @@ -324,11 +324,12 @@ def write_command(self, commands: dict[str, float], _mode: ControlMode) -> bool: """Write gripper position via adapter.write_gripper_position(). Mode is ignored — gripper is always position-controlled. + Re-sends last commanded position when no new command arrives (hold-last-value). """ joint_name = self._joint_names[0] - if joint_name not in commands: - return True # nothing commanded this tick, hold current - return self._adapter.write_gripper_position(commands[joint_name]) + if joint_name in commands: + self._last_commanded[joint_name] = commands[joint_name] + return self._adapter.write_gripper_position(self._last_commanded[joint_name]) __all__ = [ From 210371b3804394f8ad3ee99a0623adce283a5415 Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Thu, 26 Feb 2026 12:54:38 -0800 Subject: [PATCH 12/18] fix: blueprint + mypy tests --- dimos/control/coordinator.py | 4 ++-- dimos/control/tasks/teleop_task.py | 2 +- dimos/robot/all_blueprints.py | 1 + 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index ba13fbd1af..05a8fbc42f 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -394,11 +394,11 @@ def add_hardware( logger.warning(f"Hardware {component.hardware_id} already registered") return False - if is_gripper: + if is_gripper and isinstance(adapter, ManipulatorAdapter): from dimos.control.hardware_interface import ConnectedGripper connected: ConnectedHardware = ConnectedGripper( - adapter=adapter, # type: ignore[arg-type] + adapter=adapter, component=component, ) elif isinstance(adapter, TwistBaseAdapter): diff --git a/dimos/control/tasks/teleop_task.py b/dimos/control/tasks/teleop_task.py index 028ed649bc..e2ea8b5138 100644 --- a/dimos/control/tasks/teleop_task.py +++ b/dimos/control/tasks/teleop_task.py @@ -79,7 +79,7 @@ class TeleopIKTaskConfig: ee_joint_id: int priority: int = 10 timeout: float = 0.5 - max_joint_delta_deg: float = 20.0 + max_joint_delta_deg: float = 5.0 # ~500°/s at 100Hz hand: str = "" gripper_joint: str | None = None gripper_open_pos: float = 0.0 diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index c9f9e8a1c7..14aa2bbc64 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -34,6 +34,7 @@ "coordinator-piper-xarm": "dimos.control.blueprints:coordinator_piper_xarm", "coordinator-teleop-dual": "dimos.control.blueprints:coordinator_teleop_dual", "coordinator-teleop-piper": "dimos.control.blueprints:coordinator_teleop_piper", + "coordinator-teleop-xarm6": "dimos.control.blueprints:coordinator_teleop_xarm6", "coordinator-teleop-xarm7": "dimos.control.blueprints:coordinator_teleop_xarm7", "coordinator-velocity-xarm6": "dimos.control.blueprints:coordinator_velocity_xarm6", "coordinator-xarm6": "dimos.control.blueprints:coordinator_xarm6", From 7837c7fce9335b559930e686537e19b67af30e2b Mon Sep 17 00:00:00 2001 From: ruthwikdasyam <63036454+ruthwikdasyam@users.noreply.github.com> Date: Thu, 26 Feb 2026 21:14:51 +0000 Subject: [PATCH 13/18] CI code cleanup --- dimos/control/coordinator.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index 05a8fbc42f..79f601c3e5 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -48,6 +48,7 @@ from dimos.hardware.drive_trains.spec import ( TwistBaseAdapter, ) +from dimos.hardware.manipulators.spec import ManipulatorAdapter from dimos.msgs.geometry_msgs import ( PoseStamped, # noqa: TC001 - needed at runtime for In[PoseStamped] Twist, # noqa: TC001 - needed at runtime for In[Twist] @@ -64,7 +65,6 @@ from collections.abc import Callable from pathlib import Path - from dimos.hardware.manipulators.spec import ManipulatorAdapter logger = setup_logger() From 2de1e46db00552cd6950929235ad16657f3ad12c Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Fri, 27 Feb 2026 16:02:11 -0800 Subject: [PATCH 14/18] Fix: no gripper as component, adding with joints --- dimos/control/__init__.py | 4 +- dimos/control/blueprints.py | 11 +-- dimos/control/components.py | 20 +++--- dimos/control/coordinator.py | 44 +++--------- dimos/control/hardware_interface.py | 107 ++++++++++++---------------- dimos/control/tasks/teleop_task.py | 2 +- 6 files changed, 72 insertions(+), 116 deletions(-) diff --git a/dimos/control/__init__.py b/dimos/control/__init__.py index 9831abe0cc..639f0ba38a 100644 --- a/dimos/control/__init__.py +++ b/dimos/control/__init__.py @@ -60,7 +60,7 @@ "HardwareType", "JointName", "JointState", - "make_gripper_joint", + "make_gripper_joints", "make_joints", ], "coordinator": [ @@ -69,7 +69,7 @@ "TaskConfig", "control_coordinator", ], - "hardware_interface": ["ConnectedGripper", "ConnectedHardware"], + "hardware_interface": ["ConnectedHardware"], "task": [ "ControlMode", "ControlTask", diff --git a/dimos/control/blueprints.py b/dimos/control/blueprints.py index c80095e066..0384c69160 100644 --- a/dimos/control/blueprints.py +++ b/dimos/control/blueprints.py @@ -33,7 +33,7 @@ from dimos.control.components import ( HardwareComponent, HardwareType, - make_gripper_joint, + make_gripper_joints, make_joints, make_twist_base_joints, ) @@ -488,12 +488,7 @@ adapter_type="xarm", address="192.168.2.235", auto_enable=True, - ), - HardwareComponent( - hardware_id=make_gripper_joint("arm"), - hardware_type=HardwareType.GRIPPER, - joints=[make_gripper_joint("arm")], - parent_hardware_id="arm", + gripper_joints=make_gripper_joints("arm"), ), ], tasks=[ @@ -505,7 +500,7 @@ model_path=_XARM7_MODEL_PATH, ee_joint_id=7, hand="right", - gripper_joint=make_gripper_joint("arm"), + gripper_joint=make_gripper_joints("arm")[0], gripper_open_pos=0.85, # xArm gripper range gripper_closed_pos=0.0, ), diff --git a/dimos/control/components.py b/dimos/control/components.py index dd2e6a8d98..d7c87cfc74 100644 --- a/dimos/control/components.py +++ b/dimos/control/components.py @@ -25,7 +25,6 @@ class HardwareType(Enum): MANIPULATOR = "manipulator" BASE = "base" - GRIPPER = "gripper" @dataclass(frozen=True) @@ -43,12 +42,12 @@ class HardwareComponent: Attributes: hardware_id: Unique identifier, also used as joint name prefix - hardware_type: Type of hardware (MANIPULATOR, BASE, GRIPPER) + hardware_type: Type of hardware (MANIPULATOR, BASE) 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 - parent_hardware_id: For GRIPPER type only — gripper shares the parent's already-connected adapter. + gripper_joints: Joints that use adapter gripper methods. Auto-appended to joints. """ hardware_id: HardwareId @@ -57,19 +56,22 @@ class HardwareComponent: adapter_type: str = "mock" address: str | None = None auto_enable: bool = True - parent_hardware_id: HardwareId | None = None + gripper_joints: list[JointName] = field(default_factory=list) + def __post_init__(self) -> None: + self.joints.extend(self.gripper_joints) -def make_gripper_joint(hardware_id: HardwareId) -> str: - """Create the gripper joint name for a hardware device. + +def make_gripper_joints(hardware_id: HardwareId) -> list[JointName]: + """Create gripper joint names for a hardware device. Args: hardware_id: The hardware identifier (e.g., "arm") Returns: - Joint name 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]: @@ -126,7 +128,7 @@ def make_twist_base_joints( "JointName", "JointState", "TaskName", - "make_gripper_joint", + "make_gripper_joints", "make_joints", "make_twist_base_joints", ] diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index 79f601c3e5..feb1deaae0 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -48,7 +48,6 @@ from dimos.hardware.drive_trains.spec import ( TwistBaseAdapter, ) -from dimos.hardware.manipulators.spec import ManipulatorAdapter from dimos.msgs.geometry_msgs import ( PoseStamped, # noqa: TC001 - needed at runtime for In[PoseStamped] Twist, # noqa: TC001 - needed at runtime for In[Twist] @@ -65,6 +64,8 @@ from collections.abc import Callable from pathlib import Path + from dimos.hardware.manipulators.spec import ManipulatorAdapter + logger = setup_logger() @@ -231,10 +232,6 @@ def _setup_from_config(self) -> None: def _setup_hardware(self, component: HardwareComponent) -> None: """Connect and add a single hardware adapter.""" - if component.hardware_type == HardwareType.GRIPPER: - self._setup_gripper_hardware(component) - return - adapter: ManipulatorAdapter | TwistBaseAdapter if component.hardware_type == HardwareType.BASE: adapter = self._create_twist_base_adapter(component) @@ -253,31 +250,15 @@ def _setup_hardware(self, component: HardwareComponent) -> None: adapter.disconnect() raise - def _setup_gripper_hardware(self, component: HardwareComponent) -> None: - """Register a gripper by borrowing the parent arm's adapter.""" - if not component.parent_hardware_id: - raise ValueError( - f"Gripper component '{component.hardware_id}' requires parent_hardware_id" - ) - - with self._hardware_lock: - parent = self._hardware.get(component.parent_hardware_id) - - if parent is None: - raise ValueError( - f"Parent hardware '{component.parent_hardware_id}' not found for gripper " - f"'{component.hardware_id}'. Add the parent arm before the gripper." - ) - - self.add_hardware(parent.adapter, component) - def _create_adapter(self, component: HardwareComponent) -> ManipulatorAdapter: """Create a manipulator adapter from component config.""" from dimos.hardware.manipulators.registry import adapter_registry + # Adapter DOF is arm joints only — gripper joints use separate adapter methods. + arm_dof = len(component.joints) - len(component.gripper_joints) return adapter_registry.create( component.adapter_type, - dof=len(component.joints), + dof=arm_dof, address=component.address, ) @@ -378,11 +359,9 @@ def add_hardware( component: HardwareComponent, ) -> bool: """Register a hardware adapter with the coordinator.""" - is_gripper = component.hardware_type == HardwareType.GRIPPER is_base = component.hardware_type == HardwareType.BASE - # Grippers reuse their parent arm's ManipulatorAdapter — skip the base/adapter check - if not is_gripper and (is_base != isinstance(adapter, TwistBaseAdapter)): + if is_base != isinstance(adapter, TwistBaseAdapter): raise TypeError( f"Hardware type / adapter mismatch for '{component.hardware_id}': " f"hardware_type={component.hardware_type.value} but got " @@ -394,15 +373,8 @@ def add_hardware( logger.warning(f"Hardware {component.hardware_id} already registered") return False - if is_gripper and isinstance(adapter, ManipulatorAdapter): - from dimos.control.hardware_interface import ConnectedGripper - - connected: ConnectedHardware = ConnectedGripper( - adapter=adapter, - component=component, - ) - elif isinstance(adapter, TwistBaseAdapter): - connected = ConnectedTwistBase( + if isinstance(adapter, TwistBaseAdapter): + connected: ConnectedHardware = ConnectedTwistBase( adapter=adapter, component=component, ) diff --git a/dimos/control/hardware_interface.py b/dimos/control/hardware_interface.py index 20e2de34ce..6f93d73d38 100644 --- a/dimos/control/hardware_interface.py +++ b/dimos/control/hardware_interface.py @@ -67,6 +67,13 @@ def __init__( self._component = component self._joint_names = component.joints + # Gripper joints use adapter.read/write_gripper_position() instead of + # the array-based read/write_joint_positions(). + self._gripper_joints: frozenset[str] = frozenset(component.gripper_joints) + self._arm_joint_names: list[JointName] = [ + j for j in component.joints if j not in self._gripper_joints + ] + # Track last commanded values for hold-last behavior self._last_commanded: dict[str, float] = {} self._initialized = False @@ -114,15 +121,27 @@ def read_state(self) -> dict[JointName, JointState]: velocities = self._adapter.read_joint_velocities() efforts = self._adapter.read_joint_efforts() - return { + result: dict[JointName, JointState] = { name: JointState( position=positions[i], velocity=velocities[i], effort=efforts[i], ) - for i, name in enumerate(self._joint_names) + for i, name in enumerate(self._arm_joint_names) } + # Append gripper joint(s) via adapter gripper method + if self._gripper_joints: + gripper_pos = self._adapter.read_gripper_position() + for gj in self._gripper_joints: + result[gj] = JointState( + position=gripper_pos if gripper_pos is not None else 0.0, + velocity=0.0, + effort=0.0, + ) + + return result + def write_command(self, commands: dict[str, float], mode: ControlMode) -> bool: """Write commands - allows partial joint sets, holds last for missing. @@ -153,8 +172,8 @@ def write_command(self, commands: dict[str, float], mode: ControlMode) -> bool: ) self._warned_unknown_joints.add(joint_name) - # Build ordered list for adapter - ordered = self._build_ordered_command() + # Build ordered list for arm joints only + arm_ordered = [self._last_commanded[name] for name in self._arm_joint_names] # Switch control mode if needed if mode != self._current_mode: @@ -163,25 +182,43 @@ def write_command(self, commands: dict[str, float], mode: ControlMode) -> bool: return False self._current_mode = mode - # Send to adapter + # Send arm joints to adapter + arm_ok: bool match mode: case ControlMode.POSITION | ControlMode.SERVO_POSITION: - return self._adapter.write_joint_positions(ordered) + arm_ok = self._adapter.write_joint_positions(arm_ordered) case ControlMode.VELOCITY: - return self._adapter.write_joint_velocities(ordered) + arm_ok = self._adapter.write_joint_velocities(arm_ordered) case ControlMode.TORQUE: logger.warning(f"Hardware {self.hardware_id} does not support torque mode") - return False + arm_ok = False case _: - return False + arm_ok = False + + # Send gripper joints via adapter gripper method + gripper_ok = True + for gj in self._gripper_joints: + if gj in self._last_commanded: + gripper_ok = ( + self._adapter.write_gripper_position(self._last_commanded[gj]) and gripper_ok + ) + + return arm_ok and gripper_ok def _initialize_last_commanded(self) -> None: """Initialize last_commanded with current hardware positions.""" for _ in range(10): try: current = self._adapter.read_joint_positions() - for i, name in enumerate(self._joint_names): + for i, name in enumerate(self._arm_joint_names): self._last_commanded[name] = current[i] + + # Initialize gripper joint(s) from adapter + if self._gripper_joints: + gripper_pos = self._adapter.read_gripper_position() + for gj in self._gripper_joints: + self._last_commanded[gj] = gripper_pos if gripper_pos is not None else 0.0 + self._initialized = True return except Exception: @@ -191,10 +228,6 @@ def _initialize_last_commanded(self) -> None: f"Hardware {self.hardware_id} failed to read initial positions after retries" ) - def _build_ordered_command(self) -> list[float]: - """Build ordered command list from last_commanded dict.""" - return [self._last_commanded[name] for name in self._joint_names] - class ConnectedTwistBase(ConnectedHardware): """Runtime wrapper for a twist base connected to the coordinator. @@ -287,53 +320,7 @@ def write_command(self, commands: dict[str, float], _mode: ControlMode) -> bool: return self._twist_adapter.write_velocities(ordered) -class ConnectedGripper(ConnectedHardware): - """Runtime wrapper for a gripper attached to a manipulator. - - Registered as a separate HardwareComponent with hardware_type=GRIPPER - so the tick loop treats it uniformly alongside arm joints. - """ - - def __init__( - self, - adapter: ManipulatorAdapter, - component: HardwareComponent, - ) -> None: - super().__init__(adapter, component) - self._last_commanded = {name: 0.0 for name in self._joint_names} - self._initialized = True - - def disconnect(self) -> None: - """No-op: lifecycle is owned by the parent ConnectedHardware.""" - - def read_state(self) -> dict[JointName, JointState]: - """Read gripper position via adapter.read_gripper_position().""" - from dimos.control.components import JointState - - pos = self._adapter.read_gripper_position() - joint_name = self._joint_names[0] - return { - joint_name: JointState( - position=pos if pos is not None else 0.0, - velocity=0.0, - effort=0.0, - ) - } - - def write_command(self, commands: dict[str, float], _mode: ControlMode) -> bool: - """Write gripper position via adapter.write_gripper_position(). - - Mode is ignored — gripper is always position-controlled. - Re-sends last commanded position when no new command arrives (hold-last-value). - """ - joint_name = self._joint_names[0] - if joint_name in commands: - self._last_commanded[joint_name] = commands[joint_name] - return self._adapter.write_gripper_position(self._last_commanded[joint_name]) - - __all__ = [ - "ConnectedGripper", "ConnectedHardware", "ConnectedTwistBase", ] diff --git a/dimos/control/tasks/teleop_task.py b/dimos/control/tasks/teleop_task.py index e2ea8b5138..0ded183921 100644 --- a/dimos/control/tasks/teleop_task.py +++ b/dimos/control/tasks/teleop_task.py @@ -259,7 +259,7 @@ def compute(self, state: CoordinatorState) -> JointCommandOutput | None: joint_names = list(self._joint_names_list) positions = q_solution.flatten().tolist() - # Append gripper joint if configured — routed to ConnectedGripper by tick loop + # Append gripper joint if configured — routed to ConnectedHardware by tick loop if self._config.gripper_joint: with self._lock: gripper_pos = self._gripper_target From 191ec86dfa06adb7cb87f95375bc8c5bc61f5c5b Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Fri, 27 Feb 2026 16:30:18 -0800 Subject: [PATCH 15/18] feat: add literal for hand str --- dimos/control/coordinator.py | 8 +++---- dimos/control/tasks/teleop_task.py | 35 ++++++++---------------------- 2 files changed, 12 insertions(+), 31 deletions(-) diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index feb1deaae0..c8bfd620e4 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -30,7 +30,7 @@ from dataclasses import dataclass, field import threading import time -from typing import TYPE_CHECKING, Any +from typing import TYPE_CHECKING, Any, Literal from dimos.control.components import ( TWIST_SUFFIX_MAP, @@ -99,7 +99,7 @@ class TaskConfig: # Cartesian IK / Teleop IK specific model_path: str | Path | None = None ee_joint_id: int = 6 - hand: str = "" # teleop_ik only: "left" or "right" controller + hand: Literal["left", "right"] | None = None # teleop_ik only # Teleop IK gripper specific gripper_joint: str | None = None gripper_open_pos: float = 0.0 @@ -254,11 +254,9 @@ def _create_adapter(self, component: HardwareComponent) -> ManipulatorAdapter: """Create a manipulator adapter from component config.""" from dimos.hardware.manipulators.registry import adapter_registry - # Adapter DOF is arm joints only — gripper joints use separate adapter methods. - arm_dof = len(component.joints) - len(component.gripper_joints) return adapter_registry.create( component.adapter_type, - dof=arm_dof, + dof=len(component.joints), address=component.address, ) diff --git a/dimos/control/tasks/teleop_task.py b/dimos/control/tasks/teleop_task.py index 0ded183921..184cc686e2 100644 --- a/dimos/control/tasks/teleop_task.py +++ b/dimos/control/tasks/teleop_task.py @@ -27,7 +27,7 @@ from dataclasses import dataclass import threading -from typing import TYPE_CHECKING, Any +from typing import TYPE_CHECKING, Any, Literal import numpy as np import pinocchio # type: ignore[import-untyped] @@ -80,7 +80,7 @@ class TeleopIKTaskConfig: priority: int = 10 timeout: float = 0.5 max_joint_delta_deg: float = 5.0 # ~500°/s at 100Hz - hand: str = "" + hand: Literal["left", "right"] | None = None gripper_joint: str | None = None gripper_open_pos: float = 0.0 gripper_closed_pos: float = 0.0 @@ -127,6 +127,8 @@ def __init__(self, name: str, config: TeleopIKTaskConfig) -> None: raise ValueError(f"TeleopIKTask '{name}' requires at least one joint") if not config.model_path: raise ValueError(f"TeleopIKTask '{name}' requires model_path for IK solver") + if config.hand not in ("left", "right"): + raise ValueError(f"TeleopIKTask '{name}' requires hand='left' or 'right'") self._name = name self._config = config @@ -297,43 +299,24 @@ def on_preempted(self, by_task: str, joints: frozenset[str]) -> None: # ========================================================================= def on_buttons(self, msg: Buttons) -> bool: - """Press-and-hold engage: hold primary button to track, release to stop. - - Checks only the button matching self._config.hand (left_primary or right_primary). - If hand is not set, listens to both. - """ - hand = self._config.hand - if hand == "left": - primary = msg.left_primary - elif hand == "right": - primary = msg.right_primary - else: - primary = msg.left_primary or msg.right_primary + """Press-and-hold engage: hold primary button to track, release to stop.""" + is_left = self._config.hand == "left" + primary = msg.left_primary if is_left else msg.right_primary if primary and not self._prev_primary: - # Rising edge: reset initial pose so compute() recaptures logger.info(f"TeleopIKTask {self._name}: engage") with self._lock: self._initial_ee_pose = None elif not primary and self._prev_primary: - # Falling edge: stop tracking logger.info(f"TeleopIKTask {self._name}: disengage") with self._lock: self._target_pose = None self._initial_ee_pose = None self._prev_primary = primary - # Gripper: decode analog trigger from bits 16-31 of Buttons and update target if self._config.gripper_joint: - if hand == "left": - self.on_gripper_trigger(msg.left_trigger_analog, 0.0) - elif hand == "right": - self.on_gripper_trigger(msg.right_trigger_analog, 0.0) - else: - logger.warning( - f"TeleopIKTask {self._name}: gripper_joint is set but hand is not " - f"'left' or 'right' — cannot determine which trigger to use" - ) + trigger = msg.left_trigger_analog if is_left else msg.right_trigger_analog + self.on_gripper_trigger(trigger, 0.0) return True From 4f7bb440d2b2a51817557f3661e4c7ee1cd8f16b Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Fri, 27 Feb 2026 16:32:01 -0800 Subject: [PATCH 16/18] fix: arm and gripper joint params --- dimos/control/components.py | 8 +++++--- dimos/control/hardware_interface.py | 15 +++++++-------- 2 files changed, 12 insertions(+), 11 deletions(-) diff --git a/dimos/control/components.py b/dimos/control/components.py index d7c87cfc74..a32b395b83 100644 --- a/dimos/control/components.py +++ b/dimos/control/components.py @@ -47,7 +47,7 @@ class HardwareComponent: adapter_type: Adapter type ("mock", "xarm", "piper") address: Connection address - IP for TCP, port for CAN auto_enable: Whether to auto-enable servos - gripper_joints: Joints that use adapter gripper methods. Auto-appended to joints. + gripper_joints: Joints that use adapter gripper methods (separate from joints). """ hardware_id: HardwareId @@ -58,8 +58,10 @@ class HardwareComponent: auto_enable: bool = True gripper_joints: list[JointName] = field(default_factory=list) - def __post_init__(self) -> None: - self.joints.extend(self.gripper_joints) + @property + def all_joints(self) -> list[JointName]: + """All joints: arm joints + gripper joints.""" + return self.joints + self.gripper_joints def make_gripper_joints(hardware_id: HardwareId) -> list[JointName]: diff --git a/dimos/control/hardware_interface.py b/dimos/control/hardware_interface.py index 6f93d73d38..b4f84a2507 100644 --- a/dimos/control/hardware_interface.py +++ b/dimos/control/hardware_interface.py @@ -65,14 +65,9 @@ def __init__( self._adapter = adapter self._component = component - self._joint_names = component.joints - - # Gripper joints use adapter.read/write_gripper_position() instead of - # the array-based read/write_joint_positions(). - self._gripper_joints: frozenset[str] = frozenset(component.gripper_joints) - self._arm_joint_names: list[JointName] = [ - j for j in component.joints if j not in self._gripper_joints - ] + self._arm_joint_names: list[JointName] = list(component.joints) + self._gripper_joints: list[JointName] = list(component.gripper_joints) + self._joint_names: list[JointName] = component.all_joints # Track last commanded values for hold-last behavior self._last_commanded: dict[str, float] = {} @@ -228,6 +223,10 @@ def _initialize_last_commanded(self) -> None: f"Hardware {self.hardware_id} failed to read initial positions after retries" ) + def _build_ordered_command(self) -> list[float]: + """Build ordered command list from last_commanded dict.""" + return [self._last_commanded[name] for name in self._joint_names] + class ConnectedTwistBase(ConnectedHardware): """Runtime wrapper for a twist base connected to the coordinator. From fb45d3bc14ed11fb3f3540bfcae085a5f6f1b507 Mon Sep 17 00:00:00 2001 From: ruthwikdasyam <63036454+ruthwikdasyam@users.noreply.github.com> Date: Sat, 28 Feb 2026 08:18:31 +0000 Subject: [PATCH 17/18] CI code cleanup --- dimos/control/coordinator.py | 1 - 1 file changed, 1 deletion(-) diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index a2d1c32c4f..21d4c9d06c 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -65,7 +65,6 @@ from collections.abc import Callable - logger = setup_logger() From 82cabb5cc629fb5ac9953451bc621de592f2cbf0 Mon Sep 17 00:00:00 2001 From: Ruthwik Date: Sat, 28 Feb 2026 10:43:58 -0800 Subject: [PATCH 18/18] Misc: docstrings --- dimos/control/tasks/teleop_task.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/dimos/control/tasks/teleop_task.py b/dimos/control/tasks/teleop_task.py index 184cc686e2..ce63dc4006 100644 --- a/dimos/control/tasks/teleop_task.py +++ b/dimos/control/tasks/teleop_task.py @@ -70,8 +70,8 @@ class TeleopIKTaskConfig: 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_open_pos: Gripper position (meters) at trigger value 0.0 (no press). - gripper_closed_pos: Gripper position (meters) at trigger value 1.0 (full press). + 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). """ joint_names: list[str] @@ -107,6 +107,7 @@ class TeleopIKTask(BaseControlTask): ... ee_joint_id=6, ... priority=10, ... timeout=0.5, + ... hand="right", ... ), ... ) >>> coordinator.add_task(task) @@ -316,7 +317,7 @@ def on_buttons(self, msg: Buttons) -> bool: if self._config.gripper_joint: trigger = msg.left_trigger_analog if is_left else msg.right_trigger_analog - self.on_gripper_trigger(trigger, 0.0) + self.on_gripper_trigger(trigger) return True @@ -329,7 +330,7 @@ def on_cartesian_command(self, pose: Pose | PoseStamped, t_now: float) -> bool: return True - def on_gripper_trigger(self, value: float, _t_now: float) -> bool: + def on_gripper_trigger(self, value: float, _t_now: float = 0.0) -> bool: """Map analog trigger (0-1) to gripper position""" if not self._config.gripper_joint: return False