|
| 1 | +# Manipulator Drivers |
| 2 | + |
| 3 | +Component-based framework for integrating robotic manipulators into DIMOS. |
| 4 | + |
| 5 | +## Quick Start: Adding a New Manipulator |
| 6 | + |
| 7 | +Adding support for a new robot arm requires **two files**: |
| 8 | +1. **SDK Wrapper** (~200-500 lines) - Translates vendor SDK to standard interface |
| 9 | +2. **Driver** (~30-50 lines) - Assembles components and configuration |
| 10 | + |
| 11 | +## Directory Structure |
| 12 | + |
| 13 | +``` |
| 14 | +manipulators/ |
| 15 | +├── base/ # Framework (don't modify) |
| 16 | +│ ├── sdk_interface.py # BaseManipulatorSDK abstract class |
| 17 | +│ ├── driver.py # BaseManipulatorDriver base class |
| 18 | +│ ├── spec.py # ManipulatorCapabilities dataclass |
| 19 | +│ └── components/ # Reusable standard components |
| 20 | +├── xarm/ # XArm implementation (reference) |
| 21 | +└── piper/ # Piper implementation (reference) |
| 22 | +``` |
| 23 | + |
| 24 | +## Hardware Requirements |
| 25 | + |
| 26 | +Your manipulator **must** support: |
| 27 | + |
| 28 | +| Requirement | Description | |
| 29 | +|-------------|-------------| |
| 30 | +| Joint Position Feedback | Read current joint angles | |
| 31 | +| Joint Position Control | Command target joint positions | |
| 32 | +| Servo Enable/Disable | Enable and disable motor power | |
| 33 | +| Error Reporting | Report error codes/states | |
| 34 | +| Emergency Stop | Hardware or software e-stop | |
| 35 | + |
| 36 | +**Optional:** velocity control, torque control, cartesian control, F/T sensor, gripper |
| 37 | + |
| 38 | +## Step 1: Implement SDK Wrapper |
| 39 | + |
| 40 | +Create `your_arm/your_arm_wrapper.py` implementing `BaseManipulatorSDK`: |
| 41 | + |
| 42 | +```python |
| 43 | +from dimos.hardware.manipulators.base.sdk_interface import BaseManipulatorSDK, ManipulatorInfo |
| 44 | + |
| 45 | +class YourArmSDKWrapper(BaseManipulatorSDK): |
| 46 | + def __init__(self): |
| 47 | + self._sdk = None |
| 48 | + |
| 49 | + def connect(self, config: dict) -> bool: |
| 50 | + self._sdk = YourNativeSDK(config['ip']) |
| 51 | + return self._sdk.connect() |
| 52 | + |
| 53 | + def get_joint_positions(self) -> list[float]: |
| 54 | + """Return positions in RADIANS.""" |
| 55 | + degrees = self._sdk.get_angles() |
| 56 | + return [math.radians(d) for d in degrees] |
| 57 | + |
| 58 | + def set_joint_positions(self, positions: list[float], |
| 59 | + velocity: float, acceleration: float) -> bool: |
| 60 | + return self._sdk.move_joints(positions, velocity) |
| 61 | + |
| 62 | + def enable_servos(self) -> bool: |
| 63 | + return self._sdk.motor_on() |
| 64 | + |
| 65 | + # ... implement remaining required methods (see sdk_interface.py) |
| 66 | +``` |
| 67 | + |
| 68 | +### Unit Conventions |
| 69 | + |
| 70 | +**All SDK wrappers must use these standard units:** |
| 71 | + |
| 72 | +| Quantity | Unit | |
| 73 | +|----------|------| |
| 74 | +| Joint positions | radians | |
| 75 | +| Joint velocities | rad/s | |
| 76 | +| Joint accelerations | rad/s^2 | |
| 77 | +| Joint torques | Nm | |
| 78 | +| Cartesian positions | meters | |
| 79 | +| Forces | N | |
| 80 | + |
| 81 | +## Step 2: Create Driver Assembly |
| 82 | + |
| 83 | +Create `your_arm/your_arm_driver.py`: |
| 84 | + |
| 85 | +```python |
| 86 | +from dimos.hardware.manipulators.base.driver import BaseManipulatorDriver |
| 87 | +from dimos.hardware.manipulators.base.spec import ManipulatorCapabilities |
| 88 | +from dimos.hardware.manipulators.base.components import ( |
| 89 | + StandardMotionComponent, |
| 90 | + StandardServoComponent, |
| 91 | + StandardStatusComponent, |
| 92 | +) |
| 93 | +from .your_arm_wrapper import YourArmSDKWrapper |
| 94 | + |
| 95 | +class YourArmDriver(BaseManipulatorDriver): |
| 96 | + def __init__(self, config: dict): |
| 97 | + sdk = YourArmSDKWrapper() |
| 98 | + |
| 99 | + capabilities = ManipulatorCapabilities( |
| 100 | + dof=6, |
| 101 | + has_gripper=False, |
| 102 | + has_force_torque=False, |
| 103 | + joint_limits_lower=[-3.14, -2.09, -3.14, -3.14, -3.14, -3.14], |
| 104 | + joint_limits_upper=[3.14, 2.09, 3.14, 3.14, 3.14, 3.14], |
| 105 | + max_joint_velocity=[2.0] * 6, |
| 106 | + max_joint_acceleration=[4.0] * 6, |
| 107 | + ) |
| 108 | + |
| 109 | + components = [ |
| 110 | + StandardMotionComponent(), |
| 111 | + StandardServoComponent(), |
| 112 | + StandardStatusComponent(), |
| 113 | + ] |
| 114 | + |
| 115 | + super().__init__(sdk, components, config, capabilities) |
| 116 | +``` |
| 117 | + |
| 118 | +## Component API Decorator |
| 119 | + |
| 120 | +Use `@component_api` to expose methods as RPC endpoints: |
| 121 | + |
| 122 | +```python |
| 123 | +from dimos.hardware.manipulators.base.components import component_api |
| 124 | + |
| 125 | +class StandardMotionComponent: |
| 126 | + @component_api |
| 127 | + def move_joint(self, positions: list[float], velocity: float = 1.0): |
| 128 | + """Auto-exposed as driver.move_joint()""" |
| 129 | + ... |
| 130 | +``` |
| 131 | + |
| 132 | +## Threading Architecture |
| 133 | + |
| 134 | +The driver runs **2 threads**: |
| 135 | +1. **Control Loop (100Hz)** - Processes commands, reads joint state, publishes feedback |
| 136 | +2. **Monitor Loop (10Hz)** - Reads robot state, errors, optional sensors |
| 137 | + |
| 138 | +``` |
| 139 | +RPC Call → Command Queue → Control Loop → SDK → Hardware |
| 140 | + ↓ |
| 141 | + SharedState → LCM Publisher |
| 142 | +``` |
| 143 | + |
| 144 | +## Testing Your Driver |
| 145 | + |
| 146 | +```python |
| 147 | +driver = YourArmDriver({"ip": "192.168.1.100"}) |
| 148 | +driver.start() |
| 149 | +driver.enable_servo() |
| 150 | +driver.move_joint([0, 0, 0, 0, 0, 0], velocity=0.5) |
| 151 | +state = driver.get_joint_state() |
| 152 | +driver.stop() |
| 153 | +``` |
| 154 | + |
| 155 | +## Common Issues |
| 156 | + |
| 157 | +| Issue | Solution | |
| 158 | +|-------|----------| |
| 159 | +| Unit mismatch | Verify wrapper converts to radians/meters | |
| 160 | +| Commands ignored | Ensure servos are enabled before commanding | |
| 161 | +| Velocity not working | Some arms need mode switch via `set_control_mode()` | |
| 162 | + |
| 163 | +## Architecture Details |
| 164 | + |
| 165 | +For complete architecture documentation including full SDK interface specification, |
| 166 | +component details, and testing strategies, see: |
| 167 | + |
| 168 | +**[component_based_architecture.md](base/component_based_architecture.md)** |
| 169 | + |
| 170 | +## Reference Implementations |
| 171 | + |
| 172 | +- **XArm**: [xarm/xarm_wrapper.py](xarm/xarm_wrapper.py) - Full-featured wrapper |
| 173 | +- **Piper**: [piper/piper_wrapper.py](piper/piper_wrapper.py) - Shows velocity workaround |
0 commit comments