Skip to content

Commit 8dac89a

Browse files
committed
fix(bt): integrate BTManipulationModule, fix pickle/detection/Docker issues
- Add BTManipulationModule: slim ManipulationModule subclass for BT workflow with perception integration, GraspGen Docker, and MeshCat visualization - Fix Pydantic pickle errors: change Iterable/Sequence to list in config - Fix OSR __init__ to accept **kwargs for GlobalConfig passthrough - Fix PointCloud2 pickle: strip cached Open3D bounding boxes in __getstate__ - Fix detect skill: accept prompts as keyword list instead of varargs - Fix xArm adapter: add clean_error/motion_enable on connect, error logging - Add langchain-core to Docker extras for module.py import - Update all BT actions/conditions to use BTManipulationModule RPC names
1 parent 312df02 commit 8dac89a

12 files changed

Lines changed: 447 additions & 57 deletions

File tree

dimos/hardware/manipulators/xarm/adapter.py

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,11 +20,14 @@
2020

2121
from __future__ import annotations
2222

23+
import logging
2324
import math
2425
from typing import TYPE_CHECKING
2526

2627
from xarm.wrapper import XArmAPI
2728

29+
logger = logging.getLogger(__name__)
30+
2831
if TYPE_CHECKING:
2932
from dimos.hardware.manipulators.registry import AdapterRegistry
3033

@@ -74,6 +77,10 @@ def connect(self) -> bool:
7477
print(f"ERROR: XArm at {self._ip} not reachable (connected=False)")
7578
return False
7679

80+
# Clear any stale errors and enable motion before setting mode
81+
self._arm.clean_error()
82+
self._arm.motion_enable(enable=True)
83+
7784
# Initialize to servo mode for high-frequency control
7885
self._arm.set_mode(_XARM_MODE_SERVO_CARTESIAN) # Mode 1 = servo mode
7986
self._arm.set_state(0)
@@ -221,6 +228,12 @@ def write_joint_positions(
221228
# Use set_servo_angle_j for high-frequency servo control (100Hz+)
222229
# This only executes the last instruction, suitable for real-time control
223230
code: int = self._arm.set_servo_angle_j(angles, speed=100, mvacc=500)
231+
if code != 0:
232+
logger.error(
233+
f"[XArm] set_servo_angle_j failed: code={code}, "
234+
f"error_code={self._arm.error_code}, warn_code={self._arm.warn_code}, "
235+
f"state={self._arm.state}, mode={self._arm.mode}"
236+
)
224237
return code == 0
225238

226239
def write_joint_velocities(self, velocities: list[float]) -> bool:

dimos/manipulation/blueprints.py

Lines changed: 46 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
from dimos.core.blueprints import autoconnect
3737
from dimos.core.transport import LCMTransport
3838
from dimos.hardware.sensors.camera.realsense.camera import realsense_camera
39+
from dimos.manipulation.bt.bt_manipulation_module import bt_manipulation_module
3940
from dimos.manipulation.bt.pick_place_module import PickPlaceModule
4041
from dimos.manipulation.manipulation_module import manipulation_module
4142
from dimos.manipulation.pick_and_place_module import pick_and_place_module
@@ -501,9 +502,52 @@ def _make_piper_config(
501502
For robot_name parameters, always omit or pass None (single-arm setup).
502503
"""
503504

504-
# BT Agent mode, DL grasps via GraspGen Docker (requires GPU + Docker build)
505+
# BT Agent mode — uses BTManipulationModule (no skills) + BT PickPlaceModule (skills only)
506+
# DL grasps via GraspGen Docker (requires GPU + Docker build)
507+
_bt_xarm_perception = (
508+
autoconnect(
509+
bt_manipulation_module(
510+
robots=[
511+
_make_xarm7_config(
512+
"arm",
513+
pitch=math.radians(45),
514+
joint_prefix="arm_",
515+
coordinator_task="traj_arm",
516+
add_gripper=True,
517+
gripper_hardware_id="arm",
518+
tf_extra_links=["link7"],
519+
),
520+
],
521+
planning_timeout=10.0,
522+
enable_viz=True,
523+
graspgen_topk_num_grasps=400,
524+
graspgen_save_visualization_data=True,
525+
),
526+
realsense_camera(
527+
base_frame_id="link7",
528+
base_transform=_XARM_PERCEPTION_CAMERA_TRANSFORM,
529+
),
530+
object_scene_registration_module(target_frame="world", prompt_mode=YoloePromptMode.PROMPT),
531+
foxglove_bridge(
532+
shm_channels=[
533+
"/image#sensor_msgs.Image",
534+
"/overlay#foxglove_msgs.ImageAnnotations",
535+
"/pointcloud#sensor_msgs.PointCloud2",
536+
"/lidar#sensor_msgs.PointCloud2",
537+
"/map#sensor_msgs.PointCloud2",
538+
],
539+
),
540+
)
541+
.transports(
542+
{
543+
("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState),
544+
}
545+
)
546+
.global_config(viewer="foxglove")
547+
)
548+
505549
bt_pick_place_agent = autoconnect(
506-
xarm_perception,
550+
_bt_xarm_perception,
507551
PickPlaceModule.blueprint(),
508552
Agent.blueprint(system_prompt=_BT_AGENT_SYSTEM_PROMPT),
509553
)

dimos/manipulation/bt/__init__.py

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,10 +14,16 @@
1414

1515
"""Behavior Tree based pick-and-place orchestration.
1616
17-
Provides a robust, BT-driven PickPlaceModule that wraps PickAndPlaceModule RPCs
17+
Provides a robust, BT-driven PickPlaceModule that wraps BTManipulationModule RPCs
1818
with retry, recovery, grasp verification, and interruptible execution.
1919
"""
2020

21+
from dimos.manipulation.bt.bt_manipulation_module import BTManipulationModule, BTManipulationModuleConfig
2122
from dimos.manipulation.bt.pick_place_module import PickPlaceModule, PickPlaceModuleConfig
2223

23-
__all__ = ["PickPlaceModule", "PickPlaceModuleConfig"]
24+
__all__ = [
25+
"BTManipulationModule",
26+
"BTManipulationModuleConfig",
27+
"PickPlaceModule",
28+
"PickPlaceModuleConfig",
29+
]

dimos/manipulation/bt/actions.py

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414

1515
"""BT action leaf nodes for pick-and-place orchestration.
1616
17-
Each action wraps one or more PickAndPlaceModule / OSR / GraspGen RPC calls,
17+
Each action wraps one or more BTManipulationModule / OSR / GraspGen RPC calls,
1818
following the py_trees lifecycle: initialise() → update() → terminate().
1919
2020
Long-running operations (trajectory execution, gripper settle) return RUNNING
@@ -81,11 +81,11 @@ def update(self) -> Status:
8181
time.sleep(self.module.config.prompt_settle_time)
8282

8383
self.module.get_rpc_calls(
84-
"PickAndPlaceModule.refresh_obstacles"
84+
"BTManipulationModule.refresh_obstacles"
8585
)(self.min_duration)
8686

8787
detections = self.module.get_rpc_calls(
88-
"PickAndPlaceModule.list_cached_detections"
88+
"BTManipulationModule.list_cached_detections"
8989
)() or []
9090

9191
self.bb.detections = detections
@@ -214,7 +214,7 @@ def initialise(self) -> None:
214214
def _run() -> None:
215215
try:
216216
self._result = self.module.get_rpc_calls(
217-
"PickAndPlaceModule.generate_grasps"
217+
"BTManipulationModule.generate_grasps"
218218
)(obj_pc, scene_pc, rpc_timeout=self.rpc_timeout)
219219
except Exception as e:
220220
self._error = e
@@ -295,7 +295,7 @@ def update(self) -> Status:
295295
if not candidates:
296296
return Status.SUCCESS
297297
try:
298-
self.module.get_rpc_calls("PickAndPlaceModule.visualize_grasps")(candidates)
298+
self.module.get_rpc_calls("BTManipulationModule.visualize_grasps")(candidates)
299299
except Exception as e:
300300
logger.warning(f"[VisualizeGrasps] Visualization failed (non-fatal): {e}")
301301
return Status.SUCCESS
@@ -441,8 +441,8 @@ def update(self) -> Status:
441441
f"[PlanToPose] Planning to {self.pose_key} "
442442
f"({pose.position.x:.3f}, {pose.position.y:.3f}, {pose.position.z:.3f})"
443443
)
444-
self.module.get_rpc_calls("PickAndPlaceModule.reset")()
445-
result = self.module.get_rpc_calls("PickAndPlaceModule.plan_to_pose")(pose)
444+
self.module.get_rpc_calls("BTManipulationModule.reset")()
445+
result = self.module.get_rpc_calls("BTManipulationModule.plan_to_pose")(pose)
446446
if result:
447447
return Status.SUCCESS
448448
self.bb.error_message = f"Error: Planning to {self.pose_key} failed"
@@ -466,8 +466,8 @@ def update(self) -> Status:
466466
if isinstance(joints, list):
467467
joints = JointState(position=joints)
468468
logger.info(f"[PlanToJoints] Planning to {self.joints_key}")
469-
self.module.get_rpc_calls("PickAndPlaceModule.reset")()
470-
result = self.module.get_rpc_calls("PickAndPlaceModule.plan_to_joints")(joints)
469+
self.module.get_rpc_calls("BTManipulationModule.reset")()
470+
result = self.module.get_rpc_calls("BTManipulationModule.plan_to_joints")(joints)
471471
if result:
472472
return Status.SUCCESS
473473
self.bb.error_message = f"Error: Joint planning to {self.joints_key} failed"
@@ -495,7 +495,7 @@ def __init__(
495495
def initialise(self) -> None:
496496
self._seen_executing = False
497497
try:
498-
result = self.module.get_rpc_calls("PickAndPlaceModule.execute")()
498+
result = self.module.get_rpc_calls("BTManipulationModule.execute")()
499499
self._execute_ok = bool(result)
500500
except Exception as e:
501501
logger.error(f"[ExecuteTrajectory] Execute call failed: {e}")
@@ -508,7 +508,7 @@ def update(self) -> Status:
508508
return Status.FAILURE
509509

510510
try:
511-
status = self.module.get_rpc_calls("PickAndPlaceModule.get_trajectory_status")()
511+
status = self.module.get_rpc_calls("BTManipulationModule.get_trajectory_status")()
512512
except Exception as e:
513513
logger.warning(f"[ExecuteTrajectory] Status poll failed: {e}")
514514
status = None
@@ -541,7 +541,7 @@ def update(self) -> Status:
541541
def terminate(self, new_status: Status) -> None:
542542
if new_status == Status.INVALID:
543543
try:
544-
self.module.get_rpc_calls("PickAndPlaceModule.cancel")()
544+
self.module.get_rpc_calls("BTManipulationModule.cancel")()
545545
logger.info("[ExecuteTrajectory] Cancelled trajectory on interrupt")
546546
except Exception as e:
547547
logger.warning(f"[ExecuteTrajectory] Cancel on interrupt failed (best-effort): {e}")
@@ -566,7 +566,7 @@ def __init__(
566566

567567
def initialise(self) -> None:
568568
try:
569-
self.module.get_rpc_calls("PickAndPlaceModule.set_gripper")(self.position)
569+
self.module.get_rpc_calls("BTManipulationModule.set_gripper")(self.position)
570570
self._command_sent = True
571571
except Exception as e:
572572
logger.error(f"[SetGripper] Command failed: {e}")
@@ -641,11 +641,11 @@ def update(self) -> Status:
641641
# --- Robot state actions ---
642642

643643
class ResetRobot(ManipulationAction):
644-
"""Call PickAndPlaceModule.reset() to clear fault/abort state."""
644+
"""Call BTManipulationModule.reset() to clear fault/abort state."""
645645

646646
def update(self) -> Status:
647647
try:
648-
result = self.module.get_rpc_calls("PickAndPlaceModule.reset")()
648+
result = self.module.get_rpc_calls("BTManipulationModule.reset")()
649649
if result:
650650
logger.info("[ResetRobot] Reset succeeded")
651651
return Status.SUCCESS
@@ -675,7 +675,7 @@ def initialise(self) -> None:
675675
def update(self) -> Status:
676676
if not self._cancel_sent:
677677
try:
678-
self.module.get_rpc_calls("PickAndPlaceModule.cancel")()
678+
self.module.get_rpc_calls("BTManipulationModule.cancel")()
679679
logger.info("[CancelMotion] Cancel sent, waiting for settle")
680680
except Exception as e:
681681
logger.warning(f"[CancelMotion] Cancel failed (best-effort): {e}")
@@ -734,7 +734,7 @@ def __init__(self, name: str, module: PickPlaceModule) -> None:
734734

735735
def update(self) -> Status:
736736
try:
737-
pos = float(self.module.get_rpc_calls("PickAndPlaceModule.get_gripper")())
737+
pos = float(self.module.get_rpc_calls("BTManipulationModule.get_gripper")())
738738
threshold = self.module.config.gripper_grasp_threshold
739739
open_pos = self.module.config.gripper_open_position
740740
# Upper bound at 90% of open prevents false positive when gripper is wide open
@@ -778,7 +778,7 @@ def update(self) -> Status:
778778
lift_h = self._lift_height if self._lift_height is not None else self.module.config.lift_height
779779

780780
try:
781-
base_pose = self.module.get_rpc_calls("PickAndPlaceModule.get_ee_pose")()
781+
base_pose = self.module.get_rpc_calls("BTManipulationModule.get_ee_pose")()
782782
except Exception as e:
783783
logger.warning(f"[ComputeLiftPose] get_ee_pose failed, falling back to current_grasp: {e}")
784784
base_pose = None
@@ -811,7 +811,7 @@ def update(self) -> Status:
811811
height = self._retreat_height if self._retreat_height is not None else self.module.config.lift_height
812812

813813
try:
814-
base_pose = self.module.get_rpc_calls("PickAndPlaceModule.get_ee_pose")()
814+
base_pose = self.module.get_rpc_calls("BTManipulationModule.get_ee_pose")()
815815
except Exception as e:
816816
logger.warning(f"[ComputeLocalRetreatPose] get_ee_pose failed: {e}")
817817
base_pose = None

0 commit comments

Comments
 (0)