dexcontrol 0.2.12__py3-none-any.whl → 0.3.1__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.
Potentially problematic release.
This version of dexcontrol might be problematic. Click here for more details.
- dexcontrol/__init__.py +18 -8
- dexcontrol/apps/dualsense_teleop_base.py +1 -1
- dexcontrol/comm/__init__.py +51 -0
- dexcontrol/comm/base.py +421 -0
- dexcontrol/comm/rtc.py +400 -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 +61 -37
- dexcontrol/core/chassis.py +141 -119
- dexcontrol/core/component.py +110 -59
- dexcontrol/core/hand.py +118 -85
- dexcontrol/core/head.py +18 -29
- dexcontrol/core/misc.py +327 -155
- dexcontrol/core/robot_query_interface.py +463 -0
- dexcontrol/core/torso.py +4 -8
- dexcontrol/proto/dexcontrol_msg_pb2.py +27 -39
- dexcontrol/proto/dexcontrol_msg_pb2.pyi +75 -118
- dexcontrol/proto/dexcontrol_query_pb2.py +39 -39
- dexcontrol/proto/dexcontrol_query_pb2.pyi +17 -4
- dexcontrol/robot.py +245 -574
- dexcontrol/sensors/__init__.py +1 -2
- dexcontrol/sensors/camera/__init__.py +0 -2
- dexcontrol/sensors/camera/base_camera.py +144 -0
- dexcontrol/sensors/camera/rgb_camera.py +67 -63
- dexcontrol/sensors/camera/zed_camera.py +89 -147
- dexcontrol/sensors/imu/chassis_imu.py +76 -56
- dexcontrol/sensors/imu/zed_imu.py +54 -43
- dexcontrol/sensors/lidar/rplidar.py +16 -20
- dexcontrol/sensors/manager.py +4 -11
- dexcontrol/sensors/ultrasonic.py +14 -27
- dexcontrol/utils/__init__.py +0 -11
- dexcontrol/utils/comm_helper.py +111 -0
- dexcontrol/utils/constants.py +1 -1
- dexcontrol/utils/os_utils.py +169 -1
- dexcontrol/utils/pb_utils.py +0 -22
- {dexcontrol-0.2.12.dist-info → dexcontrol-0.3.1.dist-info}/METADATA +13 -1
- dexcontrol-0.3.1.dist-info/RECORD +68 -0
- dexcontrol/config/sensors/cameras/luxonis_camera.py +0 -51
- dexcontrol/sensors/camera/luxonis_camera.py +0 -169
- 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.1.dist-info}/WHEEL +0 -0
- {dexcontrol-0.2.12.dist-info → dexcontrol-0.3.1.dist-info}/licenses/LICENSE +0 -0
|
@@ -0,0 +1,463 @@
|
|
|
1
|
+
# Copyright (C) 2025 Dexmate Inc.
|
|
2
|
+
#
|
|
3
|
+
# This software is dual-licensed:
|
|
4
|
+
#
|
|
5
|
+
# 1. GNU Affero General Public License v3.0 (AGPL-3.0)
|
|
6
|
+
# See LICENSE-AGPL for details
|
|
7
|
+
#
|
|
8
|
+
# 2. Commercial License
|
|
9
|
+
# For commercial licensing terms, contact: contact@dexmate.ai
|
|
10
|
+
|
|
11
|
+
"""Query utilities for robot communication using DexComm.
|
|
12
|
+
|
|
13
|
+
This module provides the RobotQueryInterface class that encapsulates all communication
|
|
14
|
+
queries with the robot server using DexComm's service pattern. It handles various query
|
|
15
|
+
types including hand type detection, version information, status queries, and control
|
|
16
|
+
operations.
|
|
17
|
+
"""
|
|
18
|
+
|
|
19
|
+
import json
|
|
20
|
+
import time
|
|
21
|
+
from typing import TYPE_CHECKING, Any, Literal, cast
|
|
22
|
+
|
|
23
|
+
# Use DexComm for all communication
|
|
24
|
+
from dexcomm import call_service
|
|
25
|
+
from loguru import logger
|
|
26
|
+
|
|
27
|
+
from dexcontrol.config.vega import VegaConfig, get_vega_config
|
|
28
|
+
from dexcontrol.core.hand import HandType
|
|
29
|
+
from dexcontrol.proto import dexcontrol_query_pb2
|
|
30
|
+
from dexcontrol.utils.comm_helper import get_zenoh_config_path
|
|
31
|
+
from dexcontrol.utils.os_utils import resolve_key_name
|
|
32
|
+
from dexcontrol.utils.pb_utils import (
|
|
33
|
+
ComponentStatus,
|
|
34
|
+
status_to_dict,
|
|
35
|
+
)
|
|
36
|
+
from dexcontrol.utils.viz_utils import show_component_status
|
|
37
|
+
|
|
38
|
+
if TYPE_CHECKING:
|
|
39
|
+
from dexcontrol.config.vega import VegaConfig
|
|
40
|
+
|
|
41
|
+
|
|
42
|
+
class RobotQueryInterface:
|
|
43
|
+
"""Base class for zenoh query operations.
|
|
44
|
+
|
|
45
|
+
This class provides a clean interface for all zenoh-based queries and
|
|
46
|
+
communication operations. It maintains references to the zenoh session
|
|
47
|
+
and configuration needed for queries.
|
|
48
|
+
|
|
49
|
+
Can be used as a context manager for automatic resource cleanup:
|
|
50
|
+
>>> with RobotQueryInterface.create() as interface:
|
|
51
|
+
... version_info = interface.get_version_info()
|
|
52
|
+
"""
|
|
53
|
+
|
|
54
|
+
def __init__(self, configs: "VegaConfig"):
|
|
55
|
+
"""Initialize the RobotQueryInterface.
|
|
56
|
+
|
|
57
|
+
Args:
|
|
58
|
+
configs: Robot configuration containing query names.
|
|
59
|
+
"""
|
|
60
|
+
# Session parameter kept for compatibility but not used
|
|
61
|
+
self._configs = configs
|
|
62
|
+
self._owns_session = False
|
|
63
|
+
|
|
64
|
+
@classmethod
|
|
65
|
+
def create(cls) -> "RobotQueryInterface":
|
|
66
|
+
"""Create a standalone RobotQueryInterface.
|
|
67
|
+
|
|
68
|
+
This class method provides a convenient way to create a RobotQueryInterface
|
|
69
|
+
without requiring the full Robot class. DexComm handles all session
|
|
70
|
+
management internally.
|
|
71
|
+
|
|
72
|
+
Returns:
|
|
73
|
+
RobotQueryInterface instance ready for use.
|
|
74
|
+
|
|
75
|
+
Example:
|
|
76
|
+
>>> query_interface = RobotQueryInterface.create()
|
|
77
|
+
>>> version_info = query_interface.get_version_info()
|
|
78
|
+
>>> query_interface.close()
|
|
79
|
+
"""
|
|
80
|
+
# DexComm handles session internally, we just need config
|
|
81
|
+
config: VegaConfig = get_vega_config()
|
|
82
|
+
instance = cls(config)
|
|
83
|
+
instance._owns_session = True
|
|
84
|
+
return instance
|
|
85
|
+
|
|
86
|
+
def close(self) -> None:
|
|
87
|
+
"""Close the communication session if owned by this instance.
|
|
88
|
+
|
|
89
|
+
This method should be called when done using a standalone
|
|
90
|
+
RobotQueryInterface to properly clean up resources.
|
|
91
|
+
"""
|
|
92
|
+
if self._owns_session:
|
|
93
|
+
# DexComm cleanup is handled automatically
|
|
94
|
+
logger.debug("DexComm session cleanup handled automatically")
|
|
95
|
+
|
|
96
|
+
def __enter__(self) -> "RobotQueryInterface":
|
|
97
|
+
"""Enter context manager."""
|
|
98
|
+
return self
|
|
99
|
+
|
|
100
|
+
def __exit__(self, exc_type, exc_val, exc_tb) -> None:
|
|
101
|
+
"""Exit context manager and clean up resources."""
|
|
102
|
+
self.close()
|
|
103
|
+
|
|
104
|
+
def query_hand_type(self) -> dict[str, HandType]:
|
|
105
|
+
"""Query the hand type information from the server.
|
|
106
|
+
|
|
107
|
+
Returns:
|
|
108
|
+
Dictionary containing hand type information for left and right hands.
|
|
109
|
+
Format: {"left": hand_type_name, "right": hand_type_name}
|
|
110
|
+
Possible hand types: "UNKNOWN", "HandF5D6_V1", "HandF5D6_V2"
|
|
111
|
+
UNKNOWN means not connected or unknown end effector connected.
|
|
112
|
+
|
|
113
|
+
Raises:
|
|
114
|
+
RuntimeError: If hand type information cannot be retrieved.
|
|
115
|
+
"""
|
|
116
|
+
try:
|
|
117
|
+
# Query hand type using DexComm service
|
|
118
|
+
full_topic = resolve_key_name(self._configs.hand_info_query_name)
|
|
119
|
+
|
|
120
|
+
response = call_service(
|
|
121
|
+
full_topic,
|
|
122
|
+
timeout=5.0,
|
|
123
|
+
config=get_zenoh_config_path(),
|
|
124
|
+
request_serializer=None,
|
|
125
|
+
response_deserializer=None,
|
|
126
|
+
)
|
|
127
|
+
|
|
128
|
+
if response:
|
|
129
|
+
# Parse JSON response directly
|
|
130
|
+
if isinstance(response, bytes):
|
|
131
|
+
payload_str = response.decode("utf-8")
|
|
132
|
+
else:
|
|
133
|
+
payload_str = response
|
|
134
|
+
|
|
135
|
+
hand_info = json.loads(payload_str)
|
|
136
|
+
|
|
137
|
+
# Validate the expected format
|
|
138
|
+
if isinstance(hand_info, dict):
|
|
139
|
+
logger.info(f"End effector hand types: {hand_info}")
|
|
140
|
+
return {
|
|
141
|
+
"left": HandType(hand_info["left"]),
|
|
142
|
+
"right": HandType(hand_info["right"]),
|
|
143
|
+
}
|
|
144
|
+
else:
|
|
145
|
+
logger.warning(f"Invalid hand type format received: {hand_info}")
|
|
146
|
+
|
|
147
|
+
# If no valid response received, assume v1 for backward compatibility
|
|
148
|
+
return {"left": HandType.HandF5D6_V1, "right": HandType.HandF5D6_V1}
|
|
149
|
+
|
|
150
|
+
except Exception as e:
|
|
151
|
+
logger.warning(f"Failed to query hand type: {e}. Assuming v1 hand types.")
|
|
152
|
+
return {"left": HandType.HandF5D6_V1, "right": HandType.HandF5D6_V1}
|
|
153
|
+
|
|
154
|
+
def query_ntp(
|
|
155
|
+
self,
|
|
156
|
+
sample_count: int = 30,
|
|
157
|
+
show: bool = False,
|
|
158
|
+
timeout: float = 1.0,
|
|
159
|
+
device: Literal["soc", "jetson"] = "soc",
|
|
160
|
+
) -> dict[Literal["success", "offset", "rtt"], bool | float]:
|
|
161
|
+
"""Query the NTP server via zenoh for time synchronization and compute robust statistics.
|
|
162
|
+
|
|
163
|
+
Args:
|
|
164
|
+
sample_count: Number of NTP samples to request (default: 50).
|
|
165
|
+
show: Whether to print summary statistics using a rich table.
|
|
166
|
+
timeout: Timeout for the zenoh querier in seconds (default: 2.0).
|
|
167
|
+
device: Which device to query for NTP ("soc" or "jetson").
|
|
168
|
+
|
|
169
|
+
Returns:
|
|
170
|
+
Dictionary with keys:
|
|
171
|
+
- "success": True if any replies were received, False otherwise.
|
|
172
|
+
- "offset": Mean offset (in seconds) after removing RTT outliers.
|
|
173
|
+
- "rtt": Mean round-trip time (in seconds) after removing RTT outliers.
|
|
174
|
+
"""
|
|
175
|
+
if device == "soc":
|
|
176
|
+
ntp_key = resolve_key_name(self._configs.soc_ntp_query_name)
|
|
177
|
+
elif device == "jetson":
|
|
178
|
+
raise NotImplementedError("Jetson NTP query is not implemented yet")
|
|
179
|
+
|
|
180
|
+
time_offset = []
|
|
181
|
+
time_rtt = []
|
|
182
|
+
|
|
183
|
+
reply_count = 0
|
|
184
|
+
for i in range(sample_count):
|
|
185
|
+
request = dexcontrol_query_pb2.NTPRequest()
|
|
186
|
+
request.client_send_time_ns = time.time_ns()
|
|
187
|
+
request.sample_count = sample_count
|
|
188
|
+
request.sample_index = i
|
|
189
|
+
|
|
190
|
+
# Use call_service for NTP query
|
|
191
|
+
try:
|
|
192
|
+
response_data = call_service(
|
|
193
|
+
ntp_key,
|
|
194
|
+
request=request,
|
|
195
|
+
timeout=timeout,
|
|
196
|
+
config=get_zenoh_config_path(),
|
|
197
|
+
request_serializer=lambda x: x.SerializeToString(),
|
|
198
|
+
response_deserializer=None,
|
|
199
|
+
)
|
|
200
|
+
|
|
201
|
+
if response_data:
|
|
202
|
+
reply_count += 1
|
|
203
|
+
client_receive_time_ns = time.time_ns()
|
|
204
|
+
response = dexcontrol_query_pb2.NTPResponse()
|
|
205
|
+
response.ParseFromString(response_data)
|
|
206
|
+
t0 = request.client_send_time_ns
|
|
207
|
+
t1 = response.server_receive_time_ns
|
|
208
|
+
t2 = response.server_send_time_ns
|
|
209
|
+
t3 = client_receive_time_ns
|
|
210
|
+
offset = ((t1 - t0) + (t2 - t3)) // 2 / 1e9
|
|
211
|
+
rtt = (t3 - t0) / 1e9
|
|
212
|
+
time_offset.append(offset)
|
|
213
|
+
time_rtt.append(rtt)
|
|
214
|
+
except Exception as e:
|
|
215
|
+
logger.debug(f"NTP query {i} failed: {e}")
|
|
216
|
+
|
|
217
|
+
if i < sample_count - 1:
|
|
218
|
+
time.sleep(0.01)
|
|
219
|
+
if reply_count == 0:
|
|
220
|
+
return {"success": False, "offset": 0.0, "rtt": 0.0}
|
|
221
|
+
|
|
222
|
+
# Compute simple NTP statistics
|
|
223
|
+
import numpy as np
|
|
224
|
+
|
|
225
|
+
stats = {
|
|
226
|
+
"offset (mean)": float(np.mean(time_offset)) if time_offset else 0.0,
|
|
227
|
+
"round_trip_time (mean)": float(np.mean(time_rtt)) if time_rtt else 0.0,
|
|
228
|
+
"offset (std)": float(np.std(time_offset)) if time_offset else 0.0,
|
|
229
|
+
"round_trip_time (std)": float(np.std(time_rtt)) if time_rtt else 0.0,
|
|
230
|
+
}
|
|
231
|
+
offset = float(stats["offset (mean)"])
|
|
232
|
+
rtt = float(stats["round_trip_time (mean)"])
|
|
233
|
+
if show:
|
|
234
|
+
from dexcontrol.utils.viz_utils import show_ntp_stats
|
|
235
|
+
|
|
236
|
+
show_ntp_stats(stats)
|
|
237
|
+
|
|
238
|
+
return {"success": True, "offset": offset, "rtt": rtt}
|
|
239
|
+
|
|
240
|
+
def get_version_info(self, show: bool = True) -> dict[str, Any]:
|
|
241
|
+
"""Retrieve comprehensive version information using JSON interface.
|
|
242
|
+
|
|
243
|
+
This method queries the new JSON-based version endpoint that provides:
|
|
244
|
+
- Server component versions (hardware, software, compile_time, hashes)
|
|
245
|
+
- Minimum required client version
|
|
246
|
+
- Version compatibility information
|
|
247
|
+
|
|
248
|
+
Args:
|
|
249
|
+
show: Whether to display the version information.
|
|
250
|
+
|
|
251
|
+
Returns:
|
|
252
|
+
Dictionary containing comprehensive version information with structure:
|
|
253
|
+
{
|
|
254
|
+
"server": {
|
|
255
|
+
"component_name": {
|
|
256
|
+
"hardware_version": int,
|
|
257
|
+
"software_version": int,
|
|
258
|
+
"compile_time": str,
|
|
259
|
+
"main_hash": str,
|
|
260
|
+
"sub_hash": str
|
|
261
|
+
}
|
|
262
|
+
},
|
|
263
|
+
"client": {
|
|
264
|
+
"minimal_version": str
|
|
265
|
+
}
|
|
266
|
+
}
|
|
267
|
+
|
|
268
|
+
Raises:
|
|
269
|
+
RuntimeError: If version information cannot be retrieved.
|
|
270
|
+
"""
|
|
271
|
+
try:
|
|
272
|
+
response = call_service(
|
|
273
|
+
resolve_key_name(self._configs.version_info_name),
|
|
274
|
+
timeout=5.0,
|
|
275
|
+
config=get_zenoh_config_path(),
|
|
276
|
+
request_serializer=None,
|
|
277
|
+
response_deserializer=None,
|
|
278
|
+
)
|
|
279
|
+
|
|
280
|
+
if response:
|
|
281
|
+
try:
|
|
282
|
+
# Parse JSON response directly
|
|
283
|
+
if isinstance(response, bytes):
|
|
284
|
+
payload_str = response.decode("utf-8")
|
|
285
|
+
else:
|
|
286
|
+
payload_str = response
|
|
287
|
+
version_info = json.loads(payload_str)
|
|
288
|
+
|
|
289
|
+
# Validate expected structure
|
|
290
|
+
if (
|
|
291
|
+
isinstance(version_info, dict)
|
|
292
|
+
and "server" in version_info
|
|
293
|
+
and "client" in version_info
|
|
294
|
+
):
|
|
295
|
+
if show:
|
|
296
|
+
self._show_version_info(version_info)
|
|
297
|
+
return version_info
|
|
298
|
+
else:
|
|
299
|
+
logger.warning(
|
|
300
|
+
f"Invalid version info format received: {version_info}"
|
|
301
|
+
)
|
|
302
|
+
except (json.JSONDecodeError, UnicodeDecodeError) as e:
|
|
303
|
+
logger.warning(f"Failed to parse version info response: {e}")
|
|
304
|
+
|
|
305
|
+
raise RuntimeError("No valid version information received from server")
|
|
306
|
+
|
|
307
|
+
except Exception as e:
|
|
308
|
+
raise RuntimeError(f"Failed to retrieve version information: {e}") from e
|
|
309
|
+
|
|
310
|
+
def get_component_status(
|
|
311
|
+
self, show: bool = True
|
|
312
|
+
) -> dict[str, dict[str, bool | ComponentStatus]]:
|
|
313
|
+
"""Retrieve status information for all components.
|
|
314
|
+
|
|
315
|
+
Args:
|
|
316
|
+
show: Whether to display the status information.
|
|
317
|
+
|
|
318
|
+
Returns:
|
|
319
|
+
Dictionary containing status information for all components.
|
|
320
|
+
|
|
321
|
+
Raises:
|
|
322
|
+
RuntimeError: If status information cannot be retrieved.
|
|
323
|
+
"""
|
|
324
|
+
try:
|
|
325
|
+
response = call_service(
|
|
326
|
+
resolve_key_name(self._configs.status_info_name),
|
|
327
|
+
timeout=2.0,
|
|
328
|
+
config=get_zenoh_config_path(),
|
|
329
|
+
request_serializer=None,
|
|
330
|
+
response_deserializer=None,
|
|
331
|
+
)
|
|
332
|
+
|
|
333
|
+
status_dict = {}
|
|
334
|
+
if response:
|
|
335
|
+
# Parse protobuf response directly
|
|
336
|
+
status_msg = cast(
|
|
337
|
+
dexcontrol_query_pb2.ComponentStates,
|
|
338
|
+
dexcontrol_query_pb2.ComponentStates.FromString(response),
|
|
339
|
+
)
|
|
340
|
+
status_dict = status_to_dict(status_msg)
|
|
341
|
+
|
|
342
|
+
if show:
|
|
343
|
+
show_component_status(status_dict)
|
|
344
|
+
return status_dict
|
|
345
|
+
except Exception as e:
|
|
346
|
+
raise RuntimeError(f"Failed to retrieve component status: {e}") from e
|
|
347
|
+
|
|
348
|
+
def reboot_component(
|
|
349
|
+
self,
|
|
350
|
+
part: Literal["arm", "chassis", "torso"],
|
|
351
|
+
) -> None:
|
|
352
|
+
"""Reboot a specific robot component.
|
|
353
|
+
|
|
354
|
+
Args:
|
|
355
|
+
part: Component to reboot ("arm", "chassis", or "torso").
|
|
356
|
+
|
|
357
|
+
Raises:
|
|
358
|
+
ValueError: If the specified component is invalid.
|
|
359
|
+
RuntimeError: If the reboot operation fails.
|
|
360
|
+
"""
|
|
361
|
+
component_map = {
|
|
362
|
+
"arm": dexcontrol_query_pb2.RebootComponent.Component.ARM,
|
|
363
|
+
"chassis": dexcontrol_query_pb2.RebootComponent.Component.CHASSIS,
|
|
364
|
+
"torso": dexcontrol_query_pb2.RebootComponent.Component.TORSO,
|
|
365
|
+
}
|
|
366
|
+
|
|
367
|
+
if part not in component_map:
|
|
368
|
+
raise ValueError(f"Invalid component: {part}")
|
|
369
|
+
|
|
370
|
+
try:
|
|
371
|
+
query_msg = dexcontrol_query_pb2.RebootComponent(
|
|
372
|
+
component=component_map[part]
|
|
373
|
+
)
|
|
374
|
+
|
|
375
|
+
call_service(
|
|
376
|
+
resolve_key_name(self._configs.reboot_query_name),
|
|
377
|
+
request=query_msg,
|
|
378
|
+
timeout=2.0,
|
|
379
|
+
config=get_zenoh_config_path(),
|
|
380
|
+
request_serializer=lambda x: x.SerializeToString(),
|
|
381
|
+
response_deserializer=None,
|
|
382
|
+
)
|
|
383
|
+
logger.info(f"Rebooting component: {part}")
|
|
384
|
+
except Exception as e:
|
|
385
|
+
raise RuntimeError(f"Failed to reboot component {part}: {e}") from e
|
|
386
|
+
|
|
387
|
+
def clear_error(
|
|
388
|
+
self,
|
|
389
|
+
part: Literal["left_arm", "right_arm", "chassis", "head"] | str,
|
|
390
|
+
) -> None:
|
|
391
|
+
"""Clear error state for a specific component.
|
|
392
|
+
|
|
393
|
+
Args:
|
|
394
|
+
part: Component to clear error state for.
|
|
395
|
+
|
|
396
|
+
Raises:
|
|
397
|
+
ValueError: If the specified component is invalid.
|
|
398
|
+
RuntimeError: If the error clearing operation fails.
|
|
399
|
+
"""
|
|
400
|
+
component_map = {
|
|
401
|
+
"left_arm": dexcontrol_query_pb2.ClearError.Component.LEFT_ARM,
|
|
402
|
+
"right_arm": dexcontrol_query_pb2.ClearError.Component.RIGHT_ARM,
|
|
403
|
+
"chassis": dexcontrol_query_pb2.ClearError.Component.CHASSIS,
|
|
404
|
+
"head": dexcontrol_query_pb2.ClearError.Component.HEAD,
|
|
405
|
+
}
|
|
406
|
+
|
|
407
|
+
if part not in component_map:
|
|
408
|
+
raise ValueError(f"Invalid component: {part}")
|
|
409
|
+
|
|
410
|
+
try:
|
|
411
|
+
query_msg = dexcontrol_query_pb2.ClearError(component=component_map[part])
|
|
412
|
+
|
|
413
|
+
call_service(
|
|
414
|
+
resolve_key_name(self._configs.clear_error_query_name),
|
|
415
|
+
request=query_msg,
|
|
416
|
+
timeout=2.0,
|
|
417
|
+
config=get_zenoh_config_path(),
|
|
418
|
+
request_serializer=lambda x: x.SerializeToString(),
|
|
419
|
+
response_deserializer=None,
|
|
420
|
+
)
|
|
421
|
+
logger.info(f"Cleared error of {part}")
|
|
422
|
+
except Exception as e:
|
|
423
|
+
raise RuntimeError(
|
|
424
|
+
f"Failed to clear error for component {part}: {e}"
|
|
425
|
+
) from e
|
|
426
|
+
|
|
427
|
+
def _show_version_info(self, version_info: dict[str, Any]) -> None:
|
|
428
|
+
"""Display comprehensive version information in a formatted table.
|
|
429
|
+
|
|
430
|
+
Args:
|
|
431
|
+
version_info: Dictionary containing server and client version information.
|
|
432
|
+
"""
|
|
433
|
+
from rich.console import Console
|
|
434
|
+
from rich.table import Table
|
|
435
|
+
|
|
436
|
+
console = Console()
|
|
437
|
+
table = Table(title="🤖 Robot System Version Information")
|
|
438
|
+
|
|
439
|
+
table.add_column("Component", justify="left", style="cyan", no_wrap=True)
|
|
440
|
+
table.add_column("Hardware Ver.", justify="center", style="magenta")
|
|
441
|
+
table.add_column("Software Ver.", justify="center", style="green")
|
|
442
|
+
table.add_column("Compile Time", justify="center", style="yellow")
|
|
443
|
+
table.add_column("Main Hash", justify="center", style="blue")
|
|
444
|
+
table.add_column("Sub Hash", justify="center", style="red")
|
|
445
|
+
|
|
446
|
+
# Display server components
|
|
447
|
+
server_info = version_info.get("server", {})
|
|
448
|
+
for component, info in server_info.items():
|
|
449
|
+
if isinstance(info, dict):
|
|
450
|
+
table.add_row(
|
|
451
|
+
component,
|
|
452
|
+
str(info.get("hardware_version", "N/A")),
|
|
453
|
+
str(info.get("software_version", "N/A")),
|
|
454
|
+
str(info.get("compile_time", "N/A")),
|
|
455
|
+
str(info.get("main_hash", "N/A")[:8])
|
|
456
|
+
if info.get("main_hash")
|
|
457
|
+
else "N/A",
|
|
458
|
+
str(info.get("sub_hash", "N/A")[:8])
|
|
459
|
+
if info.get("sub_hash")
|
|
460
|
+
else "N/A",
|
|
461
|
+
)
|
|
462
|
+
|
|
463
|
+
console.print(table)
|
dexcontrol/core/torso.py
CHANGED
|
@@ -15,7 +15,6 @@ communication. It handles joint position and velocity control and state monitori
|
|
|
15
15
|
"""
|
|
16
16
|
|
|
17
17
|
import numpy as np
|
|
18
|
-
import zenoh
|
|
19
18
|
from jaxtyping import Float
|
|
20
19
|
|
|
21
20
|
from dexcontrol.config.core import TorsoConfig
|
|
@@ -37,20 +36,17 @@ class Torso(RobotJointComponent):
|
|
|
37
36
|
def __init__(
|
|
38
37
|
self,
|
|
39
38
|
configs: TorsoConfig,
|
|
40
|
-
zenoh_session: zenoh.Session,
|
|
41
39
|
) -> None:
|
|
42
40
|
"""Initialize the torso controller.
|
|
43
41
|
|
|
44
42
|
Args:
|
|
45
43
|
configs: Torso configuration parameters containing communication topics
|
|
46
44
|
and default velocity settings.
|
|
47
|
-
zenoh_session: Active Zenoh communication session for message passing.
|
|
48
45
|
"""
|
|
49
46
|
super().__init__(
|
|
50
47
|
state_sub_topic=configs.state_sub_topic,
|
|
51
48
|
control_pub_topic=configs.control_pub_topic,
|
|
52
|
-
state_message_type=dexcontrol_msg_pb2.
|
|
53
|
-
zenoh_session=zenoh_session,
|
|
49
|
+
state_message_type=dexcontrol_msg_pb2.MotorStateWithCurrent,
|
|
54
50
|
joint_name=configs.joint_name,
|
|
55
51
|
joint_limit=configs.joint_limit
|
|
56
52
|
if hasattr(configs, "joint_limit")
|
|
@@ -119,9 +115,9 @@ class Torso(RobotJointComponent):
|
|
|
119
115
|
)
|
|
120
116
|
|
|
121
117
|
# Create and send control message
|
|
122
|
-
control_msg = dexcontrol_msg_pb2.
|
|
123
|
-
control_msg.
|
|
124
|
-
control_msg.
|
|
118
|
+
control_msg = dexcontrol_msg_pb2.MotorPosVelCommand()
|
|
119
|
+
control_msg.pos.extend(joint_pos.tolist())
|
|
120
|
+
control_msg.vel.extend(joint_vel.tolist())
|
|
125
121
|
self._publish_control(control_msg)
|
|
126
122
|
|
|
127
123
|
# Wait if specified
|
|
@@ -25,49 +25,37 @@ _sym_db = _symbol_database.Default()
|
|
|
25
25
|
|
|
26
26
|
|
|
27
27
|
|
|
28
|
-
DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x14\x64\x65xcontrol_msg.proto\x12\ndexcontrol\"
|
|
28
|
+
DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x14\x64\x65xcontrol_msg.proto\x12\ndexcontrol\"e\n\x14MotorStateWithTorque\x12\x0b\n\x03pos\x18\x01 \x03(\x02\x12\x0b\n\x03vel\x18\x02 \x03(\x02\x12\x0e\n\x06torque\x18\x03 \x03(\x02\x12\r\n\x05\x65rror\x18\x04 \x03(\r\x12\x14\n\x0ctimestamp_ns\x18\x05 \x01(\x04\"c\n\x15MotorStateWithCurrent\x12\x0b\n\x03pos\x18\x01 \x03(\x02\x12\x0b\n\x03vel\x18\x02 \x03(\x02\x12\x0b\n\x03\x63ur\x18\x03 \x03(\x02\x12\r\n\x05\x65rror\x18\x04 \x03(\r\x12\x14\n\x0ctimestamp_ns\x18\x05 \x01(\x04\"4\n\x0fMotorPosCommand\x12\x0b\n\x03pos\x18\x01 \x03(\x02\x12\x14\n\x0ctimestamp_ns\x18\x02 \x01(\x04\"4\n\x0fMotorVelCommand\x12\x0b\n\x03vel\x18\x01 \x03(\x02\x12\x14\n\x0ctimestamp_ns\x18\x02 \x01(\x04\"D\n\x12MotorPosVelCommand\x12\x0b\n\x03pos\x18\x01 \x03(\x02\x12\x0b\n\x03vel\x18\x02 \x03(\x02\x12\x14\n\x0ctimestamp_ns\x18\x03 \x01(\x04\"X\n\x19MotorPosVelCurrentCommand\x12\x0b\n\x03pos\x18\x01 \x03(\x02\x12\x0b\n\x03vel\x18\x02 \x03(\x02\x12\x0b\n\x03\x63ur\x18\x03 \x03(\x02\x12\x14\n\x0ctimestamp_ns\x18\x04 \x01(\x04\"C\n\x1d\x45ndEffectorPassThroughCommand\x12\x0c\n\x04\x64\x61ta\x18\x01 \x01(\x0c\x12\x14\n\x0ctimestamp_ns\x18\x02 \x01(\x04\"\x8f\x01\n\x08\x42MSState\x12\x0f\n\x07voltage\x18\x01 \x01(\x02\x12\x0f\n\x07\x63urrent\x18\x02 \x01(\x02\x12\x13\n\x0btemperature\x18\x03 \x01(\x02\x12\x12\n\npercentage\x18\x04 \x01(\r\x12\x13\n\x0bis_charging\x18\x05 \x01(\x08\x12\r\n\x05\x65rror\x18\x06 \x01(\r\x12\x14\n\x0ctimestamp_ns\x18\x07 \x01(\x04\"^\n\x0bWrenchState\x12\x0e\n\x06wrench\x18\x01 \x03(\x02\x12\x13\n\x0b\x62lue_button\x18\x02 \x01(\x08\x12\x14\n\x0cgreen_button\x18\x03 \x01(\x08\x12\x14\n\x0ctimestamp_ns\x18\x04 \x01(\x04\"\xbc\x01\n\nEStopState\x12\x1e\n\x16software_estop_enabled\x18\x01 \x01(\x08\x12\x1b\n\x13left_button_pressed\x18\x02 \x01(\x08\x12\x1c\n\x14right_button_pressed\x18\x03 \x01(\x08\x12\x1c\n\x14waist_button_pressed\x18\x04 \x01(\x08\x12\x1f\n\x17wireless_button_pressed\x18\x05 \x01(\x08\x12\x14\n\x0ctimestamp_ns\x18\x06 \x01(\x04\"w\n\x0fUltrasonicState\x12\x12\n\nfront_left\x18\x01 \x01(\x02\x12\x13\n\x0b\x66ront_right\x18\x02 \x01(\x02\x12\x11\n\tback_left\x18\x03 \x01(\x02\x12\x12\n\nback_right\x18\x04 \x01(\x02\x12\x14\n\x0ctimestamp_ns\x18\x05 \x01(\x04\"\xbd\x01\n\x08IMUState\x12\r\n\x05\x61\x63\x63_x\x18\x01 \x01(\x02\x12\r\n\x05\x61\x63\x63_y\x18\x02 \x01(\x02\x12\r\n\x05\x61\x63\x63_z\x18\x03 \x01(\x02\x12\x0e\n\x06gyro_x\x18\x04 \x01(\x02\x12\x0e\n\x06gyro_y\x18\x05 \x01(\x02\x12\x0e\n\x06gyro_z\x18\x06 \x01(\x02\x12\x0e\n\x06quat_w\x18\x07 \x01(\x02\x12\x0e\n\x06quat_x\x18\x08 \x01(\x02\x12\x0e\n\x06quat_y\x18\t \x01(\x02\x12\x0e\n\x06quat_z\x18\n \x01(\x02\x12\x14\n\x0ctimestamp_ns\x18\x0b \x01(\x04\";\n\x14HandTouchSensorState\x12\r\n\x05\x66orce\x18\x01 \x03(\x02\x12\x14\n\x0ctimestamp_ns\x18\x02 \x01(\x04\x62\x06proto3')
|
|
29
29
|
|
|
30
30
|
_globals = globals()
|
|
31
31
|
_builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals)
|
|
32
32
|
_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'dexcontrol_msg_pb2', _globals)
|
|
33
33
|
if not _descriptor._USE_C_DESCRIPTORS:
|
|
34
34
|
DESCRIPTOR._loaded_options = None
|
|
35
|
-
_globals['
|
|
36
|
-
_globals['
|
|
37
|
-
_globals['
|
|
38
|
-
_globals['
|
|
39
|
-
_globals['
|
|
40
|
-
_globals['
|
|
41
|
-
_globals['
|
|
42
|
-
_globals['
|
|
43
|
-
_globals['
|
|
44
|
-
_globals['
|
|
45
|
-
_globals['
|
|
46
|
-
_globals['
|
|
47
|
-
_globals['
|
|
48
|
-
_globals['
|
|
49
|
-
_globals['
|
|
50
|
-
_globals['
|
|
51
|
-
_globals['
|
|
52
|
-
_globals['
|
|
53
|
-
_globals['
|
|
54
|
-
_globals['
|
|
55
|
-
_globals['
|
|
56
|
-
_globals['
|
|
57
|
-
_globals['
|
|
58
|
-
_globals['
|
|
59
|
-
_globals['
|
|
60
|
-
_globals['
|
|
61
|
-
_globals['_HANDCOMMAND']._serialized_start=1426
|
|
62
|
-
_globals['_HANDCOMMAND']._serialized_end=1458
|
|
63
|
-
_globals['_HEADCOMMAND']._serialized_start=1460
|
|
64
|
-
_globals['_HEADCOMMAND']._serialized_end=1511
|
|
65
|
-
_globals['_TORSOCOMMAND']._serialized_start=1513
|
|
66
|
-
_globals['_TORSOCOMMAND']._serialized_end=1565
|
|
67
|
-
_globals['_SINGLEWHEELCOMMAND']._serialized_start=1567
|
|
68
|
-
_globals['_SINGLEWHEELCOMMAND']._serialized_end=1628
|
|
69
|
-
_globals['_CHASSISCOMMAND']._serialized_start=1630
|
|
70
|
-
_globals['_CHASSISCOMMAND']._serialized_end=1739
|
|
71
|
-
_globals['_ENDEFFECTORPASSTHROUGHCOMMAND']._serialized_start=1741
|
|
72
|
-
_globals['_ENDEFFECTORPASSTHROUGHCOMMAND']._serialized_end=1786
|
|
35
|
+
_globals['_MOTORSTATEWITHTORQUE']._serialized_start=36
|
|
36
|
+
_globals['_MOTORSTATEWITHTORQUE']._serialized_end=137
|
|
37
|
+
_globals['_MOTORSTATEWITHCURRENT']._serialized_start=139
|
|
38
|
+
_globals['_MOTORSTATEWITHCURRENT']._serialized_end=238
|
|
39
|
+
_globals['_MOTORPOSCOMMAND']._serialized_start=240
|
|
40
|
+
_globals['_MOTORPOSCOMMAND']._serialized_end=292
|
|
41
|
+
_globals['_MOTORVELCOMMAND']._serialized_start=294
|
|
42
|
+
_globals['_MOTORVELCOMMAND']._serialized_end=346
|
|
43
|
+
_globals['_MOTORPOSVELCOMMAND']._serialized_start=348
|
|
44
|
+
_globals['_MOTORPOSVELCOMMAND']._serialized_end=416
|
|
45
|
+
_globals['_MOTORPOSVELCURRENTCOMMAND']._serialized_start=418
|
|
46
|
+
_globals['_MOTORPOSVELCURRENTCOMMAND']._serialized_end=506
|
|
47
|
+
_globals['_ENDEFFECTORPASSTHROUGHCOMMAND']._serialized_start=508
|
|
48
|
+
_globals['_ENDEFFECTORPASSTHROUGHCOMMAND']._serialized_end=575
|
|
49
|
+
_globals['_BMSSTATE']._serialized_start=578
|
|
50
|
+
_globals['_BMSSTATE']._serialized_end=721
|
|
51
|
+
_globals['_WRENCHSTATE']._serialized_start=723
|
|
52
|
+
_globals['_WRENCHSTATE']._serialized_end=817
|
|
53
|
+
_globals['_ESTOPSTATE']._serialized_start=820
|
|
54
|
+
_globals['_ESTOPSTATE']._serialized_end=1008
|
|
55
|
+
_globals['_ULTRASONICSTATE']._serialized_start=1010
|
|
56
|
+
_globals['_ULTRASONICSTATE']._serialized_end=1129
|
|
57
|
+
_globals['_IMUSTATE']._serialized_start=1132
|
|
58
|
+
_globals['_IMUSTATE']._serialized_end=1321
|
|
59
|
+
_globals['_HANDTOUCHSENSORSTATE']._serialized_start=1323
|
|
60
|
+
_globals['_HANDTOUCHSENSORSTATE']._serialized_end=1382
|
|
73
61
|
# @@protoc_insertion_point(module_scope)
|