Skip to content
Open
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
11 changes: 9 additions & 2 deletions dimos/core/blueprints.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,9 +63,16 @@ def create(
streams: list[StreamRef] = []
module_refs: list[ModuleRef] = []

# Use get_type_hints() to properly resolve string annotations.
# Resolve annotations using namespaces from the full MRO chain so that
# In/Out behind TYPE_CHECKING + `from __future__ import annotations` work.
# Iterate reversed MRO so the most specific class's namespace wins when
# parent modules shadow names (e.g. spec.perception.Image vs sensor_msgs.Image).
globalns: dict[str, Any] = {}
for c in reversed(module.__mro__):
if c.__module__ in sys.modules:
globalns.update(sys.modules[c.__module__].__dict__)
Comment on lines +66 to +73
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This looks quite hack-y. What is the issue? I thought I fixed from __future__ import annotations. Can you show an example where it fails?

Copy link
Contributor Author

@mustafab0 mustafab0 Feb 25, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

PR #1309 from Feb 20 added from future import annotations + TYPE_CHECKING guard for Out to the RealSenseCamera — to lazy-load pyrealsense2. That broke _BlueprintAtom.create because it couldn't resolve the camera's string annotations.

The fix I just applied makes _BlueprintAtom.create use MRO-based namespace resolution (with reversed order so the defining class wins).

The object scene registration module does not capture the camera image streams. Above quote is from Claude, after workaround was implemented.

It agree with it being hacky >.<

try:
all_annotations = get_type_hints(module)
all_annotations = get_type_hints(module, globalns=globalns)
except Exception:
# Fallback to raw annotations if get_type_hints fails.
all_annotations = {}
Expand Down
8 changes: 8 additions & 0 deletions dimos/manipulation/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,18 @@
ManipulationState,
manipulation_module,
)
from dimos.manipulation.pick_and_place_module import (
PickAndPlaceModule,
PickAndPlaceModuleConfig,
pick_and_place_module,
)

__all__ = [
"ManipulationModule",
"ManipulationModuleConfig",
"ManipulationState",
"PickAndPlaceModule",
"PickAndPlaceModuleConfig",
"manipulation_module",
"pick_and_place_module",
]
57 changes: 52 additions & 5 deletions dimos/manipulation/manipulation_blueprints.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
from dimos.core.transport import LCMTransport
from dimos.hardware.sensors.camera.realsense import realsense_camera
from dimos.manipulation.manipulation_module import manipulation_module
from dimos.manipulation.pick_and_place_module import pick_and_place_module
from dimos.manipulation.planning.spec import RobotModelConfig
from dimos.msgs.geometry_msgs import PoseStamped, Quaternion, Transform, Vector3
from dimos.msgs.sensor_msgs import JointState
Expand Down Expand Up @@ -328,6 +329,43 @@ def _make_piper_config(
)


# XArm7 planner + LLM agent for testing base ManipulationModule skills
# No perception — uses the base module's planning + gripper skills only.
# Usage: dimos run coordinator-mock, then dimos run xarm7-planner-coordinator-agent
_BASE_MANIPULATION_AGENT_SYSTEM_PROMPT = """\
You are a robotic manipulation assistant controlling an xArm7 robot arm.

Available skills:
- get_robot_state: Get current joint positions, end-effector pose, and gripper state.
- move_to_pose: Move end-effector to ABSOLUTE x, y, z (meters) with optional roll, pitch, yaw (radians).
- move_to_joints: Move to a joint configuration (comma-separated radians).
- open_gripper / close_gripper / set_gripper: Control the gripper.
- go_home: Move to the home/observe position.
- go_init: Return to the startup position.
- reset: Clear a FAULT state and return to IDLE. Use this when a motion fails.

COORDINATE SYSTEM (world frame, meters):
- X axis = forward (away from the robot base)
- Y axis = left
- Z axis = up
- Z=0 is the robot base level; typical working height is Z = 0.2-0.5

CRITICAL WORKFLOW for relative movement requests (e.g. "move 20cm forward"):
1. Call get_robot_state to get the current EE pose.
2. Add the requested offset to the CURRENT position. Example: if EE is at \
(0.3, 0.0, 0.4) and user says "move 20cm forward", target is (0.5, 0.0, 0.4).
3. Call move_to_pose with the computed ABSOLUTE target.
NEVER pass only the offset as coordinates — that would send the robot to near-origin.

ERROR RECOVERY: If a motion fails or the state becomes FAULT, call reset before retrying.
"""

xarm7_planner_coordinator_agent = autoconnect(
xarm7_planner_coordinator,
Agent.blueprint(system_prompt=_BASE_MANIPULATION_AGENT_SYSTEM_PROMPT),
)


# XArm7 with eye-in-hand RealSense camera for perception-based manipulation
# TF chain: world → link7 (ManipulationModule) → camera_link (RealSense)
# Usage: dimos run coordinator-mock, then dimos run xarm-perception
Expand All @@ -338,7 +376,7 @@ def _make_piper_config(

xarm_perception = (
autoconnect(
manipulation_module(
pick_and_place_module(
robots=[
_make_xarm7_config(
"arm",
Expand Down Expand Up @@ -375,22 +413,30 @@ def _make_piper_config(
_MANIPULATION_AGENT_SYSTEM_PROMPT = """\
You are a robotic manipulation assistant controlling an xArm7 robot arm.

Use ONLY these ManipulationModule skills for manipulation tasks:
Available skills:
- get_robot_state: Get current joint positions, end-effector pose, and gripper state.
- scan_objects: Scan scene and list detected objects with 3D positions. Always call this first.
- pick: Pick up an object by name. Requires scan_objects first.
- place: Place a held object at x, y, z position.
- place_back: Place a held object back at its original pick position.
- pick_and_place: Pick an object and place it at a target location.
- move_to_pose: Move end-effector to x, y, z with optional roll, pitch, yaw.
- move_to_pose: Move end-effector to ABSOLUTE x, y, z (meters) with optional roll, pitch, yaw (radians).
- move_to_joints: Move to a joint configuration (comma-separated radians).
- open_gripper / close_gripper / set_gripper: Control the gripper.
- go_home: Move to the home/observe position.
- go_init: Return to the startup position.
- get_scene_info: Get full robot state, detected objects, and scene info.
- reset: Clear a FAULT state and return to IDLE.
- clear_perception_obstacles: Clear detected obstacles from the planning world. \
Use when planning fails with COLLISION_AT_START.

COORDINATE SYSTEM (world frame, meters): X=forward, Y=left, Z=up. Z=0 is robot base.

ERROR RECOVERY: If planning fails with COLLISION_AT_START, call clear_perception_obstacles \
then reset, then retry. Detected objects may overlap the robot's current position.

Do NOT use the 'detect' or 'select' skills — use scan_objects instead.
For robot_name parameters, always omit or pass None (single-arm setup).
After pick or place, return to init with go_init unless another action follows immediately.
Do NOT use the 'detect' or 'select' skills — use scan_objects instead.
"""

xarm_perception_agent = autoconnect(
Expand All @@ -405,6 +451,7 @@ def _make_piper_config(
"dual_xarm6_planner",
"xarm6_planner_only",
"xarm7_planner_coordinator",
"xarm7_planner_coordinator_agent",
"xarm_perception",
"xarm_perception_agent",
]
Loading
Loading