dexcontrol 0.2.10__py3-none-any.whl → 0.2.12__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 +1 -0
- dexcontrol/config/core/arm.py +5 -1
- dexcontrol/config/core/hand.py +1 -1
- dexcontrol/config/core/head.py +7 -8
- dexcontrol/config/core/misc.py +14 -1
- dexcontrol/config/core/torso.py +8 -4
- dexcontrol/config/sensors/cameras/__init__.py +2 -1
- dexcontrol/config/sensors/cameras/luxonis_camera.py +51 -0
- dexcontrol/config/sensors/cameras/rgb_camera.py +1 -1
- dexcontrol/config/sensors/cameras/zed_camera.py +2 -2
- dexcontrol/config/sensors/vega_sensors.py +9 -1
- dexcontrol/config/vega.py +30 -2
- dexcontrol/core/arm.py +71 -46
- dexcontrol/core/component.py +41 -4
- dexcontrol/core/head.py +35 -23
- dexcontrol/core/misc.py +94 -13
- dexcontrol/core/torso.py +24 -6
- dexcontrol/proto/dexcontrol_msg_pb2.py +38 -36
- dexcontrol/proto/dexcontrol_msg_pb2.pyi +48 -20
- dexcontrol/proto/dexcontrol_query_pb2.py +7 -3
- dexcontrol/proto/dexcontrol_query_pb2.pyi +24 -0
- dexcontrol/robot.py +232 -68
- dexcontrol/sensors/__init__.py +2 -1
- dexcontrol/sensors/camera/__init__.py +2 -0
- dexcontrol/sensors/camera/luxonis_camera.py +169 -0
- dexcontrol/sensors/camera/zed_camera.py +17 -8
- dexcontrol/sensors/imu/chassis_imu.py +5 -1
- dexcontrol/sensors/imu/zed_imu.py +3 -2
- dexcontrol/sensors/lidar/rplidar.py +1 -0
- dexcontrol/sensors/manager.py +3 -0
- dexcontrol/utils/constants.py +3 -0
- dexcontrol/utils/error_code.py +236 -0
- dexcontrol/utils/subscribers/lidar.py +1 -0
- dexcontrol/utils/trajectory_utils.py +17 -5
- dexcontrol/utils/viz_utils.py +86 -11
- dexcontrol/utils/zenoh_utils.py +39 -0
- {dexcontrol-0.2.10.dist-info → dexcontrol-0.2.12.dist-info}/METADATA +4 -2
- dexcontrol-0.2.12.dist-info/RECORD +75 -0
- dexcontrol-0.2.10.dist-info/RECORD +0 -72
- {dexcontrol-0.2.10.dist-info → dexcontrol-0.2.12.dist-info}/WHEEL +0 -0
- {dexcontrol-0.2.10.dist-info → dexcontrol-0.2.12.dist-info}/licenses/LICENSE +0 -0
dexcontrol/__init__.py
CHANGED
|
@@ -32,6 +32,7 @@ from dexcontrol.utils.constants import COMM_CFG_PATH_ENV_VAR
|
|
|
32
32
|
# Package-level constants
|
|
33
33
|
LIB_PATH: Final[Path] = Path(__file__).resolve().parent
|
|
34
34
|
CFG_PATH: Final[Path] = LIB_PATH / "config"
|
|
35
|
+
MIN_SOC_SOFTWARE_VERSION: int = 233
|
|
35
36
|
|
|
36
37
|
logger.configure(handlers=[{"sink": RichHandler(markup=True), "format": "{message}"}])
|
|
37
38
|
|
dexcontrol/config/core/arm.py
CHANGED
|
@@ -20,8 +20,8 @@ class ArmConfig:
|
|
|
20
20
|
wrench_sub_topic: str = "state/wrench/right"
|
|
21
21
|
control_pub_topic: str = "control/arm/right"
|
|
22
22
|
set_mode_query: str = "mode/arm/right"
|
|
23
|
+
ee_pass_through_pub_topic: str = "control/ee_pass_through/right"
|
|
23
24
|
dof: int = 7
|
|
24
|
-
default_max_vel: float = 2.0 # do not go over 3.0
|
|
25
25
|
default_control_hz: int = 100
|
|
26
26
|
joint_name: list[str] = field(
|
|
27
27
|
default_factory=lambda: [f"R_arm_j{i + 1}" for i in range(7)]
|
|
@@ -29,11 +29,15 @@ class ArmConfig:
|
|
|
29
29
|
joint_limit: list[list[float]] = field(
|
|
30
30
|
default_factory=lambda: [[-np.pi, np.pi] for _ in range(7)]
|
|
31
31
|
)
|
|
32
|
+
joint_vel_limit: list[float] = field(
|
|
33
|
+
default_factory=lambda: [2.4, 2.4, 2.7, 2.7, 2.7, 2.7, 2.7]
|
|
34
|
+
)
|
|
32
35
|
pose_pool: dict[str, list[float]] = field(
|
|
33
36
|
default_factory=lambda: {
|
|
34
37
|
"folded": [-1.57079, 0.0, 0, -3.1, 0, 0, 0.69813],
|
|
35
38
|
"folded_closed_hand": [-1.57079, 0.0, 0, -3.1, 0, 0, 0.9],
|
|
36
39
|
"L_shape": [-0.064, 0.3, 0.0, -1.556, -1.271, 0.0, 0.0],
|
|
40
|
+
"lift_up": [-0.064, 0.3, 0.0, -2.756, -1.271, 0.0, 0.0],
|
|
37
41
|
"zero": [1.57079, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
|
|
38
42
|
}
|
|
39
43
|
)
|
dexcontrol/config/core/hand.py
CHANGED
|
@@ -31,6 +31,6 @@ class HandConfig:
|
|
|
31
31
|
pose_pool: dict[str, list[float]] = field(
|
|
32
32
|
default_factory=lambda: {
|
|
33
33
|
"open": [0.1834, 0.2891, 0.2801, 0.284, 0.2811, -0.0158],
|
|
34
|
-
"close": [-0.
|
|
34
|
+
"close": [-0.2668, -1.0946, -1.0844, -1.0154, -1.0118, 1.6],
|
|
35
35
|
}
|
|
36
36
|
)
|
dexcontrol/config/core/head.py
CHANGED
|
@@ -21,15 +21,14 @@ class HeadConfig:
|
|
|
21
21
|
default_factory=lambda: ["head_j1", "head_j2", "head_j3"]
|
|
22
22
|
)
|
|
23
23
|
dof: int = 3
|
|
24
|
-
|
|
25
|
-
|
|
26
|
-
|
|
24
|
+
joint_limit: list[list[float]] = field(
|
|
25
|
+
default_factory=lambda: [
|
|
26
|
+
[-1.2217, 1.2217],
|
|
27
|
+
[-2.7925, 2.7925],
|
|
28
|
+
[-1.396, 1.396],
|
|
29
|
+
]
|
|
27
30
|
)
|
|
28
|
-
|
|
29
|
-
default_factory=lambda: [1.2217, 2.7925, 1.396]
|
|
30
|
-
)
|
|
31
|
-
default_vel: float = 1.57
|
|
32
|
-
max_vel: float = 2.0
|
|
31
|
+
joint_vel_limit: list[float] = field(default_factory=lambda: [2.5, 2.5, 2.5])
|
|
33
32
|
pose_pool: dict[str, list[float]] = field(
|
|
34
33
|
default_factory=lambda: {
|
|
35
34
|
"home": [0.0, 0.0, 0.0],
|
dexcontrol/config/core/misc.py
CHANGED
|
@@ -13,7 +13,10 @@
|
|
|
13
13
|
import os
|
|
14
14
|
from dataclasses import dataclass
|
|
15
15
|
|
|
16
|
-
from dexcontrol.utils.constants import
|
|
16
|
+
from dexcontrol.utils.constants import (
|
|
17
|
+
DISABLE_ESTOP_CHECKING_ENV_VAR,
|
|
18
|
+
DISABLE_HEARTBEAT_ENV_VAR,
|
|
19
|
+
)
|
|
17
20
|
|
|
18
21
|
|
|
19
22
|
@dataclass
|
|
@@ -27,6 +30,16 @@ class EStopConfig:
|
|
|
27
30
|
_target_: str = "dexcontrol.core.misc.EStop"
|
|
28
31
|
state_sub_topic: str = "state/estop"
|
|
29
32
|
estop_query_name: str = "system/estop"
|
|
33
|
+
enabled: bool = True # Can be disabled via DEXCONTROL_DISABLE_ESTOP_CHECKING=1
|
|
34
|
+
|
|
35
|
+
def __post_init__(self):
|
|
36
|
+
"""Check environment variable to disable estop checking."""
|
|
37
|
+
if os.getenv(DISABLE_ESTOP_CHECKING_ENV_VAR, "0").lower() in (
|
|
38
|
+
"1",
|
|
39
|
+
"true",
|
|
40
|
+
"yes",
|
|
41
|
+
):
|
|
42
|
+
self.enabled = False
|
|
30
43
|
|
|
31
44
|
|
|
32
45
|
@dataclass
|
dexcontrol/config/core/torso.py
CHANGED
|
@@ -20,10 +20,14 @@ class TorsoConfig:
|
|
|
20
20
|
joint_name: list[str] = field(
|
|
21
21
|
default_factory=lambda: ["torso_j1", "torso_j2", "torso_j3"]
|
|
22
22
|
)
|
|
23
|
-
|
|
24
|
-
|
|
25
|
-
|
|
26
|
-
|
|
23
|
+
joint_limit: list[list[float]] = field(
|
|
24
|
+
default_factory=lambda: [
|
|
25
|
+
[0, 1.570],
|
|
26
|
+
[0, 3.141],
|
|
27
|
+
[-1.570, 1.570],
|
|
28
|
+
]
|
|
29
|
+
)
|
|
30
|
+
joint_vel_limit: list[float] = field(default_factory=lambda: [0.6, 0.6, 0.6])
|
|
27
31
|
pose_pool: dict[str, list[float]] = field(
|
|
28
32
|
default_factory=lambda: {
|
|
29
33
|
"home": [0.0, 0.0, 0.0],
|
|
@@ -8,7 +8,8 @@
|
|
|
8
8
|
# 2. Commercial License
|
|
9
9
|
# For commercial licensing terms, contact: contact@dexmate.ai
|
|
10
10
|
|
|
11
|
+
from .luxonis_camera import LuxonisCameraConfig
|
|
11
12
|
from .rgb_camera import RGBCameraConfig
|
|
12
13
|
from .zed_camera import ZedCameraConfig
|
|
13
14
|
|
|
14
|
-
__all__ = ["RGBCameraConfig", "ZedCameraConfig"]
|
|
15
|
+
__all__ = ["RGBCameraConfig", "ZedCameraConfig", "LuxonisCameraConfig"]
|
|
@@ -0,0 +1,51 @@
|
|
|
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
|
+
from dataclasses import dataclass, field
|
|
12
|
+
|
|
13
|
+
|
|
14
|
+
@dataclass
|
|
15
|
+
class LuxonisCameraConfig:
|
|
16
|
+
"""Configuration for LuxonisCameraSensor (wrist camera).
|
|
17
|
+
|
|
18
|
+
Attributes:
|
|
19
|
+
_target_: Target sensor class for Hydra instantiation.
|
|
20
|
+
name: Logical name of the camera.
|
|
21
|
+
enable: Whether this sensor is enabled.
|
|
22
|
+
enable_fps_tracking: Enable FPS tracking logs.
|
|
23
|
+
fps_log_interval: Frames between FPS logs.
|
|
24
|
+
subscriber_config: Topics for RGB and Depth Zenoh subscribers.
|
|
25
|
+
"""
|
|
26
|
+
|
|
27
|
+
_target_: str = "dexcontrol.sensors.camera.luxonis_camera.LuxonisCameraSensor"
|
|
28
|
+
name: str = "wrist_camera"
|
|
29
|
+
enable: bool = False
|
|
30
|
+
enable_fps_tracking: bool = False
|
|
31
|
+
fps_log_interval: int = 30
|
|
32
|
+
|
|
33
|
+
# Note: Resolution is set by the publisher (dexsensor). The publisher now defaults
|
|
34
|
+
# to 720p to match common Luxonis sensor capabilities (e.g., OV9782 supports 720p/800p).
|
|
35
|
+
# These subscribers only define topics to consume.
|
|
36
|
+
subscriber_config: dict = field(
|
|
37
|
+
default_factory=lambda: {
|
|
38
|
+
"left_rgb": {
|
|
39
|
+
"enable": True,
|
|
40
|
+
"topic": "camera/wrist/left_rgb",
|
|
41
|
+
},
|
|
42
|
+
"right_rgb": {
|
|
43
|
+
"enable": True,
|
|
44
|
+
"topic": "camera/wrist/right_rgb",
|
|
45
|
+
},
|
|
46
|
+
"depth": {
|
|
47
|
+
"enable": False,
|
|
48
|
+
"topic": "camera/wrist/depth",
|
|
49
|
+
},
|
|
50
|
+
}
|
|
51
|
+
)
|
|
@@ -19,7 +19,7 @@ class RGBCameraConfig:
|
|
|
19
19
|
_target_: The target class to instantiate.
|
|
20
20
|
name: A unique name for the sensor instance.
|
|
21
21
|
enable: Whether the sensor is enabled.
|
|
22
|
-
use_rtc: If True, uses the
|
|
22
|
+
use_rtc: If True, uses the RTCSubscriber. If False,
|
|
23
23
|
uses the standard RGBCameraSubscriber with a Zenoh topic.
|
|
24
24
|
enable_fps_tracking: If True, tracks and logs the FPS of the stream.
|
|
25
25
|
fps_log_interval: The interval in seconds for logging FPS.
|
|
@@ -19,7 +19,7 @@ class ZedCameraConfig:
|
|
|
19
19
|
_target_: The target class to instantiate.
|
|
20
20
|
name: A unique name for the sensor instance.
|
|
21
21
|
enable: Whether the sensor is enabled.
|
|
22
|
-
use_rtc: If True, RGB streams use the
|
|
22
|
+
use_rtc: If True, RGB streams use the RTCSubscriber.
|
|
23
23
|
If False, they use the standard RGBCameraSubscriber. Depth
|
|
24
24
|
always uses a standard Zenoh subscriber.
|
|
25
25
|
enable_fps_tracking: If True, tracks and logs the FPS of all streams.
|
|
@@ -31,7 +31,7 @@ class ZedCameraConfig:
|
|
|
31
31
|
_target_: str = "dexcontrol.sensors.camera.zed_camera.ZedCameraSensor"
|
|
32
32
|
name: str = "zed_camera"
|
|
33
33
|
enable: bool = False
|
|
34
|
-
use_rtc: bool =
|
|
34
|
+
use_rtc: bool = False
|
|
35
35
|
enable_fps_tracking: bool = False
|
|
36
36
|
fps_log_interval: int = 30
|
|
37
37
|
|
|
@@ -18,7 +18,7 @@ LiDAR and ultrasonic sensors.
|
|
|
18
18
|
from collections.abc import Callable
|
|
19
19
|
from dataclasses import dataclass, field
|
|
20
20
|
|
|
21
|
-
from .cameras import RGBCameraConfig, ZedCameraConfig
|
|
21
|
+
from .cameras import LuxonisCameraConfig, RGBCameraConfig, ZedCameraConfig
|
|
22
22
|
from .imu import ChassisIMUConfig, ZedIMUConfig
|
|
23
23
|
from .lidar import RPLidarConfig
|
|
24
24
|
from .ultrasonic import UltraSonicConfig
|
|
@@ -58,6 +58,12 @@ class VegaSensorsConfig:
|
|
|
58
58
|
"""
|
|
59
59
|
|
|
60
60
|
head_camera: ZedCameraConfig = field(default_factory=ZedCameraConfig)
|
|
61
|
+
left_wrist_camera: LuxonisCameraConfig = field(
|
|
62
|
+
default_factory=lambda: LuxonisCameraConfig(name="left_wrist_camera")
|
|
63
|
+
)
|
|
64
|
+
right_wrist_camera: LuxonisCameraConfig = field(
|
|
65
|
+
default_factory=lambda: LuxonisCameraConfig(name="right_wrist_camera")
|
|
66
|
+
)
|
|
61
67
|
base_left_camera: RGBCameraConfig = field(default_factory=_make_rgb_camera("left"))
|
|
62
68
|
base_right_camera: RGBCameraConfig = field(
|
|
63
69
|
default_factory=_make_rgb_camera("right")
|
|
@@ -73,6 +79,8 @@ class VegaSensorsConfig:
|
|
|
73
79
|
|
|
74
80
|
def __post_init__(self) -> None:
|
|
75
81
|
self.head_camera.enable = False
|
|
82
|
+
self.left_wrist_camera.enable = False
|
|
83
|
+
self.right_wrist_camera.enable = False
|
|
76
84
|
self.base_left_camera.enable = False
|
|
77
85
|
self.base_right_camera.enable = False
|
|
78
86
|
self.base_front_camera.enable = False
|
dexcontrol/config/vega.py
CHANGED
|
@@ -52,6 +52,7 @@ class VegaConfig:
|
|
|
52
52
|
"folded": [1.57079, 0.0, 0, -3.1, 0, 0, -0.69813],
|
|
53
53
|
"folded_closed_hand": [1.57079, 0.0, 0, -3.1, 0, 0, -0.9],
|
|
54
54
|
"L_shape": [0.064, -0.3, 0.0, -1.556, 1.271, 0.0, 0.0],
|
|
55
|
+
"lift_up": [0.064, -0.3, 0.0, -2.756, 1.271, 0.0, 0.0],
|
|
55
56
|
"zero": [-1.57079, 0.0, 0, 0.0, 0, 0, 0.0],
|
|
56
57
|
},
|
|
57
58
|
)
|
|
@@ -67,6 +68,7 @@ class VegaConfig:
|
|
|
67
68
|
"folded": [-1.57079, 0.0, 0, -3.1, 0, 0, 0.69813],
|
|
68
69
|
"folded_closed_hand": [-1.57079, 0.0, 0, -3.1, 0, 0, 0.9],
|
|
69
70
|
"L_shape": [-0.064, 0.3, 0.0, -1.556, -1.271, 0.0, 0.0],
|
|
71
|
+
"lift_up": [-0.064, 0.3, 0.0, -2.756, -1.271, 0.0, 0.0],
|
|
70
72
|
"zero": [1.57079, 0.0, 0, 0.0, 0, 0, 0.0],
|
|
71
73
|
},
|
|
72
74
|
)
|
|
@@ -114,6 +116,7 @@ class VegaConfig:
|
|
|
114
116
|
reboot_query_name: str = "system/reboot"
|
|
115
117
|
clear_error_query_name: str = "system/clear_error"
|
|
116
118
|
led_query_name: str = "system/led"
|
|
119
|
+
soc_ntp_query_name: str = "time/soc"
|
|
117
120
|
|
|
118
121
|
@classmethod
|
|
119
122
|
def register_variant(
|
|
@@ -138,11 +141,22 @@ class Vega1Config(VegaConfig):
|
|
|
138
141
|
control_pub_topic="control/arm/left",
|
|
139
142
|
set_mode_query="mode/arm/left",
|
|
140
143
|
wrench_sub_topic="state/wrench/left",
|
|
144
|
+
ee_pass_through_pub_topic="control/ee_pass_through/left",
|
|
141
145
|
joint_name=[f"L_arm_j{i + 1}" for i in range(7)],
|
|
146
|
+
joint_limit=[
|
|
147
|
+
[-3.071, 3.071],
|
|
148
|
+
[-0.453, 1.553],
|
|
149
|
+
[-3.071, 3.071],
|
|
150
|
+
[-3.071, 0.244],
|
|
151
|
+
[-3.071, 3.071],
|
|
152
|
+
[-1.396, 1.396],
|
|
153
|
+
[-1.378, 1.117],
|
|
154
|
+
],
|
|
142
155
|
pose_pool={
|
|
143
156
|
"folded": [1.57079, 0.0, 0, -3.1, 0, 0, -0.69813],
|
|
144
157
|
"folded_closed_hand": [1.57079, 0.0, 0, -3.1, 0, 0, -0.9],
|
|
145
158
|
"L_shape": [0.064, 0.3, 0.0, -1.556, 1.271, 0.0, 0.0],
|
|
159
|
+
"lift_up": [0.064, 0.3, 0.0, -2.756, 1.271, 0.0, 0.0],
|
|
146
160
|
"zero": [-1.57079, 0.0, 0, 0.0, 0, 0, 0.0],
|
|
147
161
|
},
|
|
148
162
|
)
|
|
@@ -153,11 +167,22 @@ class Vega1Config(VegaConfig):
|
|
|
153
167
|
control_pub_topic="control/arm/right",
|
|
154
168
|
set_mode_query="mode/arm/right",
|
|
155
169
|
wrench_sub_topic="state/wrench/right",
|
|
170
|
+
ee_pass_through_pub_topic="control/ee_pass_through/right",
|
|
156
171
|
joint_name=[f"R_arm_j{i + 1}" for i in range(7)],
|
|
172
|
+
joint_limit=[
|
|
173
|
+
[-3.071, 3.071],
|
|
174
|
+
[-1.553, 0.453],
|
|
175
|
+
[-3.071, 3.071],
|
|
176
|
+
[-3.071, 0.244],
|
|
177
|
+
[-3.071, 3.071],
|
|
178
|
+
[-1.396, 1.396],
|
|
179
|
+
[-1.117, 1.378],
|
|
180
|
+
],
|
|
157
181
|
pose_pool={
|
|
158
182
|
"folded": [-1.57079, 0.0, 0, -3.1, 0, 0, 0.69813],
|
|
159
183
|
"folded_closed_hand": [-1.57079, 0.0, 0, -3.1, 0, 0, 0.9],
|
|
160
184
|
"L_shape": [-0.064, -0.3, 0.0, -1.556, -1.271, 0.0, 0.0],
|
|
185
|
+
"lift_up": [-0.064, -0.3, 0.0, -2.756, -1.271, 0.0, 0.0],
|
|
161
186
|
"zero": [1.57079, 0.0, 0, 0.0, 0, 0, 0.0],
|
|
162
187
|
},
|
|
163
188
|
)
|
|
@@ -169,8 +194,11 @@ class Vega1Config(VegaConfig):
|
|
|
169
194
|
)
|
|
170
195
|
head: HeadConfig = field(
|
|
171
196
|
default_factory=lambda: HeadConfig(
|
|
172
|
-
|
|
173
|
-
|
|
197
|
+
joint_limit=[
|
|
198
|
+
[-1.483, 1.483],
|
|
199
|
+
[-2.792, 2.792],
|
|
200
|
+
[-1.378, 1.378],
|
|
201
|
+
],
|
|
174
202
|
)
|
|
175
203
|
)
|
|
176
204
|
|
dexcontrol/core/arm.py
CHANGED
|
@@ -58,6 +58,12 @@ class Arm(RobotJointComponent):
|
|
|
58
58
|
state_message_type=dexcontrol_msg_pb2.ArmState,
|
|
59
59
|
zenoh_session=zenoh_session,
|
|
60
60
|
joint_name=configs.joint_name,
|
|
61
|
+
joint_limit=configs.joint_limit
|
|
62
|
+
if hasattr(configs, "joint_limit")
|
|
63
|
+
else None,
|
|
64
|
+
joint_vel_limit=configs.joint_vel_limit
|
|
65
|
+
if hasattr(configs, "joint_vel_limit")
|
|
66
|
+
else None,
|
|
61
67
|
pose_pool=configs.pose_pool,
|
|
62
68
|
)
|
|
63
69
|
|
|
@@ -72,14 +78,21 @@ class Arm(RobotJointComponent):
|
|
|
72
78
|
configs.wrench_sub_topic, zenoh_session
|
|
73
79
|
)
|
|
74
80
|
|
|
75
|
-
|
|
76
|
-
self.
|
|
77
|
-
|
|
78
|
-
|
|
79
|
-
f"Max velocity is set to {self._default_max_vel}, which is greater than 3.0. This is not recommended."
|
|
81
|
+
# Initialize end effector pass through publisher
|
|
82
|
+
self._ee_pass_through_publisher: Final[zenoh.Publisher] = (
|
|
83
|
+
zenoh_session.declare_publisher(
|
|
84
|
+
resolve_key_name(configs.ee_pass_through_pub_topic)
|
|
80
85
|
)
|
|
81
|
-
|
|
82
|
-
|
|
86
|
+
)
|
|
87
|
+
|
|
88
|
+
self._default_control_hz = configs.default_control_hz
|
|
89
|
+
if self._joint_vel_limit is not None:
|
|
90
|
+
if np.any(self._joint_vel_limit > 2.8):
|
|
91
|
+
logger.warning(
|
|
92
|
+
"Joint velocity limit is greater than 2.8. This is not recommended."
|
|
93
|
+
)
|
|
94
|
+
self._joint_vel_limit = np.clip(self._joint_vel_limit, 0, 2.8)
|
|
95
|
+
logger.warning("Joint velocity limit is clamped to 2.8")
|
|
83
96
|
|
|
84
97
|
def set_mode(self, mode: Literal["position", "disable"]) -> None:
|
|
85
98
|
"""Sets the operating mode of the arm.
|
|
@@ -137,6 +150,13 @@ class Arm(RobotJointComponent):
|
|
|
137
150
|
immediately. If wait_time is greater than 0, the joint positions will
|
|
138
151
|
be interpolated between the current position and the target position,
|
|
139
152
|
and the function will wait for the specified time between each movement.
|
|
153
|
+
|
|
154
|
+
**IMPORTANT: When wait_time is 0, you MUST call this function repeatedly
|
|
155
|
+
in a high-frequency loop (e.g., 100 Hz). DO NOT call it just once!**
|
|
156
|
+
The function is designed for continuous control when wait_time=0.
|
|
157
|
+
The highest frequency that the user can call this function is 500 Hz.
|
|
158
|
+
|
|
159
|
+
|
|
140
160
|
wait_kwargs: Keyword arguments for the interpolation (only used if
|
|
141
161
|
wait_time > 0). Supported keys:
|
|
142
162
|
- control_hz: Control frequency in Hz (default: 100).
|
|
@@ -152,6 +172,11 @@ class Arm(RobotJointComponent):
|
|
|
152
172
|
resolved_joint_pos = (
|
|
153
173
|
self._resolve_relative_joint_cmd(joint_pos) if relative else joint_pos
|
|
154
174
|
)
|
|
175
|
+
resolved_joint_pos = self._convert_joint_cmd_to_array(resolved_joint_pos)
|
|
176
|
+
if self._joint_limit is not None:
|
|
177
|
+
resolved_joint_pos = np.clip(
|
|
178
|
+
resolved_joint_pos, self._joint_limit[:, 0], self._joint_limit[:, 1]
|
|
179
|
+
)
|
|
155
180
|
|
|
156
181
|
if wait_time > 0.0:
|
|
157
182
|
self._execute_trajectory_motion(
|
|
@@ -162,16 +187,11 @@ class Arm(RobotJointComponent):
|
|
|
162
187
|
exit_on_reach_kwargs,
|
|
163
188
|
)
|
|
164
189
|
else:
|
|
165
|
-
# Convert to array format
|
|
166
|
-
if isinstance(resolved_joint_pos, (list, dict)):
|
|
167
|
-
resolved_joint_pos = self._convert_joint_cmd_to_array(
|
|
168
|
-
resolved_joint_pos
|
|
169
|
-
)
|
|
170
190
|
self._send_position_command(resolved_joint_pos)
|
|
171
191
|
|
|
172
192
|
def _execute_trajectory_motion(
|
|
173
193
|
self,
|
|
174
|
-
|
|
194
|
+
target_joint_pos: Float[np.ndarray, " N"],
|
|
175
195
|
wait_time: float,
|
|
176
196
|
wait_kwargs: dict[str, float],
|
|
177
197
|
exit_on_reach: bool = False,
|
|
@@ -180,7 +200,7 @@ class Arm(RobotJointComponent):
|
|
|
180
200
|
"""Execute trajectory-based motion to target position.
|
|
181
201
|
|
|
182
202
|
Args:
|
|
183
|
-
|
|
203
|
+
target_joint_pos: Target joint positions as numpy array.
|
|
184
204
|
wait_time: Total time for the motion.
|
|
185
205
|
wait_kwargs: Parameters for trajectory generation.
|
|
186
206
|
exit_on_reach: If True, the function will exit when the joint positions are reached.
|
|
@@ -188,7 +208,11 @@ class Arm(RobotJointComponent):
|
|
|
188
208
|
"""
|
|
189
209
|
# Set default parameters
|
|
190
210
|
control_hz = wait_kwargs.get("control_hz", self._default_control_hz)
|
|
191
|
-
max_vel = wait_kwargs.get("max_vel"
|
|
211
|
+
max_vel = wait_kwargs.get("max_vel")
|
|
212
|
+
if max_vel is None:
|
|
213
|
+
max_vel = (
|
|
214
|
+
self._joint_vel_limit if self._joint_vel_limit is not None else 2.8
|
|
215
|
+
)
|
|
192
216
|
exit_on_reach_kwargs = exit_on_reach_kwargs or {}
|
|
193
217
|
exit_on_reach_kwargs.setdefault("tolerance", 0.05)
|
|
194
218
|
|
|
@@ -196,19 +220,9 @@ class Arm(RobotJointComponent):
|
|
|
196
220
|
rate_limiter = RateLimiter(control_hz)
|
|
197
221
|
current_joint_pos = self.get_joint_pos().copy()
|
|
198
222
|
|
|
199
|
-
# Convert input to numpy array for trajectory generation
|
|
200
|
-
if isinstance(joint_pos, (list, dict)):
|
|
201
|
-
target_pos = (
|
|
202
|
-
self._convert_dict_to_array(joint_pos)
|
|
203
|
-
if isinstance(joint_pos, dict)
|
|
204
|
-
else np.array(joint_pos, dtype=np.float32)
|
|
205
|
-
)
|
|
206
|
-
else:
|
|
207
|
-
target_pos = joint_pos
|
|
208
|
-
|
|
209
223
|
# Generate trajectory using utility function
|
|
210
224
|
trajectory, _ = generate_linear_trajectory(
|
|
211
|
-
current_joint_pos,
|
|
225
|
+
current_joint_pos, target_joint_pos, max_vel, control_hz
|
|
212
226
|
)
|
|
213
227
|
# Execute trajectory with time limit
|
|
214
228
|
start_time = time.time()
|
|
@@ -220,10 +234,10 @@ class Arm(RobotJointComponent):
|
|
|
220
234
|
|
|
221
235
|
# Hold final position for remaining time
|
|
222
236
|
while time.time() - start_time < wait_time:
|
|
223
|
-
self._send_position_command(
|
|
237
|
+
self._send_position_command(target_joint_pos)
|
|
224
238
|
rate_limiter.sleep()
|
|
225
239
|
if exit_on_reach and self.is_joint_pos_reached(
|
|
226
|
-
|
|
240
|
+
target_joint_pos, **exit_on_reach_kwargs
|
|
227
241
|
):
|
|
228
242
|
break
|
|
229
243
|
|
|
@@ -235,6 +249,16 @@ class Arm(RobotJointComponent):
|
|
|
235
249
|
) -> None:
|
|
236
250
|
"""Controls the arm in joint position mode with a velocity feedforward term.
|
|
237
251
|
|
|
252
|
+
Warning:
|
|
253
|
+
The joint_vel parameter should be well-planned (such as from a trajectory planner).
|
|
254
|
+
Sending poorly planned or inappropriate joint velocity commands can cause the robot
|
|
255
|
+
to behave unexpectedly or potentially get damaged. Ensure velocity commands are
|
|
256
|
+
smooth, within safe limits, and properly coordinated across all joints.
|
|
257
|
+
|
|
258
|
+
Additionally, this command MUST be called at high frequency (e.g., 100Hz) to take
|
|
259
|
+
effect properly. DO NOT call this function just once or at low frequency, as this
|
|
260
|
+
can lead to unpredictable robot behavior.
|
|
261
|
+
|
|
238
262
|
Args:
|
|
239
263
|
joint_pos: Joint positions as either:
|
|
240
264
|
- List of joint values [j1, j2, ..., j7]
|
|
@@ -244,6 +268,7 @@ class Arm(RobotJointComponent):
|
|
|
244
268
|
- List of joint values [v1, v2, ..., v7]
|
|
245
269
|
- Numpy array with shape (7,), in radians/sec
|
|
246
270
|
- Dictionary of joint names and velocity values
|
|
271
|
+
|
|
247
272
|
relative: If True, the joint positions are relative to the current position.
|
|
248
273
|
|
|
249
274
|
Raises:
|
|
@@ -252,25 +277,15 @@ class Arm(RobotJointComponent):
|
|
|
252
277
|
resolved_joint_pos = (
|
|
253
278
|
self._resolve_relative_joint_cmd(joint_pos) if relative else joint_pos
|
|
254
279
|
)
|
|
255
|
-
|
|
256
|
-
|
|
257
|
-
|
|
258
|
-
|
|
259
|
-
self._convert_dict_to_array(resolved_joint_pos)
|
|
260
|
-
if isinstance(resolved_joint_pos, dict)
|
|
261
|
-
else np.array(resolved_joint_pos, dtype=np.float32)
|
|
262
|
-
)
|
|
263
|
-
else:
|
|
264
|
-
target_pos = resolved_joint_pos
|
|
265
|
-
|
|
266
|
-
if isinstance(joint_vel, (list, dict)):
|
|
267
|
-
target_vel = (
|
|
268
|
-
self._convert_dict_to_array(joint_vel)
|
|
269
|
-
if isinstance(joint_vel, dict)
|
|
270
|
-
else np.array(joint_vel, dtype=np.float32)
|
|
280
|
+
resolved_joint_pos = self._convert_joint_cmd_to_array(resolved_joint_pos)
|
|
281
|
+
if self._joint_limit is not None:
|
|
282
|
+
resolved_joint_pos = np.clip(
|
|
283
|
+
resolved_joint_pos, self._joint_limit[:, 0], self._joint_limit[:, 1]
|
|
271
284
|
)
|
|
272
|
-
|
|
273
|
-
|
|
285
|
+
target_pos = resolved_joint_pos
|
|
286
|
+
target_vel = self._convert_joint_cmd_to_array(
|
|
287
|
+
joint_vel, clip_value=self._joint_vel_limit
|
|
288
|
+
)
|
|
274
289
|
|
|
275
290
|
control_msg = dexcontrol_msg_pb2.ArmCommand(
|
|
276
291
|
command_type=dexcontrol_msg_pb2.ArmCommand.CommandType.VELOCITY_FEEDFORWARD,
|
|
@@ -296,6 +311,16 @@ class Arm(RobotJointComponent):
|
|
|
296
311
|
if self.wrench_sensor:
|
|
297
312
|
self.wrench_sensor.shutdown()
|
|
298
313
|
|
|
314
|
+
def send_ee_pass_through_message(self, message: bytes):
|
|
315
|
+
"""Send an end effector pass through message to the robot arm.
|
|
316
|
+
|
|
317
|
+
Args:
|
|
318
|
+
message: The message to send to the robot arm.
|
|
319
|
+
"""
|
|
320
|
+
control_msg = dexcontrol_msg_pb2.EndEffectorPassThroughCommand(data=message)
|
|
321
|
+
control_data = control_msg.SerializeToString()
|
|
322
|
+
self._ee_pass_through_publisher.put(control_data)
|
|
323
|
+
|
|
299
324
|
|
|
300
325
|
class ArmWrenchSensor(RobotComponent):
|
|
301
326
|
"""Wrench sensor reader for the robot arm.
|
dexcontrol/core/component.py
CHANGED
|
@@ -89,11 +89,11 @@ class RobotComponent:
|
|
|
89
89
|
Parsed protobuf state message.
|
|
90
90
|
|
|
91
91
|
Raises:
|
|
92
|
-
|
|
92
|
+
None: If no state data is available.
|
|
93
93
|
"""
|
|
94
94
|
state = self._subscriber.get_latest_data()
|
|
95
95
|
if state is None:
|
|
96
|
-
|
|
96
|
+
logger.error(f"No state data available for {self.__class__.__name__}")
|
|
97
97
|
return state
|
|
98
98
|
|
|
99
99
|
def wait_for_active(self, timeout: float = 5.0) -> bool:
|
|
@@ -133,6 +133,15 @@ class RobotComponent:
|
|
|
133
133
|
if hasattr(self, "_subscriber") and self._subscriber:
|
|
134
134
|
self._subscriber.shutdown()
|
|
135
135
|
|
|
136
|
+
def get_timestamp_ns(self) -> int:
|
|
137
|
+
"""Get the current timestamp (in nanoseconds) of the most recent state update.
|
|
138
|
+
|
|
139
|
+
Returns:
|
|
140
|
+
The current timestamp in nanoseconds when driver updated the state.
|
|
141
|
+
We convert the time to client clock by adding the server time offset.
|
|
142
|
+
"""
|
|
143
|
+
return self._get_state().timestamp_ns
|
|
144
|
+
|
|
136
145
|
|
|
137
146
|
class RobotJointComponent(RobotComponent):
|
|
138
147
|
"""Base class for robot components with both state and control interfaces.
|
|
@@ -171,6 +180,8 @@ class RobotJointComponent(RobotComponent):
|
|
|
171
180
|
state_message_type: type[M],
|
|
172
181
|
zenoh_session: zenoh.Session,
|
|
173
182
|
joint_name: list[str] | None = None,
|
|
183
|
+
joint_limit: list[list[float]] | None = None,
|
|
184
|
+
joint_vel_limit: list[float] | None = None,
|
|
174
185
|
pose_pool: Mapping[str, list[float] | np.ndarray] | None = None,
|
|
175
186
|
) -> None:
|
|
176
187
|
"""Initializes RobotJointComponent.
|
|
@@ -190,6 +201,13 @@ class RobotJointComponent(RobotComponent):
|
|
|
190
201
|
resolved_topic
|
|
191
202
|
)
|
|
192
203
|
self._joint_name: list[str] | None = joint_name
|
|
204
|
+
self._joint_limit: np.ndarray | None = (
|
|
205
|
+
np.array(joint_limit) if joint_limit else None
|
|
206
|
+
)
|
|
207
|
+
self._joint_vel_limit: np.ndarray | None = (
|
|
208
|
+
np.array(joint_vel_limit) if joint_vel_limit else None
|
|
209
|
+
)
|
|
210
|
+
|
|
193
211
|
self._pose_pool: dict[str, np.ndarray] | None = (
|
|
194
212
|
self._convert_pose_pool_to_arrays(pose_pool)
|
|
195
213
|
)
|
|
@@ -231,6 +249,18 @@ class RobotJointComponent(RobotComponent):
|
|
|
231
249
|
raise ValueError("Joint names not available for this component")
|
|
232
250
|
return self._joint_name.copy()
|
|
233
251
|
|
|
252
|
+
@property
|
|
253
|
+
def joint_limit(self) -> np.ndarray | None:
|
|
254
|
+
"""Gets the joint limits of the component."""
|
|
255
|
+
return self._joint_limit.copy() if self._joint_limit is not None else None
|
|
256
|
+
|
|
257
|
+
@property
|
|
258
|
+
def joint_vel_limit(self) -> np.ndarray | None:
|
|
259
|
+
"""Gets the joint velocity limits of the component."""
|
|
260
|
+
return (
|
|
261
|
+
self._joint_vel_limit.copy() if self._joint_vel_limit is not None else None
|
|
262
|
+
)
|
|
263
|
+
|
|
234
264
|
def get_predefined_pose(self, pose_name: str) -> np.ndarray:
|
|
235
265
|
"""Gets a predefined pose from the pose pool.
|
|
236
266
|
|
|
@@ -466,7 +496,7 @@ class RobotJointComponent(RobotComponent):
|
|
|
466
496
|
def _convert_joint_cmd_to_array(
|
|
467
497
|
self,
|
|
468
498
|
joint_cmd: Float[np.ndarray, " N"] | list[float] | dict[str, float],
|
|
469
|
-
clip_value: float | None = None,
|
|
499
|
+
clip_value: float | np.ndarray | None = None,
|
|
470
500
|
) -> np.ndarray:
|
|
471
501
|
"""Convert joint command to numpy array format.
|
|
472
502
|
|
|
@@ -475,7 +505,9 @@ class RobotJointComponent(RobotComponent):
|
|
|
475
505
|
- List of joint values [j1, j2, ..., jN]
|
|
476
506
|
- Numpy array with shape (N,)
|
|
477
507
|
- Dictionary mapping joint names to values
|
|
478
|
-
clip_value: Optional value to clip the output array
|
|
508
|
+
clip_value: Optional value to clip the output array. Can be:
|
|
509
|
+
- float: symmetric clipping between [-clip_value, clip_value]
|
|
510
|
+
- numpy array: element-wise clipping between [-clip_value, clip_value]
|
|
479
511
|
|
|
480
512
|
Returns:
|
|
481
513
|
Joint command as numpy array.
|
|
@@ -660,6 +692,11 @@ class RobotJointComponent(RobotComponent):
|
|
|
660
692
|
if isinstance(joint_pos, (list, dict)):
|
|
661
693
|
joint_pos = self._convert_joint_cmd_to_array(joint_pos)
|
|
662
694
|
|
|
695
|
+
if self._joint_limit is not None:
|
|
696
|
+
joint_pos = np.clip(
|
|
697
|
+
joint_pos, self._joint_limit[:, 0], self._joint_limit[:, 1]
|
|
698
|
+
)
|
|
699
|
+
|
|
663
700
|
self._send_position_command(joint_pos)
|
|
664
701
|
|
|
665
702
|
if wait_time > 0.0:
|