dexcontrol 0.2.10__py3-none-any.whl → 0.3.0__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.

Files changed (47) hide show
  1. dexcontrol/__init__.py +2 -0
  2. dexcontrol/config/core/arm.py +5 -1
  3. dexcontrol/config/core/chassis.py +9 -4
  4. dexcontrol/config/core/hand.py +2 -1
  5. dexcontrol/config/core/head.py +7 -8
  6. dexcontrol/config/core/misc.py +14 -1
  7. dexcontrol/config/core/torso.py +8 -4
  8. dexcontrol/config/sensors/cameras/__init__.py +2 -1
  9. dexcontrol/config/sensors/cameras/luxonis_camera.py +51 -0
  10. dexcontrol/config/sensors/cameras/rgb_camera.py +1 -1
  11. dexcontrol/config/sensors/cameras/zed_camera.py +2 -2
  12. dexcontrol/config/sensors/vega_sensors.py +9 -1
  13. dexcontrol/config/vega.py +34 -3
  14. dexcontrol/core/arm.py +103 -58
  15. dexcontrol/core/chassis.py +146 -115
  16. dexcontrol/core/component.py +83 -20
  17. dexcontrol/core/hand.py +74 -39
  18. dexcontrol/core/head.py +41 -28
  19. dexcontrol/core/misc.py +256 -25
  20. dexcontrol/core/robot_query_interface.py +440 -0
  21. dexcontrol/core/torso.py +28 -10
  22. dexcontrol/proto/dexcontrol_msg_pb2.py +27 -37
  23. dexcontrol/proto/dexcontrol_msg_pb2.pyi +111 -126
  24. dexcontrol/proto/dexcontrol_query_pb2.py +39 -35
  25. dexcontrol/proto/dexcontrol_query_pb2.pyi +41 -4
  26. dexcontrol/robot.py +266 -409
  27. dexcontrol/sensors/__init__.py +2 -1
  28. dexcontrol/sensors/camera/__init__.py +2 -0
  29. dexcontrol/sensors/camera/luxonis_camera.py +169 -0
  30. dexcontrol/sensors/camera/zed_camera.py +17 -8
  31. dexcontrol/sensors/imu/chassis_imu.py +5 -1
  32. dexcontrol/sensors/imu/zed_imu.py +3 -2
  33. dexcontrol/sensors/lidar/rplidar.py +1 -0
  34. dexcontrol/sensors/manager.py +3 -0
  35. dexcontrol/utils/constants.py +3 -0
  36. dexcontrol/utils/error_code.py +236 -0
  37. dexcontrol/utils/os_utils.py +183 -1
  38. dexcontrol/utils/pb_utils.py +0 -22
  39. dexcontrol/utils/subscribers/lidar.py +1 -0
  40. dexcontrol/utils/trajectory_utils.py +17 -5
  41. dexcontrol/utils/viz_utils.py +86 -11
  42. dexcontrol/utils/zenoh_utils.py +288 -2
  43. {dexcontrol-0.2.10.dist-info → dexcontrol-0.3.0.dist-info}/METADATA +15 -2
  44. dexcontrol-0.3.0.dist-info/RECORD +76 -0
  45. dexcontrol-0.2.10.dist-info/RECORD +0 -72
  46. {dexcontrol-0.2.10.dist-info → dexcontrol-0.3.0.dist-info}/WHEEL +0 -0
  47. {dexcontrol-0.2.10.dist-info → dexcontrol-0.3.0.dist-info}/licenses/LICENSE +0 -0
dexcontrol/__init__.py CHANGED
@@ -30,8 +30,10 @@ from dexcontrol.robot import Robot
30
30
  from dexcontrol.utils.constants import COMM_CFG_PATH_ENV_VAR
31
31
 
32
32
  # Package-level constants
33
+ __version__: str = "0.3.0" # Current library version
33
34
  LIB_PATH: Final[Path] = Path(__file__).resolve().parent
34
35
  CFG_PATH: Final[Path] = LIB_PATH / "config"
36
+ MIN_SOC_SOFTWARE_VERSION: int = 286
35
37
 
36
38
  logger.configure(handlers=[{"sink": RichHandler(markup=True), "format": "{message}"}])
37
39
 
@@ -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
  )
@@ -14,14 +14,19 @@ from dataclasses import dataclass, field
14
14
  @dataclass
15
15
  class ChassisConfig:
16
16
  _target_: str = "dexcontrol.core.chassis.Chassis"
17
- control_pub_topic: str = "control/chassis"
18
- state_sub_topic: str = "state/chassis"
17
+ steer_control_pub_topic: str = "control/chassis/steer"
18
+ steer_state_sub_topic: str = "state/chassis/steer"
19
+ drive_control_pub_topic: str = "control/chassis/drive"
20
+ drive_state_sub_topic: str = "state/chassis/drive"
19
21
  dof: int = 2
20
22
  center_to_wheel_axis_dist: float = (
21
23
  0.219 # the distance between base center and wheel axis in m
22
24
  )
23
25
  wheels_dist: float = 0.45 # the distance between two wheels in m (0.41 for vega-rc2, 0.45 for vega-1)
24
- joint_name: list[str] = field(
25
- default_factory=lambda: ["L_wheel_j1", "L_wheel_j2", "R_wheel_j1", "R_wheel_j2"]
26
+ steer_joint_name: list[str] = field(
27
+ default_factory=lambda: ["L_wheel_j1", "R_wheel_j1"]
28
+ )
29
+ drive_joint_name: list[str] = field(
30
+ default_factory=lambda: ["L_wheel_j2", "R_wheel_j2"]
26
31
  )
27
32
  max_vel: float = 0.8
@@ -16,6 +16,7 @@ class HandConfig:
16
16
  _target_: str = "dexcontrol.core.hand.HandF5D6"
17
17
  state_sub_topic: str = "state/hand/right"
18
18
  control_pub_topic: str = "control/hand/right"
19
+ touch_sensor_sub_topic: str = "state/hand/right/touch" # Only for V2 hand
19
20
  dof: int = 6
20
21
  joint_name: list[str] = field(
21
22
  default_factory=lambda: [
@@ -31,6 +32,6 @@ class HandConfig:
31
32
  pose_pool: dict[str, list[float]] = field(
32
33
  default_factory=lambda: {
33
34
  "open": [0.1834, 0.2891, 0.2801, 0.284, 0.2811, -0.0158],
34
- "close": [-0.3468, -1.0946, -1.0844, -1.0154, -1.0118, 1.6],
35
+ "close": [-0.2668, -1.0946, -1.0844, -1.0154, -1.0118, 1.6],
35
36
  }
36
37
  )
@@ -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
- # Use the following varaibles if you are using vega-rc2
25
- joint_limit_lower: list[float] = field(
26
- default_factory=lambda: [-1.2217, -2.7925, -1.396]
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
- joint_limit_upper: list[float] = field(
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],
@@ -13,7 +13,10 @@
13
13
  import os
14
14
  from dataclasses import dataclass
15
15
 
16
- from dexcontrol.utils.constants import DISABLE_HEARTBEAT_ENV_VAR
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
@@ -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
- default_vel: float = 0.4 # rad/s, will be used if joint_vel is not provided
24
- max_vel: float = 0.6 # max velocity of torso joint, will be used to clip
25
- # the joint_vel, Highly recommended to set this value
26
- # not higher than 0.6 rad/s
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 high-performance RTCSubscriber. If False,
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 high-performance RTCSubscriber.
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 = True
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
  )
@@ -75,6 +77,7 @@ class VegaConfig:
75
77
  default_factory=lambda: HandConfig(
76
78
  state_sub_topic="state/hand/left",
77
79
  control_pub_topic="control/hand/left",
80
+ touch_sensor_sub_topic="state/hand/left/touch",
78
81
  joint_name=[
79
82
  "L_th_j1",
80
83
  "L_ff_j1",
@@ -89,6 +92,7 @@ class VegaConfig:
89
92
  default_factory=lambda: HandConfig(
90
93
  state_sub_topic="state/hand/right",
91
94
  control_pub_topic="control/hand/right",
95
+ touch_sensor_sub_topic="state/hand/right/touch",
92
96
  joint_name=[
93
97
  "R_th_j1",
94
98
  "R_ff_j1",
@@ -109,11 +113,13 @@ class VegaConfig:
109
113
  heartbeat: HeartbeatConfig = field(default_factory=HeartbeatConfig)
110
114
 
111
115
  # Queries
112
- version_info_name: str = "info/version"
116
+ version_info_name: str = "info/versions" # Updated to use JSON interface
113
117
  status_info_name: str = "info/status"
118
+ hand_info_query_name: str = "info/hand_type"
114
119
  reboot_query_name: str = "system/reboot"
115
120
  clear_error_query_name: str = "system/clear_error"
116
121
  led_query_name: str = "system/led"
122
+ soc_ntp_query_name: str = "time/soc"
117
123
 
118
124
  @classmethod
119
125
  def register_variant(
@@ -138,11 +144,22 @@ class Vega1Config(VegaConfig):
138
144
  control_pub_topic="control/arm/left",
139
145
  set_mode_query="mode/arm/left",
140
146
  wrench_sub_topic="state/wrench/left",
147
+ ee_pass_through_pub_topic="control/ee_pass_through/left",
141
148
  joint_name=[f"L_arm_j{i + 1}" for i in range(7)],
149
+ joint_limit=[
150
+ [-3.071, 3.071],
151
+ [-0.453, 1.553],
152
+ [-3.071, 3.071],
153
+ [-3.071, 0.244],
154
+ [-3.071, 3.071],
155
+ [-1.396, 1.396],
156
+ [-1.378, 1.117],
157
+ ],
142
158
  pose_pool={
143
159
  "folded": [1.57079, 0.0, 0, -3.1, 0, 0, -0.69813],
144
160
  "folded_closed_hand": [1.57079, 0.0, 0, -3.1, 0, 0, -0.9],
145
161
  "L_shape": [0.064, 0.3, 0.0, -1.556, 1.271, 0.0, 0.0],
162
+ "lift_up": [0.064, 0.3, 0.0, -2.756, 1.271, 0.0, 0.0],
146
163
  "zero": [-1.57079, 0.0, 0, 0.0, 0, 0, 0.0],
147
164
  },
148
165
  )
@@ -153,11 +170,22 @@ class Vega1Config(VegaConfig):
153
170
  control_pub_topic="control/arm/right",
154
171
  set_mode_query="mode/arm/right",
155
172
  wrench_sub_topic="state/wrench/right",
173
+ ee_pass_through_pub_topic="control/ee_pass_through/right",
156
174
  joint_name=[f"R_arm_j{i + 1}" for i in range(7)],
175
+ joint_limit=[
176
+ [-3.071, 3.071],
177
+ [-1.553, 0.453],
178
+ [-3.071, 3.071],
179
+ [-3.071, 0.244],
180
+ [-3.071, 3.071],
181
+ [-1.396, 1.396],
182
+ [-1.117, 1.378],
183
+ ],
157
184
  pose_pool={
158
185
  "folded": [-1.57079, 0.0, 0, -3.1, 0, 0, 0.69813],
159
186
  "folded_closed_hand": [-1.57079, 0.0, 0, -3.1, 0, 0, 0.9],
160
187
  "L_shape": [-0.064, -0.3, 0.0, -1.556, -1.271, 0.0, 0.0],
188
+ "lift_up": [-0.064, -0.3, 0.0, -2.756, -1.271, 0.0, 0.0],
161
189
  "zero": [1.57079, 0.0, 0, 0.0, 0, 0, 0.0],
162
190
  },
163
191
  )
@@ -169,8 +197,11 @@ class Vega1Config(VegaConfig):
169
197
  )
170
198
  head: HeadConfig = field(
171
199
  default_factory=lambda: HeadConfig(
172
- joint_limit_lower=[-1.483, -2.792, -1.378],
173
- joint_limit_upper=[1.483, 2.792, 1.483],
200
+ joint_limit=[
201
+ [-1.483, 1.483],
202
+ [-2.792, 2.792],
203
+ [-1.378, 1.378],
204
+ ],
174
205
  )
175
206
  )
176
207
 
dexcontrol/core/arm.py CHANGED
@@ -55,9 +55,15 @@ class Arm(RobotJointComponent):
55
55
  super().__init__(
56
56
  state_sub_topic=configs.state_sub_topic,
57
57
  control_pub_topic=configs.control_pub_topic,
58
- state_message_type=dexcontrol_msg_pb2.ArmState,
58
+ state_message_type=dexcontrol_msg_pb2.MotorStateWithCurrent,
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,18 +78,28 @@ class Arm(RobotJointComponent):
72
78
  configs.wrench_sub_topic, zenoh_session
73
79
  )
74
80
 
75
- self._default_max_vel = configs.default_max_vel
76
- self._default_control_hz = configs.default_control_hz
77
- if self._default_max_vel > 3.0:
78
- logger.warning(
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
- self._default_max_vel = 3.0
82
- logger.warning("Max velocity is clamped to 3.0")
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.
86
99
 
100
+ .. deprecated::
101
+ Use set_modes() instead for setting arm modes.
102
+
87
103
  Args:
88
104
  mode: Operating mode for the arm. Must be either "position" or "disable".
89
105
  "position": Enable position control
@@ -92,17 +108,35 @@ class Arm(RobotJointComponent):
92
108
  Raises:
93
109
  ValueError: If an invalid mode is specified.
94
110
  """
111
+ logger.warning("arm.set_mode() is deprecated, use set_modes() instead")
112
+ self.set_modes([mode] * 7)
113
+
114
+ def set_modes(self, modes: list[Literal["position", "disable", "release"]]) -> None:
115
+ """Sets the operating modes of the arm.
116
+
117
+ Args:
118
+ modes: List of operating modes for the arm. Each mode must be either "position", "disable", or "current".
119
+
120
+ Raises:
121
+ ValueError: If any mode in the list is invalid.
122
+ """
95
123
  mode_map = {
96
124
  "position": dexcontrol_query_pb2.SetArmMode.Mode.POSITION,
97
125
  "disable": dexcontrol_query_pb2.SetArmMode.Mode.DISABLE,
126
+ "release": dexcontrol_query_pb2.SetArmMode.Mode.CURRENT,
98
127
  }
99
128
 
100
- if mode not in mode_map:
101
- raise ValueError(
102
- f"Invalid mode: {mode}. Must be one of {list(mode_map.keys())}"
103
- )
129
+ for mode in modes:
130
+ if mode not in mode_map:
131
+ raise ValueError(
132
+ f"Invalid mode: {mode}. Must be one of {list(mode_map.keys())}"
133
+ )
104
134
 
105
- query_msg = dexcontrol_query_pb2.SetArmMode(mode=mode_map[mode])
135
+ if len(modes) != 7:
136
+ raise ValueError("Arm modes length must match arm DoF (7).")
137
+
138
+ converted_modes = [mode_map[mode] for mode in modes]
139
+ query_msg = dexcontrol_query_pb2.SetArmMode(modes=converted_modes)
106
140
  self.mode_querier.get(payload=query_msg.SerializeToString())
107
141
 
108
142
  def _send_position_command(self, joint_pos: np.ndarray) -> None:
@@ -111,8 +145,8 @@ class Arm(RobotJointComponent):
111
145
  Args:
112
146
  joint_pos: Joint positions as numpy array.
113
147
  """
114
- control_msg = dexcontrol_msg_pb2.ArmCommand()
115
- control_msg.joint_pos.extend(joint_pos.tolist())
148
+ control_msg = dexcontrol_msg_pb2.MotorPosVelCurrentCommand()
149
+ control_msg.pos.extend(joint_pos.tolist())
116
150
  self._publish_control(control_msg)
117
151
 
118
152
  def set_joint_pos(
@@ -137,6 +171,13 @@ class Arm(RobotJointComponent):
137
171
  immediately. If wait_time is greater than 0, the joint positions will
138
172
  be interpolated between the current position and the target position,
139
173
  and the function will wait for the specified time between each movement.
174
+
175
+ **IMPORTANT: When wait_time is 0, you MUST call this function repeatedly
176
+ in a high-frequency loop (e.g., 100 Hz). DO NOT call it just once!**
177
+ The function is designed for continuous control when wait_time=0.
178
+ The highest frequency that the user can call this function is 500 Hz.
179
+
180
+
140
181
  wait_kwargs: Keyword arguments for the interpolation (only used if
141
182
  wait_time > 0). Supported keys:
142
183
  - control_hz: Control frequency in Hz (default: 100).
@@ -152,6 +193,11 @@ class Arm(RobotJointComponent):
152
193
  resolved_joint_pos = (
153
194
  self._resolve_relative_joint_cmd(joint_pos) if relative else joint_pos
154
195
  )
196
+ resolved_joint_pos = self._convert_joint_cmd_to_array(resolved_joint_pos)
197
+ if self._joint_limit is not None:
198
+ resolved_joint_pos = np.clip(
199
+ resolved_joint_pos, self._joint_limit[:, 0], self._joint_limit[:, 1]
200
+ )
155
201
 
156
202
  if wait_time > 0.0:
157
203
  self._execute_trajectory_motion(
@@ -162,16 +208,11 @@ class Arm(RobotJointComponent):
162
208
  exit_on_reach_kwargs,
163
209
  )
164
210
  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
211
  self._send_position_command(resolved_joint_pos)
171
212
 
172
213
  def _execute_trajectory_motion(
173
214
  self,
174
- joint_pos: Float[np.ndarray, " N"] | list[float] | dict[str, float],
215
+ target_joint_pos: Float[np.ndarray, " N"],
175
216
  wait_time: float,
176
217
  wait_kwargs: dict[str, float],
177
218
  exit_on_reach: bool = False,
@@ -180,7 +221,7 @@ class Arm(RobotJointComponent):
180
221
  """Execute trajectory-based motion to target position.
181
222
 
182
223
  Args:
183
- joint_pos: Target joint positions as list, numpy array, or dictionary.
224
+ target_joint_pos: Target joint positions as numpy array.
184
225
  wait_time: Total time for the motion.
185
226
  wait_kwargs: Parameters for trajectory generation.
186
227
  exit_on_reach: If True, the function will exit when the joint positions are reached.
@@ -188,7 +229,11 @@ class Arm(RobotJointComponent):
188
229
  """
189
230
  # Set default parameters
190
231
  control_hz = wait_kwargs.get("control_hz", self._default_control_hz)
191
- max_vel = wait_kwargs.get("max_vel", self._default_max_vel)
232
+ max_vel = wait_kwargs.get("max_vel")
233
+ if max_vel is None:
234
+ max_vel = (
235
+ self._joint_vel_limit if self._joint_vel_limit is not None else 2.8
236
+ )
192
237
  exit_on_reach_kwargs = exit_on_reach_kwargs or {}
193
238
  exit_on_reach_kwargs.setdefault("tolerance", 0.05)
194
239
 
@@ -196,19 +241,9 @@ class Arm(RobotJointComponent):
196
241
  rate_limiter = RateLimiter(control_hz)
197
242
  current_joint_pos = self.get_joint_pos().copy()
198
243
 
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
244
  # Generate trajectory using utility function
210
245
  trajectory, _ = generate_linear_trajectory(
211
- current_joint_pos, target_pos, max_vel, control_hz
246
+ current_joint_pos, target_joint_pos, max_vel, control_hz
212
247
  )
213
248
  # Execute trajectory with time limit
214
249
  start_time = time.time()
@@ -220,10 +255,10 @@ class Arm(RobotJointComponent):
220
255
 
221
256
  # Hold final position for remaining time
222
257
  while time.time() - start_time < wait_time:
223
- self._send_position_command(target_pos)
258
+ self._send_position_command(target_joint_pos)
224
259
  rate_limiter.sleep()
225
260
  if exit_on_reach and self.is_joint_pos_reached(
226
- target_pos, **exit_on_reach_kwargs
261
+ target_joint_pos, **exit_on_reach_kwargs
227
262
  ):
228
263
  break
229
264
 
@@ -235,6 +270,16 @@ class Arm(RobotJointComponent):
235
270
  ) -> None:
236
271
  """Controls the arm in joint position mode with a velocity feedforward term.
237
272
 
273
+ Warning:
274
+ The joint_vel parameter should be well-planned (such as from a trajectory planner).
275
+ Sending poorly planned or inappropriate joint velocity commands can cause the robot
276
+ to behave unexpectedly or potentially get damaged. Ensure velocity commands are
277
+ smooth, within safe limits, and properly coordinated across all joints.
278
+
279
+ Additionally, this command MUST be called at high frequency (e.g., 100Hz) to take
280
+ effect properly. DO NOT call this function just once or at low frequency, as this
281
+ can lead to unpredictable robot behavior.
282
+
238
283
  Args:
239
284
  joint_pos: Joint positions as either:
240
285
  - List of joint values [j1, j2, ..., j7]
@@ -244,6 +289,7 @@ class Arm(RobotJointComponent):
244
289
  - List of joint values [v1, v2, ..., v7]
245
290
  - Numpy array with shape (7,), in radians/sec
246
291
  - Dictionary of joint names and velocity values
292
+
247
293
  relative: If True, the joint positions are relative to the current position.
248
294
 
249
295
  Raises:
@@ -252,30 +298,19 @@ class Arm(RobotJointComponent):
252
298
  resolved_joint_pos = (
253
299
  self._resolve_relative_joint_cmd(joint_pos) if relative else joint_pos
254
300
  )
255
-
256
- # Convert inputs to numpy arrays
257
- if isinstance(resolved_joint_pos, (list, dict)):
258
- target_pos = (
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)
301
+ resolved_joint_pos = self._convert_joint_cmd_to_array(resolved_joint_pos)
302
+ if self._joint_limit is not None:
303
+ resolved_joint_pos = np.clip(
304
+ resolved_joint_pos, self._joint_limit[:, 0], self._joint_limit[:, 1]
262
305
  )
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)
271
- )
272
- else:
273
- target_vel = joint_vel
306
+ target_pos = resolved_joint_pos
307
+ target_vel = self._convert_joint_cmd_to_array(
308
+ joint_vel, clip_value=self._joint_vel_limit
309
+ )
274
310
 
275
- control_msg = dexcontrol_msg_pb2.ArmCommand(
276
- command_type=dexcontrol_msg_pb2.ArmCommand.CommandType.VELOCITY_FEEDFORWARD,
277
- joint_pos=list(target_pos),
278
- joint_vel=list(target_vel),
311
+ control_msg = dexcontrol_msg_pb2.MotorPosVelCurrentCommand(
312
+ pos=list(target_pos),
313
+ vel=list(target_vel),
279
314
  )
280
315
  self._publish_control(control_msg)
281
316
 
@@ -296,6 +331,16 @@ class Arm(RobotJointComponent):
296
331
  if self.wrench_sensor:
297
332
  self.wrench_sensor.shutdown()
298
333
 
334
+ def send_ee_pass_through_message(self, message: bytes):
335
+ """Send an end effector pass through message to the robot arm.
336
+
337
+ Args:
338
+ message: The message to send to the robot arm.
339
+ """
340
+ control_msg = dexcontrol_msg_pb2.EndEffectorPassThroughCommand(data=message)
341
+ control_data = control_msg.SerializeToString()
342
+ self._ee_pass_through_publisher.put(control_data)
343
+
299
344
 
300
345
  class ArmWrenchSensor(RobotComponent):
301
346
  """Wrench sensor reader for the robot arm.