dexcontrol 0.2.12__py3-none-any.whl → 0.3.4__py3-none-any.whl
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- dexcontrol/__init__.py +17 -8
- dexcontrol/apps/dualsense_teleop_base.py +1 -1
- dexcontrol/comm/__init__.py +51 -0
- dexcontrol/comm/rtc.py +401 -0
- dexcontrol/comm/subscribers.py +329 -0
- dexcontrol/config/core/chassis.py +9 -4
- dexcontrol/config/core/hand.py +1 -0
- dexcontrol/config/sensors/cameras/__init__.py +1 -2
- dexcontrol/config/sensors/cameras/zed_camera.py +2 -2
- dexcontrol/config/sensors/vega_sensors.py +12 -18
- dexcontrol/config/vega.py +4 -1
- dexcontrol/core/arm.py +66 -42
- dexcontrol/core/chassis.py +142 -120
- dexcontrol/core/component.py +107 -58
- dexcontrol/core/hand.py +119 -86
- dexcontrol/core/head.py +22 -33
- dexcontrol/core/misc.py +331 -158
- dexcontrol/core/robot_query_interface.py +467 -0
- dexcontrol/core/torso.py +5 -9
- dexcontrol/robot.py +245 -574
- dexcontrol/sensors/__init__.py +1 -2
- dexcontrol/sensors/camera/__init__.py +0 -2
- dexcontrol/sensors/camera/base_camera.py +150 -0
- dexcontrol/sensors/camera/rgb_camera.py +68 -64
- dexcontrol/sensors/camera/zed_camera.py +140 -164
- dexcontrol/sensors/imu/chassis_imu.py +81 -62
- dexcontrol/sensors/imu/zed_imu.py +54 -43
- dexcontrol/sensors/lidar/rplidar.py +16 -20
- dexcontrol/sensors/manager.py +4 -14
- dexcontrol/sensors/ultrasonic.py +15 -28
- dexcontrol/utils/__init__.py +0 -11
- dexcontrol/utils/comm_helper.py +110 -0
- dexcontrol/utils/constants.py +1 -1
- dexcontrol/utils/error_code.py +2 -4
- dexcontrol/utils/os_utils.py +172 -4
- dexcontrol/utils/pb_utils.py +6 -28
- {dexcontrol-0.2.12.dist-info → dexcontrol-0.3.4.dist-info}/METADATA +16 -3
- dexcontrol-0.3.4.dist-info/RECORD +62 -0
- {dexcontrol-0.2.12.dist-info → dexcontrol-0.3.4.dist-info}/WHEEL +1 -1
- dexcontrol/config/sensors/cameras/luxonis_camera.py +0 -51
- dexcontrol/proto/dexcontrol_msg_pb2.py +0 -73
- dexcontrol/proto/dexcontrol_msg_pb2.pyi +0 -220
- dexcontrol/proto/dexcontrol_query_pb2.py +0 -77
- dexcontrol/proto/dexcontrol_query_pb2.pyi +0 -162
- dexcontrol/sensors/camera/luxonis_camera.py +0 -169
- dexcontrol/utils/motion_utils.py +0 -199
- dexcontrol/utils/rate_limiter.py +0 -172
- dexcontrol/utils/rtc_utils.py +0 -144
- dexcontrol/utils/subscribers/__init__.py +0 -52
- dexcontrol/utils/subscribers/base.py +0 -281
- dexcontrol/utils/subscribers/camera.py +0 -332
- dexcontrol/utils/subscribers/decoders.py +0 -88
- dexcontrol/utils/subscribers/generic.py +0 -110
- dexcontrol/utils/subscribers/imu.py +0 -175
- dexcontrol/utils/subscribers/lidar.py +0 -172
- dexcontrol/utils/subscribers/protobuf.py +0 -111
- dexcontrol/utils/subscribers/rtc.py +0 -316
- dexcontrol/utils/zenoh_utils.py +0 -122
- dexcontrol-0.2.12.dist-info/RECORD +0 -75
- {dexcontrol-0.2.12.dist-info → dexcontrol-0.3.4.dist-info}/licenses/LICENSE +0 -0
dexcontrol/robot.py
CHANGED
|
@@ -24,7 +24,7 @@ from __future__ import annotations
|
|
|
24
24
|
|
|
25
25
|
import os
|
|
26
26
|
import signal
|
|
27
|
-
import
|
|
27
|
+
import sys
|
|
28
28
|
import time
|
|
29
29
|
import weakref
|
|
30
30
|
from typing import TYPE_CHECKING, Any, Final, Literal, cast
|
|
@@ -32,7 +32,8 @@ from typing import TYPE_CHECKING, Any, Final, Literal, cast
|
|
|
32
32
|
import hydra.utils
|
|
33
33
|
import numpy as np
|
|
34
34
|
import omegaconf
|
|
35
|
-
import
|
|
35
|
+
from dexcomm import cleanup_session
|
|
36
|
+
from dexcomm.utils import RateLimiter
|
|
36
37
|
from loguru import logger
|
|
37
38
|
from rich.console import Console
|
|
38
39
|
from rich.table import Table
|
|
@@ -40,24 +41,13 @@ from rich.table import Table
|
|
|
40
41
|
import dexcontrol
|
|
41
42
|
from dexcontrol.config.vega import VegaConfig, get_vega_config
|
|
42
43
|
from dexcontrol.core.component import RobotComponent
|
|
43
|
-
from dexcontrol.
|
|
44
|
+
from dexcontrol.core.hand import HandType
|
|
45
|
+
from dexcontrol.core.misc import ServerLogSubscriber
|
|
46
|
+
from dexcontrol.core.robot_query_interface import RobotQueryInterface
|
|
44
47
|
from dexcontrol.sensors import Sensors
|
|
45
48
|
from dexcontrol.utils.constants import ROBOT_NAME_ENV_VAR
|
|
46
|
-
from dexcontrol.utils.os_utils import
|
|
47
|
-
from dexcontrol.utils.pb_utils import (
|
|
48
|
-
TYPE_SOFTWARE_VERSION,
|
|
49
|
-
ComponentStatus,
|
|
50
|
-
software_version_to_dict,
|
|
51
|
-
status_to_dict,
|
|
52
|
-
)
|
|
53
|
-
from dexcontrol.utils.rate_limiter import RateLimiter
|
|
49
|
+
from dexcontrol.utils.os_utils import check_version_compatibility, get_robot_model
|
|
54
50
|
from dexcontrol.utils.trajectory_utils import generate_linear_trajectory
|
|
55
|
-
from dexcontrol.utils.viz_utils import (
|
|
56
|
-
show_component_status,
|
|
57
|
-
show_ntp_stats,
|
|
58
|
-
show_software_version,
|
|
59
|
-
)
|
|
60
|
-
from dexcontrol.utils.zenoh_utils import compute_ntp_stats
|
|
61
51
|
|
|
62
52
|
if TYPE_CHECKING:
|
|
63
53
|
from dexcontrol.core.arm import Arm
|
|
@@ -73,66 +63,25 @@ _active_robots: weakref.WeakSet[Robot] = weakref.WeakSet()
|
|
|
73
63
|
_signal_handlers_registered: bool = False
|
|
74
64
|
|
|
75
65
|
|
|
76
|
-
def _signal_handler(signum: int, frame: Any) -> None:
|
|
77
|
-
"""Signal handler to shutdown all active Robot instances.
|
|
78
|
-
|
|
79
|
-
Args:
|
|
80
|
-
signum: Signal number received (e.g., SIGINT, SIGTERM).
|
|
81
|
-
frame: Current stack frame (unused).
|
|
82
|
-
"""
|
|
83
|
-
logger.info(f"Received signal {signum}, shutting down all active robots...")
|
|
84
|
-
# Create a list copy to avoid modification during iteration
|
|
85
|
-
robots_to_shutdown = list(_active_robots)
|
|
86
|
-
|
|
87
|
-
# Set a total timeout for all shutdowns
|
|
88
|
-
shutdown_start = time.time()
|
|
89
|
-
max_shutdown_time = 5.0 # Maximum 5 seconds for all shutdowns
|
|
90
|
-
|
|
91
|
-
for robot in robots_to_shutdown:
|
|
92
|
-
if time.time() - shutdown_start > max_shutdown_time:
|
|
93
|
-
logger.warning("Shutdown timeout reached, forcing exit")
|
|
94
|
-
break
|
|
95
|
-
|
|
96
|
-
logger.info(f"Shutting down robot: {robot}")
|
|
97
|
-
try:
|
|
98
|
-
robot.shutdown()
|
|
99
|
-
except Exception as e: # pylint: disable=broad-except
|
|
100
|
-
logger.error(f"Error during robot shutdown: {e}", exc_info=True)
|
|
101
|
-
|
|
102
|
-
logger.info("All robots shutdown complete")
|
|
103
|
-
# Force exit to ensure the process terminates
|
|
104
|
-
os._exit(0)
|
|
105
|
-
|
|
106
|
-
|
|
107
66
|
def _register_signal_handlers() -> None:
|
|
108
|
-
"""Register signal handlers for graceful shutdown.
|
|
109
|
-
|
|
110
|
-
This function ensures signal handlers are registered only once and sets up
|
|
111
|
-
handlers for SIGINT (Ctrl+C), SIGTERM, and SIGHUP (on Unix systems).
|
|
112
|
-
"""
|
|
67
|
+
"""Register signal handlers for graceful shutdown."""
|
|
113
68
|
global _signal_handlers_registered
|
|
114
69
|
if _signal_handlers_registered:
|
|
115
70
|
return
|
|
116
71
|
|
|
117
|
-
|
|
118
|
-
|
|
119
|
-
|
|
72
|
+
def signal_handler(signum: int, frame: Any) -> None:
|
|
73
|
+
sys.exit(0)
|
|
74
|
+
|
|
75
|
+
signal.signal(signal.SIGINT, signal_handler)
|
|
76
|
+
signal.signal(signal.SIGTERM, signal_handler)
|
|
120
77
|
|
|
121
|
-
# On Unix systems, also handle SIGHUP
|
|
122
78
|
if hasattr(signal, "SIGHUP"):
|
|
123
|
-
signal.signal(signal.SIGHUP,
|
|
79
|
+
signal.signal(signal.SIGHUP, signal_handler)
|
|
124
80
|
|
|
125
81
|
_signal_handlers_registered = True
|
|
126
82
|
|
|
127
83
|
|
|
128
|
-
class
|
|
129
|
-
"""Type hints for component configuration."""
|
|
130
|
-
|
|
131
|
-
_target_: str
|
|
132
|
-
configs: dict[str, Any]
|
|
133
|
-
|
|
134
|
-
|
|
135
|
-
class Robot:
|
|
84
|
+
class Robot(RobotQueryInterface):
|
|
136
85
|
"""Main interface class for robot control and monitoring.
|
|
137
86
|
|
|
138
87
|
This class serves as the primary interface for interacting with a robot system.
|
|
@@ -141,33 +90,32 @@ class Robot:
|
|
|
141
90
|
system-wide operations like status monitoring, trajectory execution, and component
|
|
142
91
|
control.
|
|
143
92
|
|
|
144
|
-
The Robot class supports context manager usage and automatic cleanup on program
|
|
145
|
-
interruption through signal handlers.
|
|
146
|
-
|
|
147
93
|
Example usage:
|
|
148
94
|
# Using context manager (recommended)
|
|
149
95
|
with Robot() as robot:
|
|
150
96
|
robot.set_joint_pos({"left_arm": [0, 0, 0, 0, 0, 0, 0]})
|
|
97
|
+
version_info = robot.get_version_info()
|
|
151
98
|
|
|
152
99
|
# Manual usage with explicit shutdown
|
|
153
100
|
robot = Robot()
|
|
154
101
|
try:
|
|
155
102
|
robot.set_joint_pos({"left_arm": [0, 0, 0, 0, 0, 0, 0]})
|
|
103
|
+
hand_types = robot.query_hand_type()
|
|
156
104
|
finally:
|
|
157
105
|
robot.shutdown()
|
|
158
106
|
|
|
159
107
|
Attributes:
|
|
160
|
-
left_arm: Left arm component interface.
|
|
161
|
-
right_arm: Right arm component interface.
|
|
162
|
-
left_hand: Left hand component interface.
|
|
163
|
-
right_hand: Right hand component interface.
|
|
164
|
-
head: Head component interface.
|
|
165
|
-
chassis: Chassis component interface.
|
|
166
|
-
torso: Torso component interface.
|
|
108
|
+
left_arm: Left arm component interface (7-DOF manipulator).
|
|
109
|
+
right_arm: Right arm component interface (7-DOF manipulator).
|
|
110
|
+
left_hand: Left hand component interface (conditional, based on hardware).
|
|
111
|
+
right_hand: Right hand component interface (conditional, based on hardware).
|
|
112
|
+
head: Head component interface (3-DOF pan-tilt-roll).
|
|
113
|
+
chassis: Chassis component interface (mobile base).
|
|
114
|
+
torso: Torso component interface (1-DOF pitch).
|
|
167
115
|
battery: Battery monitoring interface.
|
|
168
116
|
estop: Emergency stop interface.
|
|
169
117
|
heartbeat: Heartbeat monitoring interface.
|
|
170
|
-
sensors: Sensor systems interface.
|
|
118
|
+
sensors: Sensor systems interface (cameras, IMU, lidar, etc.).
|
|
171
119
|
"""
|
|
172
120
|
|
|
173
121
|
# Type annotations for dynamically created attributes
|
|
@@ -188,7 +136,6 @@ class Robot:
|
|
|
188
136
|
self,
|
|
189
137
|
robot_model: str | None = None,
|
|
190
138
|
configs: VegaConfig | None = None,
|
|
191
|
-
zenoh_config_file: str | None = None,
|
|
192
139
|
auto_shutdown: bool = True,
|
|
193
140
|
) -> None:
|
|
194
141
|
"""Initializes the Robot with the given configuration.
|
|
@@ -199,8 +146,6 @@ class Robot:
|
|
|
199
146
|
Ignored if configs is provided.
|
|
200
147
|
configs: Configuration parameters for all robot components.
|
|
201
148
|
If None, will use the configuration specified by robot_model.
|
|
202
|
-
zenoh_config_file: Optional path to the zenoh config file.
|
|
203
|
-
Defaults to None to use system defaults.
|
|
204
149
|
auto_shutdown: Whether to automatically register signal handlers for
|
|
205
150
|
graceful shutdown on program interruption. Default is True.
|
|
206
151
|
|
|
@@ -214,25 +159,19 @@ class Robot:
|
|
|
214
159
|
robot_model = get_robot_model()
|
|
215
160
|
self._robot_model: Final[str] = robot_model
|
|
216
161
|
|
|
217
|
-
|
|
218
|
-
|
|
219
|
-
except Exception as e:
|
|
220
|
-
raise ValueError(f"Failed to load robot configuration: {e}") from e
|
|
162
|
+
# Load configuration
|
|
163
|
+
self._configs: Final[VegaConfig] = configs or get_vega_config(robot_model)
|
|
221
164
|
|
|
222
|
-
|
|
223
|
-
self._zenoh_session: Final[zenoh.Session] = self._init_zenoh_session(
|
|
224
|
-
zenoh_config_file
|
|
225
|
-
)
|
|
226
|
-
except Exception as e:
|
|
227
|
-
raise RuntimeError(f"Failed to initialize zenoh session: {e}") from e
|
|
165
|
+
super().__init__(self._configs)
|
|
228
166
|
|
|
229
167
|
self._robot_name: Final[str] = os.getenv(ROBOT_NAME_ENV_VAR, "robot")
|
|
230
|
-
self._pv_components:
|
|
231
|
-
"left_hand",
|
|
232
|
-
"right_hand",
|
|
168
|
+
self._pv_components: list[str] = [
|
|
233
169
|
"head",
|
|
234
170
|
"torso",
|
|
235
171
|
]
|
|
172
|
+
# Note: zenoh_session no longer needed as DexComm handles sessions
|
|
173
|
+
self._log_subscriber = ServerLogSubscriber()
|
|
174
|
+
self._hand_types: dict[str, HandType] = {}
|
|
236
175
|
|
|
237
176
|
# Register for automatic shutdown on signals if enabled
|
|
238
177
|
if auto_shutdown:
|
|
@@ -241,53 +180,11 @@ class Robot:
|
|
|
241
180
|
|
|
242
181
|
self._print_initialization_info(robot_model)
|
|
243
182
|
|
|
244
|
-
# Initialize robot
|
|
245
|
-
|
|
246
|
-
config_dict = omegaconf.OmegaConf.to_container(self._configs, resolve=True)
|
|
247
|
-
if not isinstance(config_dict, dict):
|
|
248
|
-
raise ValueError("Invalid configuration format")
|
|
249
|
-
self._init_components(cast(dict[str, Any], config_dict))
|
|
250
|
-
except Exception as e:
|
|
251
|
-
self.shutdown() # Clean up on initialization failure
|
|
252
|
-
raise RuntimeError(f"Failed to initialize robot components: {e}") from e
|
|
253
|
-
|
|
254
|
-
# Ensure all components are active
|
|
255
|
-
try:
|
|
256
|
-
self._wait_for_components()
|
|
257
|
-
except Exception as e:
|
|
258
|
-
self.shutdown() # Clean up on initialization failure
|
|
259
|
-
raise RuntimeError(f"Failed to activate components: {e}") from e
|
|
183
|
+
# Initialize robot components with safe error handling
|
|
184
|
+
self._safe_initialize_components()
|
|
260
185
|
|
|
261
|
-
|
|
262
|
-
|
|
263
|
-
self.sensors.wait_for_all_active()
|
|
264
|
-
except Exception as e:
|
|
265
|
-
self.shutdown() # Clean up on initialization failure
|
|
266
|
-
raise RuntimeError(f"Failed to initialize sensors: {e}") from e
|
|
267
|
-
|
|
268
|
-
# Check soc software version before proceeding
|
|
269
|
-
version_dict = self.get_software_version(show=False)
|
|
270
|
-
min_soc_version = dexcontrol.MIN_SOC_SOFTWARE_VERSION
|
|
271
|
-
soc_version = version_dict.get("soc", {}).get("software_version")
|
|
272
|
-
if soc_version is None:
|
|
273
|
-
logger.warning(
|
|
274
|
-
"Could not determine the software version of the remote driver ('soc'). "
|
|
275
|
-
"Please ensure the remote server is running and reachable."
|
|
276
|
-
)
|
|
277
|
-
elif soc_version < min_soc_version:
|
|
278
|
-
logger.warning(
|
|
279
|
-
f"The remote driver ('soc') software version is too old: {soc_version}. "
|
|
280
|
-
f"Minimum required version is {min_soc_version}.\n"
|
|
281
|
-
f"Please update the remote server or downgrade this project code to match the server version. "
|
|
282
|
-
f"Otherwise, some features may not work correctly or may encounter errors."
|
|
283
|
-
)
|
|
284
|
-
|
|
285
|
-
# Set default modes
|
|
286
|
-
try:
|
|
287
|
-
self._set_default_modes()
|
|
288
|
-
except Exception as e:
|
|
289
|
-
self.shutdown() # Clean up on initialization failure
|
|
290
|
-
raise RuntimeError(f"Failed to set default modes: {e}") from e
|
|
186
|
+
# Check version compatibility using new JSON interface
|
|
187
|
+
self._check_version_compatibility()
|
|
291
188
|
|
|
292
189
|
@property
|
|
293
190
|
def robot_model(self) -> str:
|
|
@@ -307,24 +204,12 @@ class Robot:
|
|
|
307
204
|
"""
|
|
308
205
|
return self._robot_name
|
|
309
206
|
|
|
310
|
-
def __enter__(self) -> Robot:
|
|
311
|
-
"""
|
|
312
|
-
|
|
313
|
-
Returns:
|
|
314
|
-
Self reference for context management.
|
|
315
|
-
"""
|
|
207
|
+
def __enter__(self) -> "Robot":
|
|
208
|
+
"""Enter context manager."""
|
|
316
209
|
return self
|
|
317
210
|
|
|
318
|
-
def __exit__(
|
|
319
|
-
|
|
320
|
-
) -> None:
|
|
321
|
-
"""Context manager exit with automatic shutdown.
|
|
322
|
-
|
|
323
|
-
Args:
|
|
324
|
-
exc_type: Type of the exception that occurred, if any.
|
|
325
|
-
exc_val: Exception instance that occurred, if any.
|
|
326
|
-
exc_tb: Traceback of the exception that occurred, if any.
|
|
327
|
-
"""
|
|
211
|
+
def __exit__(self, exc_type, exc_val, exc_tb):
|
|
212
|
+
"""Exit context manager and clean up resources."""
|
|
328
213
|
self.shutdown()
|
|
329
214
|
|
|
330
215
|
def __del__(self) -> None:
|
|
@@ -340,41 +225,6 @@ class Robot:
|
|
|
340
225
|
# During interpreter shutdown, some modules might not be available
|
|
341
226
|
pass
|
|
342
227
|
|
|
343
|
-
@staticmethod
|
|
344
|
-
def cleanup_all() -> None:
|
|
345
|
-
"""Force cleanup of all Zenoh resources and threads.
|
|
346
|
-
|
|
347
|
-
This method can be called between Robot instances to ensure a clean state.
|
|
348
|
-
It's especially useful when creating multiple Robot instances in the same script.
|
|
349
|
-
|
|
350
|
-
Example:
|
|
351
|
-
robot1 = Robot()
|
|
352
|
-
robot1.shutdown()
|
|
353
|
-
Robot.cleanup_all() # Ensure clean state
|
|
354
|
-
|
|
355
|
-
robot2 = Robot() # Safe to create new instance
|
|
356
|
-
robot2.shutdown()
|
|
357
|
-
"""
|
|
358
|
-
import gc
|
|
359
|
-
|
|
360
|
-
# Force garbage collection to clean up any remaining resources
|
|
361
|
-
gc.collect()
|
|
362
|
-
|
|
363
|
-
# Give threads time to terminate
|
|
364
|
-
time.sleep(1.0)
|
|
365
|
-
|
|
366
|
-
# Log any remaining pyo3-closure threads
|
|
367
|
-
lingering = []
|
|
368
|
-
for thread in threading.enumerate():
|
|
369
|
-
if "pyo3-closure" in thread.name and thread.is_alive():
|
|
370
|
-
lingering.append(thread.name)
|
|
371
|
-
|
|
372
|
-
if lingering:
|
|
373
|
-
logger.debug(
|
|
374
|
-
f"Zenoh threads still active after cleanup: {lingering}. "
|
|
375
|
-
"This is normal and shouldn't affect new Robot instances."
|
|
376
|
-
)
|
|
377
|
-
|
|
378
228
|
def _print_initialization_info(self, robot_model: str | None) -> None:
|
|
379
229
|
"""Print initialization information.
|
|
380
230
|
|
|
@@ -393,40 +243,114 @@ class Robot:
|
|
|
393
243
|
|
|
394
244
|
console.print(table)
|
|
395
245
|
|
|
396
|
-
def
|
|
397
|
-
"""
|
|
246
|
+
def _safe_initialize_components(self) -> None:
|
|
247
|
+
"""Safely initialize all robot components with consolidated error handling.
|
|
398
248
|
|
|
399
|
-
|
|
400
|
-
|
|
249
|
+
This method consolidates the initialization of components, sensors, and
|
|
250
|
+
default modes into a single method with unified error handling.
|
|
401
251
|
|
|
402
252
|
Raises:
|
|
403
|
-
RuntimeError: If
|
|
253
|
+
RuntimeError: If any critical initialization step fails.
|
|
404
254
|
"""
|
|
255
|
+
initialization_steps = [
|
|
256
|
+
("robot components", self._initialize_robot_components),
|
|
257
|
+
("component activation", self._wait_for_components),
|
|
258
|
+
("sensors", self._initialize_sensors),
|
|
259
|
+
("default state", self._set_default_state),
|
|
260
|
+
]
|
|
261
|
+
|
|
262
|
+
for step_name, step_function in initialization_steps:
|
|
263
|
+
try:
|
|
264
|
+
step_function()
|
|
265
|
+
except Exception as e:
|
|
266
|
+
self.shutdown()
|
|
267
|
+
raise RuntimeError(
|
|
268
|
+
f"Robot initialization failed at {step_name}: {e}"
|
|
269
|
+
) from e
|
|
270
|
+
|
|
271
|
+
def _initialize_sensors(self) -> None:
|
|
272
|
+
"""Initialize sensors and wait for activation."""
|
|
273
|
+
# Note: zenoh_session no longer needed as DexComm handles sessions
|
|
274
|
+
self.sensors = Sensors(self._configs.sensors)
|
|
275
|
+
self.sensors.wait_for_all_active()
|
|
276
|
+
|
|
277
|
+
def _initialize_robot_components(self) -> None:
|
|
278
|
+
"""Initialize robot components from configuration."""
|
|
279
|
+
config_dict = omegaconf.OmegaConf.to_container(self._configs, resolve=True)
|
|
280
|
+
config_dict = cast(dict[str, Any], config_dict)
|
|
281
|
+
|
|
282
|
+
initialized_components = []
|
|
283
|
+
failed_components = []
|
|
405
284
|
for component_name, component_config in config_dict.items():
|
|
406
285
|
if component_name == "sensors":
|
|
407
286
|
continue
|
|
408
287
|
|
|
409
|
-
|
|
410
|
-
|
|
411
|
-
|
|
412
|
-
|
|
413
|
-
|
|
414
|
-
|
|
288
|
+
try:
|
|
289
|
+
# Skip hand initialization if the hand is not present on hardware or unknown
|
|
290
|
+
if (
|
|
291
|
+
component_name in ["left_hand", "right_hand"]
|
|
292
|
+
and self._hand_types == {}
|
|
293
|
+
):
|
|
294
|
+
self._hand_types = self.query_hand_type()
|
|
295
|
+
if (
|
|
296
|
+
component_name in ["left_hand", "right_hand"]
|
|
297
|
+
and self._hand_types.get(component_name.split("_")[0])
|
|
298
|
+
== HandType.UNKNOWN
|
|
299
|
+
):
|
|
300
|
+
logger.info(
|
|
301
|
+
f"Skipping {component_name} initialization, no known hand detected."
|
|
302
|
+
)
|
|
303
|
+
continue
|
|
304
|
+
|
|
305
|
+
component_config = getattr(self._configs, str(component_name))
|
|
306
|
+
if (
|
|
307
|
+
not hasattr(component_config, "_target_")
|
|
308
|
+
or not component_config._target_
|
|
309
|
+
):
|
|
310
|
+
continue
|
|
311
|
+
|
|
312
|
+
# Create component configuration
|
|
313
|
+
temp_config = omegaconf.OmegaConf.create(
|
|
314
|
+
{
|
|
315
|
+
"_target_": component_config._target_,
|
|
316
|
+
"configs": {
|
|
317
|
+
k: v for k, v in component_config.items() if k != "_target_"
|
|
318
|
+
},
|
|
319
|
+
}
|
|
320
|
+
)
|
|
415
321
|
|
|
416
|
-
|
|
417
|
-
|
|
418
|
-
"
|
|
419
|
-
"
|
|
420
|
-
|
|
421
|
-
|
|
422
|
-
|
|
423
|
-
|
|
424
|
-
|
|
425
|
-
|
|
322
|
+
# Handle different hand types
|
|
323
|
+
if component_name in ["left_hand", "right_hand"]:
|
|
324
|
+
hand_type = self._hand_types.get(component_name.split("_")[0])
|
|
325
|
+
temp_config["hand_type"] = hand_type
|
|
326
|
+
|
|
327
|
+
# Instantiate component with error handling
|
|
328
|
+
# Note: zenoh_session no longer needed as DexComm handles sessions
|
|
329
|
+
component_instance = hydra.utils.instantiate(temp_config)
|
|
330
|
+
|
|
331
|
+
# Store component instance both as attribute and in tracking dictionaries
|
|
332
|
+
setattr(self, str(component_name), component_instance)
|
|
333
|
+
initialized_components.append(component_name)
|
|
334
|
+
|
|
335
|
+
except Exception as e:
|
|
336
|
+
logger.error(f"Failed to initialize component {component_name}: {e}")
|
|
337
|
+
failed_components.append(component_name)
|
|
338
|
+
# Continue with other components rather than failing completely
|
|
339
|
+
# Report initialization summary
|
|
340
|
+
if failed_components:
|
|
341
|
+
logger.warning(
|
|
342
|
+
f"Failed to initialize components: {', '.join(failed_components)}"
|
|
426
343
|
)
|
|
427
|
-
setattr(self, str(component_name), component_instance)
|
|
428
344
|
|
|
429
|
-
|
|
345
|
+
# Raise error only if no critical components were initialized
|
|
346
|
+
critical_components = ["left_arm", "right_arm", "head", "torso", "chassis"]
|
|
347
|
+
initialized_critical = [
|
|
348
|
+
c for c in critical_components if c in initialized_components
|
|
349
|
+
]
|
|
350
|
+
if not initialized_critical:
|
|
351
|
+
raise RuntimeError("Failed to initialize any critical components")
|
|
352
|
+
|
|
353
|
+
def _set_default_state(self) -> None:
|
|
430
354
|
"""Set default control modes for robot components.
|
|
431
355
|
|
|
432
356
|
Raises:
|
|
@@ -434,7 +358,7 @@ class Robot:
|
|
|
434
358
|
"""
|
|
435
359
|
for arm in ["left_arm", "right_arm"]:
|
|
436
360
|
if component := getattr(self, arm, None):
|
|
437
|
-
component.
|
|
361
|
+
component.set_modes(["position"] * 7)
|
|
438
362
|
|
|
439
363
|
if head := getattr(self, "head", None):
|
|
440
364
|
head.set_mode("enable")
|
|
@@ -455,14 +379,19 @@ class Robot:
|
|
|
455
379
|
component_names: Final[list[str]] = [
|
|
456
380
|
"left_arm",
|
|
457
381
|
"right_arm",
|
|
458
|
-
"left_hand",
|
|
459
|
-
"right_hand",
|
|
460
382
|
"head",
|
|
461
383
|
"chassis",
|
|
462
384
|
"torso",
|
|
463
385
|
"battery",
|
|
464
386
|
"estop",
|
|
465
387
|
]
|
|
388
|
+
|
|
389
|
+
# Only add hands to component_names if they were actually initialized
|
|
390
|
+
if hasattr(self, "left_hand"):
|
|
391
|
+
component_names.append("left_hand")
|
|
392
|
+
if hasattr(self, "right_hand"):
|
|
393
|
+
component_names.append("right_hand")
|
|
394
|
+
|
|
466
395
|
if self._configs.heartbeat.enabled:
|
|
467
396
|
component_names.append("heartbeat")
|
|
468
397
|
|
|
@@ -520,43 +449,97 @@ class Robot:
|
|
|
520
449
|
f"Other components may work, but some features, e.g. collision avoidance, may not work correctly."
|
|
521
450
|
f"Please check the robot status immediately."
|
|
522
451
|
)
|
|
452
|
+
else:
|
|
453
|
+
logger.info("All motor components are active")
|
|
523
454
|
|
|
524
|
-
|
|
455
|
+
def get_component_map(self) -> dict[str, Any]:
|
|
456
|
+
"""Get the component mapping dictionary.
|
|
525
457
|
|
|
526
|
-
|
|
527
|
-
|
|
458
|
+
Returns:
|
|
459
|
+
Dictionary mapping component names to component instances.
|
|
460
|
+
"""
|
|
461
|
+
component_map = {
|
|
462
|
+
"left_arm": getattr(self, "left_arm", None),
|
|
463
|
+
"right_arm": getattr(self, "right_arm", None),
|
|
464
|
+
"torso": getattr(self, "torso", None),
|
|
465
|
+
"head": getattr(self, "head", None),
|
|
466
|
+
}
|
|
528
467
|
|
|
529
|
-
|
|
530
|
-
|
|
468
|
+
# Only add hands if they were initialized
|
|
469
|
+
if hasattr(self, "left_hand"):
|
|
470
|
+
component_map["left_hand"] = self.left_hand
|
|
471
|
+
if hasattr(self, "right_hand"):
|
|
472
|
+
component_map["right_hand"] = self.right_hand
|
|
531
473
|
|
|
532
|
-
|
|
533
|
-
|
|
474
|
+
# Remove None values
|
|
475
|
+
return {k: v for k, v in component_map.items() if v is not None}
|
|
476
|
+
|
|
477
|
+
def validate_component_names(self, joint_pos: dict[str, Any]) -> None:
|
|
478
|
+
"""Validate that all component names are valid and initialized.
|
|
479
|
+
|
|
480
|
+
Args:
|
|
481
|
+
joint_pos: Joint position dictionary to validate.
|
|
534
482
|
|
|
535
483
|
Raises:
|
|
536
|
-
|
|
484
|
+
ValueError: If invalid component names are found with detailed guidance.
|
|
537
485
|
"""
|
|
538
|
-
|
|
539
|
-
|
|
540
|
-
if config_path is None:
|
|
541
|
-
logger.warning("Using default zenoh config settings")
|
|
542
|
-
return zenoh.open(zenoh.Config())
|
|
543
|
-
return zenoh.open(zenoh.Config.from_file(config_path))
|
|
544
|
-
except Exception as e:
|
|
545
|
-
raise RuntimeError(f"Failed to initialize zenoh session: {e}") from e
|
|
486
|
+
if not joint_pos:
|
|
487
|
+
raise ValueError("Joint position dictionary cannot be empty")
|
|
546
488
|
|
|
547
|
-
|
|
548
|
-
|
|
549
|
-
|
|
489
|
+
component_map = self.get_component_map()
|
|
490
|
+
valid_components = set(component_map.keys())
|
|
491
|
+
provided_components = set(joint_pos.keys())
|
|
492
|
+
invalid_components = provided_components - valid_components
|
|
550
493
|
|
|
551
|
-
|
|
552
|
-
|
|
494
|
+
if invalid_components:
|
|
495
|
+
available_msg = (
|
|
496
|
+
f"Available components: {', '.join(sorted(valid_components))}"
|
|
497
|
+
)
|
|
498
|
+
invalid_msg = (
|
|
499
|
+
f"Invalid component names: {', '.join(sorted(invalid_components))}"
|
|
500
|
+
)
|
|
501
|
+
|
|
502
|
+
# Provide helpful suggestions for common mistakes
|
|
503
|
+
suggestions = []
|
|
504
|
+
for invalid in invalid_components:
|
|
505
|
+
if invalid in ["left_hand", "right_hand"]:
|
|
506
|
+
suggestions.append(f"'{invalid}' may not be connected or detected")
|
|
507
|
+
elif invalid.replace("_", "") in [
|
|
508
|
+
c.replace("_", "") for c in valid_components
|
|
509
|
+
]:
|
|
510
|
+
close_match = next(
|
|
511
|
+
(
|
|
512
|
+
c
|
|
513
|
+
for c in valid_components
|
|
514
|
+
if c.replace("_", "") == invalid.replace("_", "")
|
|
515
|
+
),
|
|
516
|
+
None,
|
|
517
|
+
)
|
|
518
|
+
if close_match:
|
|
519
|
+
suggestions.append(
|
|
520
|
+
f"Did you mean '{close_match}' instead of '{invalid}'?"
|
|
521
|
+
)
|
|
522
|
+
|
|
523
|
+
error_msg = f"{invalid_msg}. {available_msg}."
|
|
524
|
+
if suggestions:
|
|
525
|
+
error_msg += f" Suggestions: {' '.join(suggestions)}"
|
|
526
|
+
|
|
527
|
+
raise ValueError(error_msg)
|
|
528
|
+
|
|
529
|
+
def _check_version_compatibility(self) -> None:
|
|
530
|
+
"""Check version compatibility between client and server.
|
|
531
|
+
|
|
532
|
+
This method uses the new JSON-based version interface to:
|
|
533
|
+
1. Compare client library version with server's minimum required version
|
|
534
|
+
2. Check server component versions for compatibility
|
|
535
|
+
3. Provide clear guidance for version mismatches
|
|
553
536
|
"""
|
|
554
|
-
|
|
555
|
-
|
|
556
|
-
|
|
557
|
-
|
|
558
|
-
|
|
559
|
-
|
|
537
|
+
try:
|
|
538
|
+
version_info = self.get_version_info(show=False)
|
|
539
|
+
check_version_compatibility(version_info)
|
|
540
|
+
except Exception as e:
|
|
541
|
+
# Log error but don't fail initialization for version check issues
|
|
542
|
+
logger.warning(f"Version compatibility check failed: {e}")
|
|
560
543
|
|
|
561
544
|
def shutdown(self) -> None:
|
|
562
545
|
"""Cleans up and closes all component connections.
|
|
@@ -569,7 +552,7 @@ class Robot:
|
|
|
569
552
|
logger.warning("Shutdown already called, skipping")
|
|
570
553
|
return
|
|
571
554
|
|
|
572
|
-
logger.info("Shutting down robot...")
|
|
555
|
+
logger.info("Shutting down robot components...")
|
|
573
556
|
self._shutdown_called = True
|
|
574
557
|
|
|
575
558
|
# Remove from active robots registry
|
|
@@ -591,9 +574,6 @@ class Robot:
|
|
|
591
574
|
f"Error stopping component {component.__class__.__name__}: {e}"
|
|
592
575
|
)
|
|
593
576
|
|
|
594
|
-
# Brief delay to ensure all stop operations complete
|
|
595
|
-
time.sleep(0.1)
|
|
596
|
-
|
|
597
577
|
# Shutdown sensors first (they may have background threads)
|
|
598
578
|
try:
|
|
599
579
|
if hasattr(self, "sensors") and self.sensors is not None:
|
|
@@ -616,78 +596,17 @@ class Robot:
|
|
|
616
596
|
# Brief delay to allow component shutdown to complete
|
|
617
597
|
time.sleep(0.1)
|
|
618
598
|
|
|
619
|
-
#
|
|
620
|
-
|
|
621
|
-
|
|
622
|
-
|
|
623
|
-
|
|
624
|
-
"""Close zenoh session in a separate thread."""
|
|
625
|
-
nonlocal zenoh_close_success, zenoh_close_exception
|
|
626
|
-
try:
|
|
627
|
-
# Brief delay for Zenoh cleanup
|
|
628
|
-
time.sleep(0.1)
|
|
629
|
-
self._zenoh_session.close()
|
|
630
|
-
zenoh_close_success = True
|
|
631
|
-
except Exception as e: # pylint: disable=broad-except
|
|
632
|
-
zenoh_close_exception = e
|
|
633
|
-
logger.warning(f"Zenoh session close error: {e}")
|
|
634
|
-
|
|
635
|
-
# Try to close zenoh session with timeout
|
|
636
|
-
close_thread = threading.Thread(target=_close_zenoh_session, daemon=True)
|
|
637
|
-
close_thread.start()
|
|
638
|
-
|
|
639
|
-
# Wait for close with reasonable timeout
|
|
640
|
-
close_timeout = 2.0
|
|
641
|
-
close_thread.join(timeout=close_timeout)
|
|
642
|
-
|
|
643
|
-
if close_thread.is_alive():
|
|
644
|
-
logger.warning(f"Zenoh session close timed out after {close_timeout}s")
|
|
645
|
-
# The thread is daemon, so it won't block the main thread
|
|
646
|
-
elif zenoh_close_success:
|
|
647
|
-
logger.debug("Zenoh session closed cleanly")
|
|
648
|
-
elif zenoh_close_exception:
|
|
649
|
-
logger.debug(
|
|
650
|
-
f"Zenoh session close completed with error: {zenoh_close_exception}"
|
|
651
|
-
)
|
|
652
|
-
|
|
653
|
-
# Give Zenoh threads more time to clean up properly
|
|
654
|
-
# This helps ensure threads terminate naturally
|
|
655
|
-
time.sleep(0.8)
|
|
656
|
-
|
|
657
|
-
# Check for lingering pyo3-closure threads
|
|
658
|
-
# These are internal Zenoh library threads
|
|
659
|
-
lingering_threads = []
|
|
660
|
-
for thread in threading.enumerate():
|
|
661
|
-
if (
|
|
662
|
-
"pyo3-closure" in thread.name
|
|
663
|
-
and thread.is_alive()
|
|
664
|
-
and not thread.daemon
|
|
665
|
-
):
|
|
666
|
-
lingering_threads.append(thread.name)
|
|
667
|
-
|
|
668
|
-
if lingering_threads:
|
|
669
|
-
logger.debug(
|
|
670
|
-
f"Note: Zenoh library threads still active: {lingering_threads}. "
|
|
671
|
-
"These are internal library threads that should not prevent creating new Robot instances."
|
|
672
|
-
)
|
|
673
|
-
|
|
674
|
-
# If this is the last robot being shutdown and we're in the main module,
|
|
675
|
-
# help the script exit cleanly
|
|
676
|
-
import sys
|
|
677
|
-
|
|
678
|
-
if (
|
|
679
|
-
not _active_robots
|
|
680
|
-
and threading.current_thread() is threading.main_thread()
|
|
681
|
-
):
|
|
682
|
-
# Check if we're likely at the end of the main script
|
|
683
|
-
frame = sys._getframe()
|
|
684
|
-
while frame.f_back:
|
|
685
|
-
frame = frame.f_back
|
|
686
|
-
# If we're at the top level of a script (not in interactive mode)
|
|
687
|
-
if frame.f_code.co_name == "<module>" and not hasattr(sys, "ps1"):
|
|
688
|
-
logger.debug("Main script ending, forcing clean exit")
|
|
689
|
-
os._exit(0)
|
|
599
|
+
# Clean up log subscriber before closing zenoh session
|
|
600
|
+
try:
|
|
601
|
+
self._log_subscriber.shutdown()
|
|
602
|
+
except Exception as e: # pylint: disable=broad-except
|
|
603
|
+
logger.debug(f"Error shutting down log subscriber: {e}")
|
|
690
604
|
|
|
605
|
+
# Cleanup DexComm shared session
|
|
606
|
+
try:
|
|
607
|
+
cleanup_session()
|
|
608
|
+
except Exception as e:
|
|
609
|
+
logger.debug(f"Session cleanup note: {e}")
|
|
691
610
|
logger.info("Robot shutdown complete")
|
|
692
611
|
|
|
693
612
|
def is_shutdown(self) -> bool:
|
|
@@ -698,209 +617,6 @@ class Robot:
|
|
|
698
617
|
"""
|
|
699
618
|
return self._shutdown_called
|
|
700
619
|
|
|
701
|
-
def query_ntp(
|
|
702
|
-
self,
|
|
703
|
-
sample_count: int = 30,
|
|
704
|
-
show: bool = False,
|
|
705
|
-
timeout: float = 1.0,
|
|
706
|
-
device: Literal["soc", "jetson"] = "soc",
|
|
707
|
-
) -> dict[Literal["success", "offset", "rtt"], bool | float]:
|
|
708
|
-
"""Query the NTP server via zenoh for time synchronization and compute robust statistics.
|
|
709
|
-
|
|
710
|
-
Args:
|
|
711
|
-
sample_count: Number of NTP samples to request (default: 50).
|
|
712
|
-
show: Whether to print summary statistics using a rich table.
|
|
713
|
-
timeout: Timeout for the zenoh querier in seconds (default: 2.0).
|
|
714
|
-
device: Which device to query for NTP ("soc" or "jetson").
|
|
715
|
-
|
|
716
|
-
Returns:
|
|
717
|
-
Dictionary with keys:
|
|
718
|
-
- "success": True if any replies were received, False otherwise.
|
|
719
|
-
- "offset": Mean offset (in seconds) after removing RTT outliers.
|
|
720
|
-
- "rtt": Mean round-trip time (in seconds) after removing RTT outliers.
|
|
721
|
-
"""
|
|
722
|
-
if device == "soc":
|
|
723
|
-
ntp_key = resolve_key_name(self._configs.soc_ntp_query_name)
|
|
724
|
-
elif device == "jetson":
|
|
725
|
-
raise NotImplementedError("Jetson NTP query is not implemented yet")
|
|
726
|
-
time_offset = []
|
|
727
|
-
time_rtt = []
|
|
728
|
-
|
|
729
|
-
querier = self._zenoh_session.declare_querier(ntp_key, timeout=timeout)
|
|
730
|
-
time.sleep(0.1)
|
|
731
|
-
|
|
732
|
-
reply_count = 0
|
|
733
|
-
for i in range(sample_count):
|
|
734
|
-
request = dexcontrol_query_pb2.NTPRequest()
|
|
735
|
-
request.client_send_time_ns = time.time_ns()
|
|
736
|
-
request.sample_count = sample_count
|
|
737
|
-
request.sample_index = i
|
|
738
|
-
replies = querier.get(payload=request.SerializeToString())
|
|
739
|
-
|
|
740
|
-
for reply in replies:
|
|
741
|
-
reply_count += 1
|
|
742
|
-
if reply.ok and reply.ok.payload:
|
|
743
|
-
client_receive_time_ns = time.time_ns()
|
|
744
|
-
response = dexcontrol_query_pb2.NTPResponse()
|
|
745
|
-
response.ParseFromString(reply.ok.payload.to_bytes())
|
|
746
|
-
t0 = request.client_send_time_ns
|
|
747
|
-
t1 = response.server_receive_time_ns
|
|
748
|
-
t2 = response.server_send_time_ns
|
|
749
|
-
t3 = client_receive_time_ns
|
|
750
|
-
offset = ((t1 - t0) + (t2 - t3)) // 2 / 1e9
|
|
751
|
-
rtt = (t3 - t0) / 1e9
|
|
752
|
-
time_offset.append(offset)
|
|
753
|
-
time_rtt.append(rtt)
|
|
754
|
-
if i < sample_count - 1:
|
|
755
|
-
time.sleep(0.01)
|
|
756
|
-
|
|
757
|
-
querier.undeclare()
|
|
758
|
-
if reply_count == 0:
|
|
759
|
-
return {"success": False, "offset": 0, "rtt": 0}
|
|
760
|
-
|
|
761
|
-
stats = compute_ntp_stats(time_offset, time_rtt)
|
|
762
|
-
offset = stats["offset (mean)"]
|
|
763
|
-
rtt = stats["round_trip_time (mean)"]
|
|
764
|
-
if show:
|
|
765
|
-
show_ntp_stats(stats)
|
|
766
|
-
|
|
767
|
-
return {"success": True, "offset": offset, "rtt": rtt}
|
|
768
|
-
|
|
769
|
-
def get_software_version(
|
|
770
|
-
self, show: bool = True
|
|
771
|
-
) -> dict[str, TYPE_SOFTWARE_VERSION]:
|
|
772
|
-
"""Retrieve software version information for all components.
|
|
773
|
-
|
|
774
|
-
Args:
|
|
775
|
-
show: Whether to display the version information.
|
|
776
|
-
|
|
777
|
-
Returns:
|
|
778
|
-
Dictionary containing version information for all components.
|
|
779
|
-
|
|
780
|
-
Raises:
|
|
781
|
-
RuntimeError: If version information cannot be retrieved.
|
|
782
|
-
"""
|
|
783
|
-
try:
|
|
784
|
-
replies = self._zenoh_session.get(
|
|
785
|
-
resolve_key_name(self._configs.version_info_name)
|
|
786
|
-
)
|
|
787
|
-
version_dict = {}
|
|
788
|
-
for reply in replies:
|
|
789
|
-
if reply.ok and reply.ok.payload:
|
|
790
|
-
version_bytes = reply.ok.payload.to_bytes()
|
|
791
|
-
version_msg = cast(
|
|
792
|
-
dexcontrol_query_pb2.SoftwareVersion,
|
|
793
|
-
dexcontrol_query_pb2.SoftwareVersion.FromString(version_bytes),
|
|
794
|
-
)
|
|
795
|
-
version_dict = software_version_to_dict(version_msg)
|
|
796
|
-
break
|
|
797
|
-
|
|
798
|
-
if show:
|
|
799
|
-
show_software_version(version_dict)
|
|
800
|
-
return version_dict
|
|
801
|
-
except Exception as e:
|
|
802
|
-
raise RuntimeError(f"Failed to retrieve software versions: {e}") from e
|
|
803
|
-
|
|
804
|
-
def get_component_status(
|
|
805
|
-
self, show: bool = True
|
|
806
|
-
) -> dict[str, dict[str, bool | ComponentStatus]]:
|
|
807
|
-
"""Retrieve status information for all components.
|
|
808
|
-
|
|
809
|
-
Args:
|
|
810
|
-
show: Whether to display the status information.
|
|
811
|
-
|
|
812
|
-
Returns:
|
|
813
|
-
Dictionary containing status information for all components.
|
|
814
|
-
|
|
815
|
-
Raises:
|
|
816
|
-
RuntimeError: If status information cannot be retrieved.
|
|
817
|
-
"""
|
|
818
|
-
try:
|
|
819
|
-
replies = self._zenoh_session.get(
|
|
820
|
-
resolve_key_name(self._configs.status_info_name)
|
|
821
|
-
)
|
|
822
|
-
status_dict = {}
|
|
823
|
-
for reply in replies:
|
|
824
|
-
if reply.ok and reply.ok.payload:
|
|
825
|
-
status_bytes = reply.ok.payload.to_bytes()
|
|
826
|
-
status_msg = cast(
|
|
827
|
-
dexcontrol_query_pb2.ComponentStates,
|
|
828
|
-
dexcontrol_query_pb2.ComponentStates.FromString(status_bytes),
|
|
829
|
-
)
|
|
830
|
-
status_dict = status_to_dict(status_msg)
|
|
831
|
-
break
|
|
832
|
-
|
|
833
|
-
if show:
|
|
834
|
-
show_component_status(status_dict)
|
|
835
|
-
return status_dict
|
|
836
|
-
except Exception as e:
|
|
837
|
-
raise RuntimeError(f"Failed to retrieve component status: {e}") from e
|
|
838
|
-
|
|
839
|
-
def reboot_component(self, part: Literal["arm", "chassis", "torso"]) -> None:
|
|
840
|
-
"""Reboot a specific robot component.
|
|
841
|
-
|
|
842
|
-
Args:
|
|
843
|
-
part: Component to reboot ("arm", "chassis", or "torso").
|
|
844
|
-
|
|
845
|
-
Raises:
|
|
846
|
-
ValueError: If the specified component is invalid.
|
|
847
|
-
RuntimeError: If the reboot operation fails.
|
|
848
|
-
"""
|
|
849
|
-
component_map = {
|
|
850
|
-
"arm": dexcontrol_query_pb2.RebootComponent.Component.ARM,
|
|
851
|
-
"chassis": dexcontrol_query_pb2.RebootComponent.Component.CHASSIS,
|
|
852
|
-
"torso": dexcontrol_query_pb2.RebootComponent.Component.TORSO,
|
|
853
|
-
}
|
|
854
|
-
|
|
855
|
-
if part not in component_map:
|
|
856
|
-
raise ValueError(f"Invalid component: {part}")
|
|
857
|
-
|
|
858
|
-
try:
|
|
859
|
-
query_msg = dexcontrol_query_pb2.RebootComponent(
|
|
860
|
-
component=component_map[part]
|
|
861
|
-
)
|
|
862
|
-
self._zenoh_session.get(
|
|
863
|
-
resolve_key_name(self._configs.reboot_query_name),
|
|
864
|
-
payload=query_msg.SerializeToString(),
|
|
865
|
-
)
|
|
866
|
-
logger.info(f"Rebooting component: {part}")
|
|
867
|
-
except Exception as e:
|
|
868
|
-
raise RuntimeError(f"Failed to reboot component {part}: {e}") from e
|
|
869
|
-
|
|
870
|
-
def clear_error(
|
|
871
|
-
self, part: Literal["left_arm", "right_arm", "chassis", "head"] | str
|
|
872
|
-
) -> None:
|
|
873
|
-
"""Clear error state for a specific component.
|
|
874
|
-
|
|
875
|
-
Args:
|
|
876
|
-
part: Component to clear error state for.
|
|
877
|
-
|
|
878
|
-
Raises:
|
|
879
|
-
ValueError: If the specified component is invalid.
|
|
880
|
-
RuntimeError: If the error clearing operation fails.
|
|
881
|
-
"""
|
|
882
|
-
component_map = {
|
|
883
|
-
"left_arm": dexcontrol_query_pb2.ClearError.Component.LEFT_ARM,
|
|
884
|
-
"right_arm": dexcontrol_query_pb2.ClearError.Component.RIGHT_ARM,
|
|
885
|
-
"chassis": dexcontrol_query_pb2.ClearError.Component.CHASSIS,
|
|
886
|
-
"head": dexcontrol_query_pb2.ClearError.Component.HEAD,
|
|
887
|
-
}
|
|
888
|
-
|
|
889
|
-
if part not in component_map:
|
|
890
|
-
raise ValueError(f"Invalid component: {part}")
|
|
891
|
-
|
|
892
|
-
try:
|
|
893
|
-
query_msg = dexcontrol_query_pb2.ClearError(component=component_map[part])
|
|
894
|
-
self._zenoh_session.get(
|
|
895
|
-
resolve_key_name(self._configs.clear_error_query_name),
|
|
896
|
-
handler=lambda reply: logger.info(f"Cleared error of {part}"),
|
|
897
|
-
payload=query_msg.SerializeToString(),
|
|
898
|
-
)
|
|
899
|
-
except Exception as e:
|
|
900
|
-
raise RuntimeError(
|
|
901
|
-
f"Failed to clear error for component {part}: {e}"
|
|
902
|
-
) from e
|
|
903
|
-
|
|
904
620
|
def get_joint_pos_dict(
|
|
905
621
|
self,
|
|
906
622
|
component: Literal[
|
|
@@ -924,14 +640,7 @@ class Robot:
|
|
|
924
640
|
KeyError: If an invalid component name is provided.
|
|
925
641
|
RuntimeError: If joint position retrieval fails.
|
|
926
642
|
"""
|
|
927
|
-
component_map =
|
|
928
|
-
"left_arm": self.left_arm,
|
|
929
|
-
"right_arm": self.right_arm,
|
|
930
|
-
"torso": self.torso,
|
|
931
|
-
"head": self.head,
|
|
932
|
-
"left_hand": self.left_hand,
|
|
933
|
-
"right_hand": self.right_hand,
|
|
934
|
-
}
|
|
643
|
+
component_map = self.get_component_map()
|
|
935
644
|
|
|
936
645
|
try:
|
|
937
646
|
if isinstance(component, str):
|
|
@@ -1021,10 +730,10 @@ class Robot:
|
|
|
1021
730
|
|
|
1022
731
|
try:
|
|
1023
732
|
start_time = time.time()
|
|
1024
|
-
component_map = self.
|
|
733
|
+
component_map = self.get_component_map()
|
|
1025
734
|
|
|
1026
735
|
# Validate component names
|
|
1027
|
-
self.
|
|
736
|
+
self.validate_component_names(joint_pos)
|
|
1028
737
|
|
|
1029
738
|
# Separate position-velocity controlled components from others
|
|
1030
739
|
pv_components = [c for c in joint_pos if c in self._pv_components]
|
|
@@ -1150,6 +859,10 @@ class Robot:
|
|
|
1150
859
|
|
|
1151
860
|
return adjusted_positions
|
|
1152
861
|
|
|
862
|
+
def have_hand(self, side: Literal["left", "right"]) -> bool:
|
|
863
|
+
"""Check if the robot has a hand."""
|
|
864
|
+
return self._hand_types.get(side) != HandType.UNKNOWN
|
|
865
|
+
|
|
1153
866
|
def _process_trajectory(
|
|
1154
867
|
self, trajectory: dict[str, np.ndarray | dict[str, np.ndarray]]
|
|
1155
868
|
) -> dict[str, dict[str, np.ndarray]]:
|
|
@@ -1215,14 +928,7 @@ class Robot:
|
|
|
1215
928
|
ValueError: If invalid component is specified.
|
|
1216
929
|
"""
|
|
1217
930
|
rate_limiter = RateLimiter(control_hz)
|
|
1218
|
-
component_map =
|
|
1219
|
-
"left_arm": self.left_arm,
|
|
1220
|
-
"right_arm": self.right_arm,
|
|
1221
|
-
"torso": self.torso,
|
|
1222
|
-
"head": self.head,
|
|
1223
|
-
"left_hand": self.left_hand,
|
|
1224
|
-
"right_hand": self.right_hand,
|
|
1225
|
-
}
|
|
931
|
+
component_map = self.get_component_map()
|
|
1226
932
|
|
|
1227
933
|
first_component = next(iter(processed_trajectory))
|
|
1228
934
|
trajectory_length = len(processed_trajectory[first_component]["position"])
|
|
@@ -1244,41 +950,6 @@ class Robot:
|
|
|
1244
950
|
)
|
|
1245
951
|
rate_limiter.sleep()
|
|
1246
952
|
|
|
1247
|
-
def _get_component_map(self) -> dict[str, Any]:
|
|
1248
|
-
"""Get the component mapping dictionary.
|
|
1249
|
-
|
|
1250
|
-
Returns:
|
|
1251
|
-
Dictionary mapping component names to component instances.
|
|
1252
|
-
"""
|
|
1253
|
-
return {
|
|
1254
|
-
"left_arm": self.left_arm,
|
|
1255
|
-
"right_arm": self.right_arm,
|
|
1256
|
-
"torso": self.torso,
|
|
1257
|
-
"head": self.head,
|
|
1258
|
-
"left_hand": self.left_hand,
|
|
1259
|
-
"right_hand": self.right_hand,
|
|
1260
|
-
}
|
|
1261
|
-
|
|
1262
|
-
def _validate_component_names(
|
|
1263
|
-
self,
|
|
1264
|
-
joint_pos: dict[str, list[float] | np.ndarray],
|
|
1265
|
-
component_map: dict[str, Any],
|
|
1266
|
-
) -> None:
|
|
1267
|
-
"""Validate that all component names are valid.
|
|
1268
|
-
|
|
1269
|
-
Args:
|
|
1270
|
-
joint_pos: Joint position dictionary.
|
|
1271
|
-
component_map: Component mapping dictionary.
|
|
1272
|
-
|
|
1273
|
-
Raises:
|
|
1274
|
-
ValueError: If invalid component names are found.
|
|
1275
|
-
"""
|
|
1276
|
-
invalid_components = set(joint_pos.keys()) - set(component_map.keys())
|
|
1277
|
-
if invalid_components:
|
|
1278
|
-
raise ValueError(
|
|
1279
|
-
f"Invalid component names: {', '.join(invalid_components)}"
|
|
1280
|
-
)
|
|
1281
|
-
|
|
1282
953
|
def _set_pv_components(
|
|
1283
954
|
self,
|
|
1284
955
|
pv_components: list[str],
|