Skip to content

Commit f32afab

Browse files
committed
Merge branch 'xarm-rt-driver' of https://github.com/dimensionalOS/dimos into xarm-rt-driver
2 parents b1f0326 + 1a38e63 commit f32afab

File tree

20 files changed

+144
-135
lines changed

20 files changed

+144
-135
lines changed
Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,15 @@
11
"""Component classes for XArmDriver."""
22

3+
from .gripper_control import GripperControlComponent
4+
from .kinematics import KinematicsComponent
35
from .motion_control import MotionControlComponent
46
from .state_queries import StateQueryComponent
57
from .system_control import SystemControlComponent
6-
from .kinematics import KinematicsComponent
7-
from .gripper_control import GripperControlComponent
88

99
__all__ = [
10+
"GripperControlComponent",
11+
"KinematicsComponent",
1012
"MotionControlComponent",
1113
"StateQueryComponent",
1214
"SystemControlComponent",
13-
"KinematicsComponent",
14-
"GripperControlComponent",
1515
]

dimos/hardware/manipulators/xarm/interactive_control.py

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -27,30 +27,30 @@
2727
venv/bin/python dimos/hardware/manipulators/xarm/interactive_control.py
2828
"""
2929

30+
import math
3031
import os
3132
import time
32-
import math
3333

3434
from dimos import core
35-
from dimos.hardware.manipulators.xarm.xarm_driver import XArmDriver
3635
from dimos.hardware.manipulators.xarm.sample_trajectory_generator import (
3736
SampleTrajectoryGenerator,
3837
)
39-
from dimos.msgs.sensor_msgs import JointState, RobotState, JointCommand
38+
from dimos.hardware.manipulators.xarm.xarm_driver import XArmDriver
39+
from dimos.msgs.sensor_msgs import JointCommand, JointState, RobotState
4040
from dimos.utils.logging_config import setup_logger
4141

4242
logger = setup_logger(__file__)
4343

4444

45-
def print_banner():
45+
def print_banner() -> None:
4646
"""Print welcome banner."""
4747
print("\n" + "=" * 80)
4848
print(" xArm Interactive Control")
4949
print(" Real-time joint control via terminal UI")
5050
print("=" * 80)
5151

5252

53-
def print_current_state(traj_gen):
53+
def print_current_state(traj_gen) -> None:
5454
"""Display current joint positions."""
5555
state = traj_gen.get_current_state()
5656

@@ -99,7 +99,7 @@ def get_control_mode():
9999
return None
100100

101101

102-
def get_joint_selection(num_joints):
102+
def get_joint_selection(num_joints: int):
103103
"""Get joint selection from user."""
104104
while True:
105105
try:
@@ -240,14 +240,14 @@ def confirm_motion_velocity(joint_index, velocity_deg_s, duration):
240240
f" Velocity: {velocity_deg_s:+.2f}°/s ({'clockwise' if velocity_deg_s < 0 else 'counterclockwise'})"
241241
)
242242
print(f" Duration: {duration:.2f}s (with ramp up/down)")
243-
print(f" Profile: 20% ramp up, 60% constant, 20% ramp down")
243+
print(" Profile: 20% ramp up, 60% constant, 20% ramp down")
244244
print("=" * 80)
245245

246246
confirm = input("\nExecute this motion? (y/n): ").strip().lower()
247247
return confirm == "y"
248248

249249

250-
def wait_for_trajectory_completion(traj_gen, duration):
250+
def wait_for_trajectory_completion(traj_gen, duration) -> None:
251251
"""Wait for trajectory to complete and show progress."""
252252
print("\n⚙ Executing motion...")
253253

@@ -272,7 +272,7 @@ def wait_for_trajectory_completion(traj_gen, duration):
272272
print("✓ Motion complete!")
273273

274274

275-
def interactive_control_loop(xarm, traj_gen, num_joints):
275+
def interactive_control_loop(xarm, traj_gen, num_joints: int) -> None:
276276
"""Main interactive control loop."""
277277
print_banner()
278278

@@ -424,7 +424,7 @@ def interactive_control_loop(xarm, traj_gen, num_joints):
424424
print("=" * 80)
425425

426426

427-
def main():
427+
def main() -> None:
428428
"""Run interactive xArm control."""
429429
import argparse
430430

dimos/hardware/manipulators/xarm/sample_trajectory_generator.py

Lines changed: 21 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -39,14 +39,13 @@
3939
traj_gen.start()
4040
"""
4141

42-
import time
43-
import threading
44-
import math
45-
from typing import List, Optional
4642
from dataclasses import dataclass
43+
import math
44+
import threading
45+
import time
4746

48-
from dimos.core import Module, ModuleConfig, In, Out, rpc
49-
from dimos.msgs.sensor_msgs import JointState, RobotState, JointCommand
47+
from dimos.core import In, Module, ModuleConfig, Out, rpc
48+
from dimos.msgs.sensor_msgs import JointCommand, JointState, RobotState
5049
from dimos.utils.logging_config import setup_logger
5150

5251
logger = setup_logger(__file__)
@@ -85,18 +84,18 @@ class SampleTrajectoryGenerator(Module):
8584
joint_position_command: Out[JointCommand] = None # Position commands (radians)
8685
joint_velocity_command: Out[JointCommand] = None # Velocity commands (rad/s)
8786

88-
def __init__(self, **kwargs):
87+
def __init__(self, **kwargs) -> None:
8988
super().__init__(**kwargs)
9089

9190
# State tracking
92-
self._current_joint_state: Optional[JointState] = None
93-
self._current_robot_state: Optional[RobotState] = None
91+
self._current_joint_state: JointState | None = None
92+
self._current_robot_state: RobotState | None = None
9493
self._state_lock = threading.Lock()
9594

9695
# Control thread
9796
self._running = False
9897
self._stop_event = threading.Event()
99-
self._control_thread: Optional[threading.Thread] = None
98+
self._control_thread: threading.Thread | None = None
10099

101100
# Publishing enabled flag
102101
self._publishing_enabled = self.config.enable_on_start
@@ -121,7 +120,7 @@ def __init__(self, **kwargs):
121120
)
122121

123122
@rpc
124-
def start(self):
123+
def start(self) -> None:
125124
"""Start the trajectory generator."""
126125
super().start()
127126

@@ -144,7 +143,7 @@ def start(self):
144143
logger.info("Trajectory generator started")
145144

146145
@rpc
147-
def stop(self):
146+
def stop(self) -> None:
148147
"""Stop the trajectory generator."""
149148
logger.info("Stopping trajectory generator...")
150149

@@ -159,19 +158,19 @@ def stop(self):
159158
logger.info("Trajectory generator stopped")
160159

161160
@rpc
162-
def enable_publishing(self):
161+
def enable_publishing(self) -> None:
163162
"""Enable command publishing."""
164163
self._publishing_enabled = True
165164
logger.info("Command publishing enabled")
166165

167166
@rpc
168-
def disable_publishing(self):
167+
def disable_publishing(self) -> None:
169168
"""Disable command publishing."""
170169
self._publishing_enabled = False
171170
logger.info("Command publishing disabled")
172171

173172
@rpc
174-
def set_velocity_mode(self, enabled: bool):
173+
def set_velocity_mode(self, enabled: bool) -> None:
175174
"""
176175
Set velocity mode flag.
177176
@@ -313,7 +312,7 @@ def move_joint_velocity(self, joint_index: int, velocity_deg_s: float, duration:
313312
# Private Methods: Callbacks
314313
# =========================================================================
315314

316-
def _on_joint_state(self, msg: JointState):
315+
def _on_joint_state(self, msg: JointState) -> None:
317316
"""Callback for receiving joint state updates."""
318317
with self._state_lock:
319318
# Log first message with all joints
@@ -329,7 +328,7 @@ def _on_joint_state(self, msg: JointState):
329328
)
330329
self._current_joint_state = msg
331330

332-
def _on_robot_state(self, msg: RobotState):
331+
def _on_robot_state(self, msg: RobotState) -> None:
333332
"""Callback for receiving robot state updates."""
334333
with self._state_lock:
335334
# Log first message or when state/error changes
@@ -360,7 +359,7 @@ def _on_robot_state(self, msg: RobotState):
360359
# Private Methods: Control Loop
361360
# =========================================================================
362361

363-
def _start_control_loop(self):
362+
def _start_control_loop(self) -> None:
364363
"""Start the control loop thread."""
365364
logger.info(f"Starting control loop at {self.config.publish_rate}Hz")
366365

@@ -372,7 +371,7 @@ def _start_control_loop(self):
372371
)
373372
self._control_thread.start()
374373

375-
def _control_loop(self):
374+
def _control_loop(self) -> None:
376375
"""
377376
Control loop for publishing commands.
378377
@@ -436,7 +435,7 @@ def _control_loop(self):
436435

437436
logger.info("Control loop stopped")
438437

439-
def _generate_command(self) -> Optional[List[float]]:
438+
def _generate_command(self) -> list[float] | None:
440439
"""
441440
Generate command for the robot.
442441
@@ -514,7 +513,7 @@ def _generate_command(self) -> Optional[List[float]]:
514513
# Position mode with no trajectory: hold current position (safe)
515514
return list(self._current_joint_state.position)
516515

517-
def _publish_position_command(self, command: List[float]):
516+
def _publish_position_command(self, command: list[float]) -> None:
518517
"""Publish joint position command."""
519518
if self.joint_position_command._transport or (
520519
hasattr(self.joint_position_command, "connection")
@@ -539,7 +538,7 @@ def _publish_position_command(self, command: List[float]):
539538
if self._command_count == 0:
540539
logger.warning("joint_position_command transport not configured!")
541540

542-
def _publish_velocity_command(self, command: List[float]):
541+
def _publish_velocity_command(self, command: list[float]) -> None:
543542
"""Publish joint velocity command."""
544543
if self.joint_velocity_command._transport or (
545544
hasattr(self.joint_velocity_command, "connection")

dimos/hardware/manipulators/xarm/spec.py

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -12,12 +12,11 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
from typing import Protocol, List, Tuple
15+
from typing import Protocol
1616

1717
from dimos.core import In, Out
18-
from dimos.msgs.geometry_msgs import PoseStamped, Twist, WrenchStamped
19-
from dimos.msgs.nav_msgs import Path
20-
from dimos.msgs.sensor_msgs import JointState, RobotState, JointCommand
18+
from dimos.msgs.geometry_msgs import WrenchStamped
19+
from dimos.msgs.sensor_msgs import JointCommand, JointState, RobotState
2120

2221

2322
class ArmDriverSpec(Protocol):
@@ -37,14 +36,14 @@ class ArmDriverSpec(Protocol):
3736
ft_raw: Out[WrenchStamped] # Raw force/torque sensor data
3837

3938
# RPC Methods
40-
def set_joint_angles(self, angles: List[float]) -> Tuple[int, str]: ...
39+
def set_joint_angles(self, angles: list[float]) -> tuple[int, str]: ...
4140

42-
def set_joint_velocities(self, velocities: List[float]) -> Tuple[int, str]: ...
41+
def set_joint_velocities(self, velocities: list[float]) -> tuple[int, str]: ...
4342

4443
def get_joint_state(self) -> JointState: ...
4544

4645
def get_robot_state(self) -> RobotState: ...
4746

48-
def enable_servo_mode(self) -> Tuple[int, str]: ...
47+
def enable_servo_mode(self) -> tuple[int, str]: ...
4948

50-
def disable_servo_mode(self) -> Tuple[int, str]: ...
49+
def disable_servo_mode(self) -> tuple[int, str]: ...

dimos/hardware/manipulators/xarm/test_xarm_driver.py

Lines changed: 10 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,8 @@
3838

3939
from dimos import core
4040
from dimos.hardware.manipulators.xarm.xarm_driver import XArmDriver
41-
from dimos.msgs.sensor_msgs import JointState, RobotState
4241
from dimos.msgs.geometry_msgs import WrenchStamped
42+
from dimos.msgs.sensor_msgs import JointState, RobotState
4343
from dimos.utils.logging_config import setup_logger
4444

4545
logger = setup_logger(__file__)
@@ -108,7 +108,7 @@ def driver(dimos_cluster):
108108

109109

110110
@pytest.mark.tool
111-
def test_basic_connection(driver):
111+
def test_basic_connection(driver) -> None:
112112
"""Test basic connection and startup with dimos deployment."""
113113
logger.info("=" * 80)
114114
logger.info("TEST 1: Basic Connection with dimos.deploy()")
@@ -135,7 +135,7 @@ def test_basic_connection(driver):
135135

136136

137137
@pytest.mark.tool
138-
def test_joint_state_reading(driver):
138+
def test_joint_state_reading(driver) -> None:
139139
"""Test joint state reading via LCM topic subscription."""
140140
logger.info("=" * 80)
141141
logger.info("TEST 2: Joint State Reading via LCM Transport")
@@ -149,7 +149,7 @@ def test_joint_state_reading(driver):
149149
joint_states_received = []
150150
robot_states_received = []
151151

152-
def on_joint_state(msg):
152+
def on_joint_state(msg) -> None:
153153
"""Callback for receiving joint state messages from LCM."""
154154
joint_states_received.append(msg)
155155
if len(joint_states_received) <= 3:
@@ -159,7 +159,7 @@ def on_joint_state(msg):
159159
f"(showing first 3 joints)"
160160
)
161161

162-
def on_robot_state(msg):
162+
def on_robot_state(msg) -> None:
163163
"""Callback for receiving robot state messages from LCM."""
164164
robot_states_received.append(msg)
165165
if len(robot_states_received) <= 3:
@@ -227,7 +227,7 @@ def on_robot_state(msg):
227227

228228

229229
@pytest.mark.tool
230-
def test_command_sending(driver):
230+
def test_command_sending(driver) -> None:
231231
"""Test that command RPC methods are available and functional."""
232232
logger.info("=" * 80)
233233
logger.info("TEST 3: Command RPC Methods")
@@ -271,7 +271,7 @@ def test_command_sending(driver):
271271

272272

273273
@pytest.mark.tool
274-
def test_rpc_methods(driver):
274+
def test_rpc_methods(driver) -> None:
275275
"""Test RPC method calls."""
276276
logger.info("=" * 80)
277277
logger.info("TEST 4: RPC Methods")
@@ -304,7 +304,7 @@ def test_rpc_methods(driver):
304304
logger.info("✓ TEST 4 PASSED\n")
305305

306306

307-
def run_tests():
307+
def run_tests() -> None:
308308
"""Run all tests."""
309309
logger.info("=" * 80)
310310
logger.info("XArm Driver Test Suite (Full dimos Deployment)")
@@ -371,7 +371,7 @@ def run_tests():
371371
logger.error("❌ SOME TESTS FAILED")
372372

373373

374-
def run_driver():
374+
def run_driver() -> None:
375375
"""Start the xArm driver and keep it running."""
376376
logger.info("=" * 80)
377377
logger.info("XArm Driver - Starting in continuous mode")
@@ -431,9 +431,8 @@ def run_driver():
431431
logger.info("✓ Driver stopped")
432432

433433

434-
def main():
434+
def main() -> None:
435435
"""Main entry point."""
436-
import sys
437436
import argparse
438437

439438
# Parse command-line arguments

0 commit comments

Comments
 (0)