kuavo-humanoid-sdk-ws 1.2.2__20250922181225-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.
- kuavo_humanoid_sdk/__init__.py +6 -0
- kuavo_humanoid_sdk/common/logger.py +45 -0
- kuavo_humanoid_sdk/common/websocket_kuavo_sdk.py +26 -0
- kuavo_humanoid_sdk/interfaces/__init__.py +4 -0
- kuavo_humanoid_sdk/interfaces/data_types.py +293 -0
- kuavo_humanoid_sdk/interfaces/end_effector.py +62 -0
- kuavo_humanoid_sdk/interfaces/robot.py +22 -0
- kuavo_humanoid_sdk/interfaces/robot_info.py +56 -0
- kuavo_humanoid_sdk/kuavo/__init__.py +11 -0
- kuavo_humanoid_sdk/kuavo/core/audio.py +32 -0
- kuavo_humanoid_sdk/kuavo/core/core.py +602 -0
- kuavo_humanoid_sdk/kuavo/core/dex_hand_control.py +114 -0
- kuavo_humanoid_sdk/kuavo/core/leju_claw_control.py +67 -0
- kuavo_humanoid_sdk/kuavo/core/ros/audio.py +86 -0
- kuavo_humanoid_sdk/kuavo/core/ros/control.py +1045 -0
- kuavo_humanoid_sdk/kuavo/core/ros/observation.py +125 -0
- kuavo_humanoid_sdk/kuavo/core/ros/param.py +246 -0
- kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
- kuavo_humanoid_sdk/kuavo/core/ros/state.py +426 -0
- kuavo_humanoid_sdk/kuavo/core/ros/tools.py +196 -0
- kuavo_humanoid_sdk/kuavo/core/ros/vision.py +280 -0
- kuavo_humanoid_sdk/kuavo/core/ros_env.py +233 -0
- kuavo_humanoid_sdk/kuavo/dexterous_hand.py +198 -0
- kuavo_humanoid_sdk/kuavo/leju_claw.py +232 -0
- kuavo_humanoid_sdk/kuavo/robot.py +462 -0
- kuavo_humanoid_sdk/kuavo/robot_arm.py +192 -0
- kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
- kuavo_humanoid_sdk/kuavo/robot_head.py +39 -0
- kuavo_humanoid_sdk/kuavo/robot_info.py +114 -0
- kuavo_humanoid_sdk/kuavo/robot_observation.py +69 -0
- kuavo_humanoid_sdk/kuavo/robot_state.py +303 -0
- kuavo_humanoid_sdk/kuavo/robot_tool.py +58 -0
- kuavo_humanoid_sdk/kuavo/robot_vision.py +82 -0
- kuavo_humanoid_sdk/kuavo_strategy/__init__.py +2 -0
- kuavo_humanoid_sdk/kuavo_strategy/grasp_box/grasp_box_strategy.py +418 -0
- kuavo_humanoid_sdk/kuavo_strategy/kuavo_strategy.py +63 -0
- kuavo_humanoid_sdk/msg/__init__.py +4 -0
- kuavo_humanoid_sdk_ws-1.2.2.dist-info/METADATA +276 -0
- kuavo_humanoid_sdk_ws-1.2.2.dist-info/RECORD +41 -0
- kuavo_humanoid_sdk_ws-1.2.2.dist-info/WHEEL +6 -0
- kuavo_humanoid_sdk_ws-1.2.2.dist-info/top_level.txt +1 -0
|
@@ -0,0 +1,1045 @@
|
|
|
1
|
+
import os
|
|
2
|
+
import roslibpy
|
|
3
|
+
import numpy as np
|
|
4
|
+
from typing import Tuple
|
|
5
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
6
|
+
from kuavo_humanoid_sdk.common.websocket_kuavo_sdk import WebSocketKuavoSDK
|
|
7
|
+
from kuavo_humanoid_sdk.interfaces.data_types import (KuavoArmCtrlMode, KuavoIKParams, KuavoPose,
|
|
8
|
+
KuavoManipulationMpcControlFlow, KuavoManipulationMpcCtrlMode
|
|
9
|
+
,KuavoManipulationMpcFrame)
|
|
10
|
+
from kuavo_humanoid_sdk.kuavo.core.ros.sat_utils import RotatingRectangle
|
|
11
|
+
from kuavo_humanoid_sdk.kuavo.core.ros.param import EndEffectorType
|
|
12
|
+
|
|
13
|
+
|
|
14
|
+
class ControlEndEffectorWebsocket:
|
|
15
|
+
def __init__(self, eef_type: str = EndEffectorType.QIANGNAO):
|
|
16
|
+
self._eef_type = eef_type
|
|
17
|
+
self._pubs = []
|
|
18
|
+
websocket = WebSocketKuavoSDK()
|
|
19
|
+
if self._eef_type == EndEffectorType.QIANGNAO:
|
|
20
|
+
self._pub_ctrl_robot_hand = roslibpy.Topic(websocket.client, '/control_robot_hand_position', 'kuavo_msgs/robotHandPosition')
|
|
21
|
+
# publisher, name, require
|
|
22
|
+
self._pubs.append((self._pub_ctrl_robot_hand, False))
|
|
23
|
+
elif self._eef_type == EndEffectorType.QIANGNAO_TOUCH:
|
|
24
|
+
self._pub_ctrl_robot_hand = roslibpy.Topic(websocket.client, '/control_robot_hand_position', 'kuavo_msgs/robotHandPosition')
|
|
25
|
+
self._pub_dexhand_command = roslibpy.Topic(websocket.client, '/dexhand/command', 'kuavo_msgs/dexhandCommand')
|
|
26
|
+
self._pub_dexhand_right_command = roslibpy.Topic(websocket.client, '/dexhand/right/command', 'kuavo_msgs/dexhandCommand')
|
|
27
|
+
self._pub_dexhand_left_command = roslibpy.Topic(websocket.client, '/dexhand/left/command', 'kuavo_msgs/dexhandCommand')
|
|
28
|
+
# publisher, name, require
|
|
29
|
+
self._pubs.append((self._pub_dexhand_command, False))
|
|
30
|
+
self._pubs.append((self._pub_dexhand_right_command, False))
|
|
31
|
+
self._pubs.append((self._pub_dexhand_left_command, False))
|
|
32
|
+
|
|
33
|
+
def connect(self, timeout:float=1.0)-> bool:
|
|
34
|
+
return True
|
|
35
|
+
|
|
36
|
+
def pub_control_robot_dexhand(self, left_position:list, right_position:list)->bool:
|
|
37
|
+
if not self._eef_type.startswith(EndEffectorType.QIANGNAO): # qiangnao, qiangnao_touch
|
|
38
|
+
SDKLogger.warning(f"{self._eef_type} not support control dexhand")
|
|
39
|
+
return False
|
|
40
|
+
try:
|
|
41
|
+
hand_pose_msg = {
|
|
42
|
+
"left_hand_position": left_position,
|
|
43
|
+
"right_hand_position": right_position
|
|
44
|
+
}
|
|
45
|
+
self._pub_ctrl_robot_hand.publish(roslibpy.Message(hand_pose_msg))
|
|
46
|
+
SDKLogger.debug(f"publish robot dexhand: {left_position}, {right_position}")
|
|
47
|
+
return True
|
|
48
|
+
except Exception as e:
|
|
49
|
+
SDKLogger.error(f"publish robot dexhand: {e}")
|
|
50
|
+
return False
|
|
51
|
+
|
|
52
|
+
def pub_dexhand_command(self, data:list, ctrl_mode, hand_side)->bool:
|
|
53
|
+
"""
|
|
54
|
+
ctrl_mode: 0 --> POSITION, 1 --> VELOCITY
|
|
55
|
+
hand_side: 0 --> left, 1 --> right, 2-->dual
|
|
56
|
+
"""
|
|
57
|
+
if not self._eef_type == EndEffectorType.QIANGNAO_TOUCH:
|
|
58
|
+
SDKLogger.warning(f"{self._eef_type} not support pub_left_dexhand_command")
|
|
59
|
+
return False
|
|
60
|
+
try:
|
|
61
|
+
if hand_side != 2 and len(data) != 6:
|
|
62
|
+
SDKLogger.warning("Data length should be 6")
|
|
63
|
+
return False
|
|
64
|
+
if hand_side == 2 and len(data) != 12:
|
|
65
|
+
SDKLogger.warning("Data length should be 12")
|
|
66
|
+
return False
|
|
67
|
+
if ctrl_mode not in [dexhandCommand.POSITION_CONTROL, dexhandCommand.VELOCITY_CONTROL]:
|
|
68
|
+
SDKLogger.error(f"Invalid mode for pub_left_dexhand_command: {ctrl_mode}")
|
|
69
|
+
return False
|
|
70
|
+
|
|
71
|
+
msg = {
|
|
72
|
+
"data": [int(d) for d in data], # Convert data to integers
|
|
73
|
+
"control_mode": ctrl_mode
|
|
74
|
+
}
|
|
75
|
+
if hand_side == 0:
|
|
76
|
+
self._pub_dexhand_left_command.publish(roslibpy.Message(msg))
|
|
77
|
+
elif hand_side == 1:
|
|
78
|
+
self._pub_dexhand_right_command.publish(roslibpy.Message(msg))
|
|
79
|
+
else:
|
|
80
|
+
self._pub_dexhand_command.publish(roslibpy.Message(msg))
|
|
81
|
+
return True
|
|
82
|
+
except Exception as e:
|
|
83
|
+
SDKLogger.error(f"Failed to publish left dexhand command: {e}")
|
|
84
|
+
return False
|
|
85
|
+
|
|
86
|
+
def srv_execute_gesture(self, gestures:list)->bool:
|
|
87
|
+
if not self._eef_type.startswith(EndEffectorType.QIANGNAO): # qiangnao, qiangnao_touch
|
|
88
|
+
SDKLogger.warning(f"{self._eef_type} not support control dexhand")
|
|
89
|
+
return False
|
|
90
|
+
try:
|
|
91
|
+
websocket = WebSocketKuavoSDK()
|
|
92
|
+
service = roslibpy.Service(websocket.client, 'gesture/execute', 'kuavo_msgs/gestureExecute')
|
|
93
|
+
request = {
|
|
94
|
+
"gestures": [
|
|
95
|
+
{
|
|
96
|
+
"gesture_name": gs["gesture_name"],
|
|
97
|
+
"hand_side": gs["hand_side"]
|
|
98
|
+
} for gs in gestures
|
|
99
|
+
]
|
|
100
|
+
}
|
|
101
|
+
response = service.call(request)
|
|
102
|
+
if not response.get('success', False):
|
|
103
|
+
SDKLogger.error(f"Failed to execute gesture '{gestures}': {response.get('message', '')}")
|
|
104
|
+
return response.get('success', False)
|
|
105
|
+
except Exception as e:
|
|
106
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
107
|
+
return False
|
|
108
|
+
|
|
109
|
+
def srv_get_gesture_names(self)->list:
|
|
110
|
+
if not self._eef_type.startswith(EndEffectorType.QIANGNAO): # qiangnao, qiangnao_touch
|
|
111
|
+
SDKLogger.warning(f"{self._eef_type} not support control dexhand")
|
|
112
|
+
return []
|
|
113
|
+
try:
|
|
114
|
+
websocket = WebSocketKuavoSDK()
|
|
115
|
+
service = roslibpy.Service(websocket.client, 'gesture/list', 'kuavo_msgs/gestureList')
|
|
116
|
+
request = {}
|
|
117
|
+
response = service.call(request)
|
|
118
|
+
gestures = []
|
|
119
|
+
for gesture_info in response.get('gesture_infos', []):
|
|
120
|
+
gestures.append(gesture_info['gesture_name'])
|
|
121
|
+
for alias in gesture_info.get('alias', []):
|
|
122
|
+
gestures.append(alias)
|
|
123
|
+
return list(set(gestures))
|
|
124
|
+
except Exception as e:
|
|
125
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
126
|
+
return []
|
|
127
|
+
|
|
128
|
+
def srv_control_leju_claw(self, postions:list, velocities:list, torques:list) ->bool:
|
|
129
|
+
if self._eef_type != 'lejuclaw':
|
|
130
|
+
SDKLogger.warning(f"{self._eef_type} not support control lejuclaw.")
|
|
131
|
+
return False
|
|
132
|
+
try:
|
|
133
|
+
websocket = WebSocketKuavoSDK()
|
|
134
|
+
service = roslibpy.Service(websocket.client, 'control_robot_leju_claw', 'kuavo_msgs/controlLejuClaw')
|
|
135
|
+
request = {
|
|
136
|
+
"data": {
|
|
137
|
+
"position": postions,
|
|
138
|
+
"velocity": velocities,
|
|
139
|
+
"effort": torques
|
|
140
|
+
}
|
|
141
|
+
}
|
|
142
|
+
response = service.call(request)
|
|
143
|
+
if not response.get('result', False):
|
|
144
|
+
SDKLogger.error(f"Failed to control leju claw: {response.get('message', '')}")
|
|
145
|
+
return response.get('result', False)
|
|
146
|
+
except Exception as e:
|
|
147
|
+
SDKLogger.error(f"Service `control_robot_leju_claw` call failed: {e}")
|
|
148
|
+
return False
|
|
149
|
+
|
|
150
|
+
class ControlRobotArmWebsocket:
|
|
151
|
+
def __init__(self):
|
|
152
|
+
websocket = WebSocketKuavoSDK()
|
|
153
|
+
self._pub_ctrl_arm_traj = roslibpy.Topic(websocket.client, '/kuavo_arm_traj', 'sensor_msgs/JointState')
|
|
154
|
+
self._pub_ctrl_arm_target_poses = roslibpy.Topic(websocket.client, '/kuavo_arm_target_poses', 'kuavo_msgs/armTargetPoses')
|
|
155
|
+
self._pub_ctrl_hand_pose_cmd = roslibpy.Topic(websocket.client, '/mm/two_arm_hand_pose_cmd', 'kuavo_msgs/twoArmHandPoseCmd')
|
|
156
|
+
self._pub_ctrl_arm_traj.advertise()
|
|
157
|
+
self._pub_ctrl_arm_target_poses.advertise()
|
|
158
|
+
self._pub_ctrl_hand_pose_cmd.advertise()
|
|
159
|
+
|
|
160
|
+
def connect(self, timeout:float=1.0)-> bool:
|
|
161
|
+
return True
|
|
162
|
+
|
|
163
|
+
def pub_control_robot_arm_traj(self, joint_q: list)->bool:
|
|
164
|
+
try:
|
|
165
|
+
msg = {
|
|
166
|
+
"name": ["arm_joint_" + str(i) for i in range(0, 14)],
|
|
167
|
+
"position": [float(180.0 / np.pi * q) for q in joint_q] # convert to degree
|
|
168
|
+
}
|
|
169
|
+
self._pub_ctrl_arm_traj.publish(roslibpy.Message(msg))
|
|
170
|
+
return True
|
|
171
|
+
except Exception as e:
|
|
172
|
+
SDKLogger.error(f"publish robot arm traj: {e}")
|
|
173
|
+
return False
|
|
174
|
+
|
|
175
|
+
def pub_arm_target_poses(self, times:list, joint_q:list):
|
|
176
|
+
try:
|
|
177
|
+
msg_values = []
|
|
178
|
+
for i in range(len(joint_q)):
|
|
179
|
+
degs = [float(q) for q in joint_q[i]]
|
|
180
|
+
msg_values.extend(degs)
|
|
181
|
+
msg = {
|
|
182
|
+
"times": [float(q) for q in times],
|
|
183
|
+
"values": msg_values
|
|
184
|
+
}
|
|
185
|
+
self._pub_ctrl_arm_target_poses.publish(roslibpy.Message(msg))
|
|
186
|
+
return True
|
|
187
|
+
except Exception as e:
|
|
188
|
+
SDKLogger.error(f"publish arm target poses: {e}")
|
|
189
|
+
|
|
190
|
+
return False
|
|
191
|
+
|
|
192
|
+
def pub_end_effector_pose_cmd(self, left_pose: KuavoPose, right_pose: KuavoPose, frame: KuavoManipulationMpcFrame)->bool:
|
|
193
|
+
try:
|
|
194
|
+
msg = {
|
|
195
|
+
"hand_poses": {
|
|
196
|
+
"left_pose": {
|
|
197
|
+
"pos_xyz": left_pose.position,
|
|
198
|
+
"quat_xyzw": left_pose.orientation
|
|
199
|
+
},
|
|
200
|
+
"right_pose": {
|
|
201
|
+
"pos_xyz": right_pose.position,
|
|
202
|
+
"quat_xyzw": right_pose.orientation
|
|
203
|
+
}
|
|
204
|
+
},
|
|
205
|
+
"frame": frame.value
|
|
206
|
+
}
|
|
207
|
+
if frame.value not in [0, 1, 2, 3, 4]:
|
|
208
|
+
SDKLogger.error(f"Invalid frame: {frame}")
|
|
209
|
+
return False
|
|
210
|
+
self._pub_ctrl_hand_pose_cmd.publish(roslibpy.Message(msg))
|
|
211
|
+
return True
|
|
212
|
+
except Exception as e:
|
|
213
|
+
SDKLogger.error(f"publish arm target poses: {e}")
|
|
214
|
+
return False
|
|
215
|
+
|
|
216
|
+
def srv_change_manipulation_mpc_frame(self, frame: KuavoManipulationMpcFrame)->bool:
|
|
217
|
+
try:
|
|
218
|
+
websocket = WebSocketKuavoSDK()
|
|
219
|
+
service = roslibpy.Service(websocket.client, '/set_mm_ctrl_frame', 'kuavo_msgs/setMmCtrlFrame')
|
|
220
|
+
request = {
|
|
221
|
+
"frame": frame.value
|
|
222
|
+
}
|
|
223
|
+
response = service.call(request)
|
|
224
|
+
if not response.get('result', False):
|
|
225
|
+
SDKLogger.error(f"Failed to change manipulation mpc frame to {frame}: {response.get('message', '')}")
|
|
226
|
+
return response.get('result', False)
|
|
227
|
+
except Exception as e:
|
|
228
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
229
|
+
return False
|
|
230
|
+
|
|
231
|
+
def srv_change_manipulation_mpc_ctrl_mode(self, ctrl_mode: KuavoManipulationMpcCtrlMode)->bool:
|
|
232
|
+
try:
|
|
233
|
+
websocket = WebSocketKuavoSDK()
|
|
234
|
+
service = roslibpy.Service(websocket.client, '/mobile_manipulator_mpc_control', 'kuavo_msgs/changeTorsoCtrlMode')
|
|
235
|
+
request = {
|
|
236
|
+
"control_mode": ctrl_mode.value
|
|
237
|
+
}
|
|
238
|
+
response = service.call(request)
|
|
239
|
+
if not response.get('result', False):
|
|
240
|
+
SDKLogger.error(f"Failed to change manipulation mpc control mode to {ctrl_mode}: {response.get('message', '')}")
|
|
241
|
+
return response.get('result', False)
|
|
242
|
+
except Exception as e:
|
|
243
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
244
|
+
return False
|
|
245
|
+
|
|
246
|
+
def srv_change_manipulation_mpc_control_flow(self, ctrl_flow: KuavoManipulationMpcControlFlow)-> bool:
|
|
247
|
+
try:
|
|
248
|
+
websocket = WebSocketKuavoSDK()
|
|
249
|
+
service = roslibpy.Service(websocket.client, '/enable_mm_wbc_arm_trajectory_control', 'kuavo_msgs/changeArmCtrlMode')
|
|
250
|
+
request = {
|
|
251
|
+
"control_mode": ctrl_flow.value
|
|
252
|
+
}
|
|
253
|
+
response = service.call(request)
|
|
254
|
+
if not response.get('result', False):
|
|
255
|
+
SDKLogger.error(f"Failed to change manipulation mpc wbc arm trajectory control to {ctrl_flow}: {response.get('message', '')}")
|
|
256
|
+
return response.get('result', False)
|
|
257
|
+
except Exception as e:
|
|
258
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
259
|
+
return False
|
|
260
|
+
|
|
261
|
+
def srv_get_manipulation_mpc_ctrl_mode(self, )->KuavoManipulationMpcCtrlMode:
|
|
262
|
+
try:
|
|
263
|
+
websocket = WebSocketKuavoSDK()
|
|
264
|
+
service = roslibpy.Service(websocket.client, '/mobile_manipulator_get_mpc_control_mode', 'kuavo_msgs/changeTorsoCtrlMode')
|
|
265
|
+
request = {}
|
|
266
|
+
response = service.call(request)
|
|
267
|
+
if not response.get('result', False):
|
|
268
|
+
SDKLogger.error(f"Failed to get manipulation mpc control mode: {response.get('message', '')}")
|
|
269
|
+
return KuavoManipulationMpcCtrlMode.ERROR
|
|
270
|
+
return KuavoManipulationMpcCtrlMode(response.get('mode', 0))
|
|
271
|
+
except Exception as e:
|
|
272
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
273
|
+
return KuavoManipulationMpcCtrlMode.ERROR
|
|
274
|
+
|
|
275
|
+
def srv_get_manipulation_mpc_frame(self, )->KuavoManipulationMpcFrame:
|
|
276
|
+
try:
|
|
277
|
+
websocket = WebSocketKuavoSDK()
|
|
278
|
+
service = roslibpy.Service(websocket.client, '/get_mm_ctrl_frame', 'kuavo_msgs/setMmCtrlFrame')
|
|
279
|
+
request = {}
|
|
280
|
+
response = service.call(request)
|
|
281
|
+
if not response.get('result', False):
|
|
282
|
+
SDKLogger.error(f"Failed to get manipulation mpc frame: {response.get('message', '')}")
|
|
283
|
+
return KuavoManipulationMpcFrame.ERROR
|
|
284
|
+
return KuavoManipulationMpcFrame(response.get('currentFrame', 0))
|
|
285
|
+
except Exception as e:
|
|
286
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
287
|
+
return KuavoManipulationMpcFrame.ERROR
|
|
288
|
+
|
|
289
|
+
def srv_get_manipulation_mpc_control_flow(self, )->KuavoManipulationMpcControlFlow:
|
|
290
|
+
try:
|
|
291
|
+
websocket = WebSocketKuavoSDK()
|
|
292
|
+
service = roslibpy.Service(websocket.client, '/get_mm_wbc_arm_trajectory_control', 'kuavo_msgs/changeArmCtrlMode')
|
|
293
|
+
request = {}
|
|
294
|
+
response = service.call(request)
|
|
295
|
+
if not response.get('result', False):
|
|
296
|
+
SDKLogger.error(f"Failed to get manipulation mpc wbc arm trajectory control mode: {response.get('message', '')}")
|
|
297
|
+
return KuavoManipulationMpcControlFlow.ERROR
|
|
298
|
+
return KuavoManipulationMpcControlFlow(response.get('mode', 0))
|
|
299
|
+
except Exception as e:
|
|
300
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
301
|
+
return KuavoManipulationMpcControlFlow.ERROR
|
|
302
|
+
|
|
303
|
+
def srv_change_arm_ctrl_mode(self, mode: KuavoArmCtrlMode)->bool:
|
|
304
|
+
try:
|
|
305
|
+
websocket = WebSocketKuavoSDK()
|
|
306
|
+
service = roslibpy.Service(websocket.client, '/arm_traj_change_mode', 'kuavo_msgs/changeArmCtrlMode')
|
|
307
|
+
request = {
|
|
308
|
+
"control_mode": mode.value
|
|
309
|
+
}
|
|
310
|
+
response = service.call(request)
|
|
311
|
+
return response.get('result', False)
|
|
312
|
+
except Exception as e:
|
|
313
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
314
|
+
return False
|
|
315
|
+
|
|
316
|
+
def srv_get_arm_ctrl_mode(self)-> KuavoArmCtrlMode:
|
|
317
|
+
try:
|
|
318
|
+
websocket = WebSocketKuavoSDK()
|
|
319
|
+
service = roslibpy.Service(websocket.client, '/humanoid_get_arm_ctrl_mode', 'kuavo_msgs/changeArmCtrlMode')
|
|
320
|
+
request = {}
|
|
321
|
+
response = service.call(request)
|
|
322
|
+
return KuavoArmCtrlMode(response.get('control_mode', 0))
|
|
323
|
+
except Exception as e:
|
|
324
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
325
|
+
return None
|
|
326
|
+
|
|
327
|
+
|
|
328
|
+
""" Control Robot Head """
|
|
329
|
+
class ControlRobotHeadWebsocket:
|
|
330
|
+
def __init__(self):
|
|
331
|
+
websocket = WebSocketKuavoSDK()
|
|
332
|
+
self._pub_ctrl_robot_head = roslibpy.Topic(websocket.client, '/robot_head_motion_data', 'kuavo_msgs/robotHeadMotionData')
|
|
333
|
+
self._pub_ctrl_robot_head.advertise()
|
|
334
|
+
|
|
335
|
+
def connect(self, timeout:float=1.0)->bool:
|
|
336
|
+
return True
|
|
337
|
+
|
|
338
|
+
def pub_control_robot_head(self, yaw:float, pitch:float)->bool:
|
|
339
|
+
try:
|
|
340
|
+
msg = {
|
|
341
|
+
"joint_data": [float(yaw), float(pitch)]
|
|
342
|
+
}
|
|
343
|
+
self._pub_ctrl_robot_head.publish(roslibpy.Message(msg))
|
|
344
|
+
return True
|
|
345
|
+
except Exception as e:
|
|
346
|
+
SDKLogger.error(f"[Error] publish robot head: {e}")
|
|
347
|
+
return False
|
|
348
|
+
|
|
349
|
+
def srv_enable_head_tracking(self, target_id: int)->bool:
|
|
350
|
+
"""Enable the head tracking for a specific tag ID.
|
|
351
|
+
|
|
352
|
+
Args:
|
|
353
|
+
target_id: The ID of the tag to track
|
|
354
|
+
|
|
355
|
+
Returns:
|
|
356
|
+
bool: True if successful, False otherwise
|
|
357
|
+
"""
|
|
358
|
+
try:
|
|
359
|
+
websocket = WebSocketKuavoSDK()
|
|
360
|
+
# First set the target tag ID
|
|
361
|
+
set_tag_service = roslibpy.Service(websocket.client, '/set_target_tag_id', 'kuavo_msgs/setTagId')
|
|
362
|
+
set_tag_request = {
|
|
363
|
+
"tag_id": target_id
|
|
364
|
+
}
|
|
365
|
+
set_tag_response = set_tag_service.call(set_tag_request)
|
|
366
|
+
if not set_tag_response.get('success', False):
|
|
367
|
+
SDKLogger.error(f"Failed to set target tag ID: {set_tag_response.get('message', '')}")
|
|
368
|
+
return False
|
|
369
|
+
|
|
370
|
+
SDKLogger.info(f"Successfully set target tag ID to {target_id}: {set_tag_response.get('message', '')}")
|
|
371
|
+
|
|
372
|
+
# Then start continuous tracking
|
|
373
|
+
track_service = roslibpy.Service(websocket.client, '/continuous_track', 'std_srvs/SetBool')
|
|
374
|
+
track_request = {
|
|
375
|
+
"data": True
|
|
376
|
+
}
|
|
377
|
+
track_response = track_service.call(track_request)
|
|
378
|
+
if not track_response.get('success', False):
|
|
379
|
+
SDKLogger.error(f"Failed to start continuous tracking: {track_response.get('message', '')}")
|
|
380
|
+
return False
|
|
381
|
+
|
|
382
|
+
SDKLogger.info(f"Successfully started continuous tracking: {track_response.get('message', '')}")
|
|
383
|
+
return True
|
|
384
|
+
|
|
385
|
+
except Exception as e:
|
|
386
|
+
SDKLogger.error(f"Failed to enable head tracking: {e}")
|
|
387
|
+
return False
|
|
388
|
+
|
|
389
|
+
def srv_disable_head_tracking(self)->bool:
|
|
390
|
+
"""Disable the head tracking.
|
|
391
|
+
|
|
392
|
+
Returns:
|
|
393
|
+
bool: True if successful, False otherwise
|
|
394
|
+
"""
|
|
395
|
+
try:
|
|
396
|
+
websocket = WebSocketKuavoSDK()
|
|
397
|
+
service = roslibpy.Service(websocket.client, '/continuous_track', 'std_srvs/SetBool')
|
|
398
|
+
request = {
|
|
399
|
+
"data": False
|
|
400
|
+
}
|
|
401
|
+
response = service.call(request)
|
|
402
|
+
if not response.get('success', False):
|
|
403
|
+
SDKLogger.error(f"Failed to stop continuous tracking: {response.get('message', '')}")
|
|
404
|
+
return False
|
|
405
|
+
|
|
406
|
+
SDKLogger.info(f"Successfully stopped continuous tracking: {response.get('message', '')}")
|
|
407
|
+
return True
|
|
408
|
+
|
|
409
|
+
except Exception as e:
|
|
410
|
+
SDKLogger.error(f"Failed to disable head tracking: {e}")
|
|
411
|
+
return False
|
|
412
|
+
|
|
413
|
+
""" Control Robot Motion """
|
|
414
|
+
|
|
415
|
+
# JoyButton constants
|
|
416
|
+
BUTTON_A = 0
|
|
417
|
+
BUTTON_B = 1
|
|
418
|
+
BUTTON_X = 2
|
|
419
|
+
BUTTON_Y = 3
|
|
420
|
+
BUTTON_LB = 4
|
|
421
|
+
BUTTON_RB = 5
|
|
422
|
+
BUTTON_BACK = 6
|
|
423
|
+
BUTTON_START = 7
|
|
424
|
+
|
|
425
|
+
# JoyAxis constants
|
|
426
|
+
AXIS_LEFT_STICK_Y = 0
|
|
427
|
+
AXIS_LEFT_STICK_X = 1
|
|
428
|
+
AXIS_LEFT_LT = 2 # 1 -> (-1)
|
|
429
|
+
AXIS_RIGHT_STICK_YAW = 3
|
|
430
|
+
AXIS_RIGHT_STICK_Z = 4
|
|
431
|
+
AXIS_RIGHT_RT = 5 # 1 -> (-1)
|
|
432
|
+
AXIS_LEFT_RIGHT_TRIGGER = 6
|
|
433
|
+
AXIS_FORWARD_BACK_TRIGGER = 7
|
|
434
|
+
|
|
435
|
+
|
|
436
|
+
class ControlRobotMotionWebsocket:
|
|
437
|
+
def __init__(self):
|
|
438
|
+
websocket = WebSocketKuavoSDK()
|
|
439
|
+
self._pub_cmd_vel = roslibpy.Topic(websocket.client, '/cmd_vel', 'geometry_msgs/Twist')
|
|
440
|
+
self._pub_cmd_pose = roslibpy.Topic(websocket.client, '/cmd_pose', 'geometry_msgs/Twist')
|
|
441
|
+
self._pub_cmd_pose_world = roslibpy.Topic(websocket.client, '/cmd_pose_world', 'geometry_msgs/Twist')
|
|
442
|
+
self._pub_joy = roslibpy.Topic(websocket.client, '/joy', 'sensor_msgs/Joy')
|
|
443
|
+
self._pub_switch_gait = roslibpy.Topic(websocket.client, '/humanoid_switch_gait_by_name', 'kuavo_msgs/switchGaitByName')
|
|
444
|
+
self._pub_step_ctrl = roslibpy.Topic(websocket.client, '/humanoid_mpc_foot_pose_target_trajectories', 'kuavo_msgs/footPoseTargetTrajectories')
|
|
445
|
+
self._pub_cmd_vel.advertise()
|
|
446
|
+
self._pub_cmd_pose.advertise()
|
|
447
|
+
self._pub_cmd_pose_world.advertise()
|
|
448
|
+
self._pub_joy.advertise()
|
|
449
|
+
self._pub_switch_gait.advertise()
|
|
450
|
+
self._pub_step_ctrl.advertise()
|
|
451
|
+
|
|
452
|
+
def connect(self, timeout:float=2.0)-> bool:
|
|
453
|
+
return True
|
|
454
|
+
|
|
455
|
+
def pub_cmd_vel(self, linear_x: float, linear_y: float, angular_z: float)->bool:
|
|
456
|
+
try:
|
|
457
|
+
msg = {
|
|
458
|
+
"linear": {"x": float(linear_x), "y": float(linear_y), "z": 0.0},
|
|
459
|
+
"angular": {"x": 0.0, "y": 0.0, "z": float(angular_z)}
|
|
460
|
+
}
|
|
461
|
+
self._pub_cmd_vel.publish(roslibpy.Message(msg))
|
|
462
|
+
return True
|
|
463
|
+
except Exception as e:
|
|
464
|
+
SDKLogger.error(f"[Error] publish cmd vel: {e}")
|
|
465
|
+
return False
|
|
466
|
+
|
|
467
|
+
def pub_cmd_pose(self, msg)->bool:
|
|
468
|
+
try:
|
|
469
|
+
self._pub_cmd_pose.publish(roslibpy.Message(msg))
|
|
470
|
+
return True
|
|
471
|
+
except Exception as e:
|
|
472
|
+
SDKLogger.error(f"[Error] publish cmd pose: {e}")
|
|
473
|
+
return False
|
|
474
|
+
|
|
475
|
+
def pub_cmd_pose_world(self, msg)->bool:
|
|
476
|
+
try:
|
|
477
|
+
self._pub_cmd_pose_world.publish(roslibpy.Message(msg))
|
|
478
|
+
return True
|
|
479
|
+
except Exception as e:
|
|
480
|
+
SDKLogger.error(f"[Error] publish cmd pose world: {e}")
|
|
481
|
+
return False
|
|
482
|
+
|
|
483
|
+
def _pub_joy_command(self, button_index: int, command_name: str) -> bool:
|
|
484
|
+
try:
|
|
485
|
+
msg = {
|
|
486
|
+
"axes": [0.0] * 8,
|
|
487
|
+
"buttons": [0] * 16
|
|
488
|
+
}
|
|
489
|
+
msg["buttons"][button_index] = 1
|
|
490
|
+
self._pub_joy.publish(roslibpy.Message(msg))
|
|
491
|
+
SDKLogger.debug(f"Published {command_name} command")
|
|
492
|
+
return True
|
|
493
|
+
except Exception as e:
|
|
494
|
+
SDKLogger.error(f"[Error] publish {command_name}: {e}")
|
|
495
|
+
return False
|
|
496
|
+
|
|
497
|
+
def _pub_switch_gait_by_name(self, gait_name: str) -> bool:
|
|
498
|
+
try:
|
|
499
|
+
msg = {
|
|
500
|
+
"gait_name": gait_name
|
|
501
|
+
}
|
|
502
|
+
self._pub_switch_gait.publish(roslibpy.Message(msg))
|
|
503
|
+
return True
|
|
504
|
+
except Exception as e:
|
|
505
|
+
SDKLogger.error(f"[Error] publish switch gait {gait_name}: {e}")
|
|
506
|
+
return False
|
|
507
|
+
|
|
508
|
+
def pub_walk_command(self) -> bool:
|
|
509
|
+
return self._pub_switch_gait_by_name("walk")
|
|
510
|
+
|
|
511
|
+
def pub_stance_command(self) -> bool:
|
|
512
|
+
try:
|
|
513
|
+
self.pub_cmd_vel(linear_x=0.0, linear_y=0.0, angular_z=0.0)
|
|
514
|
+
return self._pub_switch_gait_by_name("stance")
|
|
515
|
+
except Exception as e:
|
|
516
|
+
SDKLogger.error(f"[Error] publish stance: {e}")
|
|
517
|
+
return False
|
|
518
|
+
|
|
519
|
+
def pub_trot_command(self) -> bool:
|
|
520
|
+
return self._pub_switch_gait_by_name("walk")
|
|
521
|
+
|
|
522
|
+
def pub_step_ctrl(self, msg)->bool:
|
|
523
|
+
try:
|
|
524
|
+
websocket_msg = {
|
|
525
|
+
"timeTrajectory": msg["timeTrajectory"],
|
|
526
|
+
"footIndexTrajectory": msg["footIndexTrajectory"],
|
|
527
|
+
"footPoseTrajectory": [
|
|
528
|
+
{
|
|
529
|
+
"footPose": list(fp["footPose"]),
|
|
530
|
+
"torsoPose": list(fp["torsoPose"])
|
|
531
|
+
} for fp in msg["footPoseTrajectory"]
|
|
532
|
+
]
|
|
533
|
+
}
|
|
534
|
+
SDKLogger.debug(f"websocket_msg {websocket_msg}")
|
|
535
|
+
self._pub_step_ctrl.publish(roslibpy.Message(websocket_msg))
|
|
536
|
+
SDKLogger.debug(f"after publish")
|
|
537
|
+
return True
|
|
538
|
+
except Exception as e:
|
|
539
|
+
SDKLogger.error(f"[Error] publish step ctrl: {e}")
|
|
540
|
+
return False
|
|
541
|
+
|
|
542
|
+
|
|
543
|
+
class KuavoRobotArmIKFKWebsocket:
|
|
544
|
+
def __init__(self):
|
|
545
|
+
pass
|
|
546
|
+
|
|
547
|
+
def arm_ik(self,
|
|
548
|
+
left_pose: KuavoPose,
|
|
549
|
+
right_pose: KuavoPose,
|
|
550
|
+
left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
|
|
551
|
+
right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
|
|
552
|
+
arm_q0: list = None,
|
|
553
|
+
params: KuavoIKParams=None) -> list:
|
|
554
|
+
try:
|
|
555
|
+
websocket = WebSocketKuavoSDK()
|
|
556
|
+
service = roslibpy.Service(websocket.client, '/ik/two_arm_hand_pose_cmd_srv', 'kuavo_msgs/twoArmHandPoseCmdSrv')
|
|
557
|
+
|
|
558
|
+
request = {
|
|
559
|
+
"twoArmHandPoseCmdRequest": {
|
|
560
|
+
"hand_poses": {
|
|
561
|
+
"header": {
|
|
562
|
+
"seq": 0,
|
|
563
|
+
"stamp": {
|
|
564
|
+
"secs": 0,
|
|
565
|
+
"nsecs": 0
|
|
566
|
+
},
|
|
567
|
+
"frame_id": ""
|
|
568
|
+
},
|
|
569
|
+
"left_pose": {
|
|
570
|
+
"pos_xyz": left_pose.position,
|
|
571
|
+
"quat_xyzw": left_pose.orientation,
|
|
572
|
+
"elbow_pos_xyz": left_elbow_pos_xyz,
|
|
573
|
+
},
|
|
574
|
+
"right_pose": {
|
|
575
|
+
"pos_xyz": right_pose.position,
|
|
576
|
+
"quat_xyzw": right_pose.orientation,
|
|
577
|
+
"elbow_pos_xyz": right_elbow_pos_xyz,
|
|
578
|
+
}
|
|
579
|
+
},
|
|
580
|
+
"use_custom_ik_param": params is not None,
|
|
581
|
+
"joint_angles_as_q0": arm_q0 is not None,
|
|
582
|
+
"ik_param": {
|
|
583
|
+
"major_optimality_tol": params.major_optimality_tol if params else 0.0,
|
|
584
|
+
"major_feasibility_tol": params.major_feasibility_tol if params else 0.0,
|
|
585
|
+
"minor_feasibility_tol": params.minor_feasibility_tol if params else 0.0,
|
|
586
|
+
"major_iterations_limit": params.major_iterations_limit if params else 0,
|
|
587
|
+
"oritation_constraint_tol": params.oritation_constraint_tol if params else 0.0,
|
|
588
|
+
"pos_constraint_tol": params.pos_constraint_tol if params else 0.0,
|
|
589
|
+
"pos_cost_weight": params.pos_cost_weight if params else 0.0
|
|
590
|
+
}
|
|
591
|
+
}
|
|
592
|
+
}
|
|
593
|
+
|
|
594
|
+
response = service.call(request)
|
|
595
|
+
if response.get('success', False):
|
|
596
|
+
return response['hand_poses']['left_pose']['joint_angles'] + response['hand_poses']['right_pose']['joint_angles']
|
|
597
|
+
return None
|
|
598
|
+
except Exception as e:
|
|
599
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
600
|
+
return None
|
|
601
|
+
|
|
602
|
+
def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
|
|
603
|
+
try:
|
|
604
|
+
websocket = WebSocketKuavoSDK()
|
|
605
|
+
service = roslibpy.Service(websocket.client, '/ik/fk_srv', 'kuavo_msgs/fkSrv')
|
|
606
|
+
request = {"q": q}
|
|
607
|
+
response = service.call(request)
|
|
608
|
+
|
|
609
|
+
if response.get('success', False):
|
|
610
|
+
left_pose = KuavoPose(
|
|
611
|
+
position=response['hand_poses']['left_pose']['pos_xyz'],
|
|
612
|
+
orientation=response['hand_poses']['left_pose']['quat_xyzw']
|
|
613
|
+
)
|
|
614
|
+
right_pose = KuavoPose(
|
|
615
|
+
position=response['hand_poses']['right_pose']['pos_xyz'],
|
|
616
|
+
orientation=response['hand_poses']['right_pose']['quat_xyzw']
|
|
617
|
+
)
|
|
618
|
+
return left_pose, right_pose
|
|
619
|
+
return None
|
|
620
|
+
except Exception as e:
|
|
621
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
622
|
+
return None
|
|
623
|
+
|
|
624
|
+
"""
|
|
625
|
+
Kuavo Robot Control
|
|
626
|
+
"""
|
|
627
|
+
class KuavoRobotControlWebsocket:
|
|
628
|
+
_instance = None
|
|
629
|
+
|
|
630
|
+
def __new__(cls, *args, **kwargs):
|
|
631
|
+
if not cls._instance:
|
|
632
|
+
cls._instance = super().__new__(cls)
|
|
633
|
+
return cls._instance
|
|
634
|
+
|
|
635
|
+
def __init__(self):
|
|
636
|
+
if not hasattr(self, '_initialized'):
|
|
637
|
+
try:
|
|
638
|
+
self._initialized = True
|
|
639
|
+
self.kuavo_eef_control = None
|
|
640
|
+
self.kuavo_head_control = ControlRobotHeadWebsocket()
|
|
641
|
+
self.kuavo_arm_control = ControlRobotArmWebsocket()
|
|
642
|
+
self.kuavo_motion_control = ControlRobotMotionWebsocket()
|
|
643
|
+
self.kuavo_arm_ik_fk = KuavoRobotArmIKFKWebsocket()
|
|
644
|
+
except Exception as e:
|
|
645
|
+
SDKLogger.error(f"Failed to initialize KuavoRobotControlWebsocket: {e}")
|
|
646
|
+
raise
|
|
647
|
+
|
|
648
|
+
def initialize(self, eef_type:str=None, debug:bool=False, timeout:float=1.0)-> Tuple[bool, str]:
|
|
649
|
+
try:
|
|
650
|
+
# init eef control
|
|
651
|
+
if eef_type is None:
|
|
652
|
+
self.kuavo_eef_control = None
|
|
653
|
+
else:
|
|
654
|
+
self.kuavo_eef_control = ControlEndEffectorWebsocket(eef_type=eef_type)
|
|
655
|
+
|
|
656
|
+
connect_success = True
|
|
657
|
+
err_msg = ''
|
|
658
|
+
if not self.kuavo_arm_control.connect(timeout):
|
|
659
|
+
connect_success = False
|
|
660
|
+
err_msg = "Failed to connect to arm control topics, \n"
|
|
661
|
+
if not self.kuavo_head_control.connect(timeout):
|
|
662
|
+
connect_success = False
|
|
663
|
+
err_msg += "Failed to connect to head control topics, \n"
|
|
664
|
+
if not self.kuavo_motion_control.connect(timeout):
|
|
665
|
+
err_msg += "Failed to connect to motion control topics, \n"
|
|
666
|
+
connect_success = False
|
|
667
|
+
|
|
668
|
+
if self.kuavo_eef_control is not None and not self.kuavo_eef_control.connect(timeout):
|
|
669
|
+
connect_success = False
|
|
670
|
+
err_msg += "Failed to connect to end effector control topics."
|
|
671
|
+
|
|
672
|
+
if connect_success:
|
|
673
|
+
err_msg = 'success'
|
|
674
|
+
return connect_success, err_msg
|
|
675
|
+
except Exception as e:
|
|
676
|
+
SDKLogger.error(f"Failed to initialize KuavoRobotControlWebsocket: {e}")
|
|
677
|
+
return False, str(e)
|
|
678
|
+
|
|
679
|
+
""" End Effector Control"""
|
|
680
|
+
def control_robot_dexhand(self, left_position:list, right_position:list)->bool:
|
|
681
|
+
"""
|
|
682
|
+
Control robot dexhand
|
|
683
|
+
Args:
|
|
684
|
+
left_position: list of 6 floats between 0 and 100
|
|
685
|
+
right_position: list of 6 floats between 0 and 100
|
|
686
|
+
"""
|
|
687
|
+
if self.kuavo_eef_control is None:
|
|
688
|
+
SDKLogger.error("End effector control is not initialized.")
|
|
689
|
+
return False
|
|
690
|
+
|
|
691
|
+
if len(left_position) != 6 or len(right_position) != 6:
|
|
692
|
+
raise ValueError("Position lists must have a length of 6.")
|
|
693
|
+
|
|
694
|
+
for position in left_position + right_position:
|
|
695
|
+
if position < 0.0 or position > 100.0:
|
|
696
|
+
raise ValueError("All position values must be in the range [0.0, 100.0].")
|
|
697
|
+
|
|
698
|
+
SDKLogger.debug(f"Control robot dexhand: {left_position}, {right_position}")
|
|
699
|
+
return self.kuavo_eef_control.pub_control_robot_dexhand(left_position, right_position)
|
|
700
|
+
|
|
701
|
+
def robot_dexhand_command(self, data, ctrl_mode, hand_side):
|
|
702
|
+
"""
|
|
703
|
+
Publish dexhand command
|
|
704
|
+
Args:
|
|
705
|
+
- data: list of 6 floats between 0 and 100
|
|
706
|
+
- ctrl_mode: int between 0(position), 1(velocity)
|
|
707
|
+
- hand_side: int between 0(left), 1(right), 2(dual)
|
|
708
|
+
"""
|
|
709
|
+
if self.kuavo_eef_control is None:
|
|
710
|
+
SDKLogger.error("End effector control is not initialized.")
|
|
711
|
+
return False
|
|
712
|
+
return self.kuavo_eef_control.pub_dexhand_command(data, ctrl_mode, hand_side)
|
|
713
|
+
|
|
714
|
+
def execute_gesture(self, gestures:list)->bool:
|
|
715
|
+
"""
|
|
716
|
+
Execute gestures
|
|
717
|
+
Arguments:
|
|
718
|
+
- gestures: list of dicts with keys 'gesture_name' and 'hand_side'
|
|
719
|
+
e.g. [{'gesture_name': 'fist', 'hand_side': 0},]
|
|
720
|
+
"""
|
|
721
|
+
if self.kuavo_eef_control is None:
|
|
722
|
+
SDKLogger.warn("End effectors control is not initialized.")
|
|
723
|
+
return False
|
|
724
|
+
return self.kuavo_eef_control.srv_execute_gesture(gestures)
|
|
725
|
+
|
|
726
|
+
def get_gesture_names(self)->list:
|
|
727
|
+
"""
|
|
728
|
+
Get the names of all gestures.
|
|
729
|
+
"""
|
|
730
|
+
if self.kuavo_eef_control is None:
|
|
731
|
+
SDKLogger.warn("End effectors control is not initialized.")
|
|
732
|
+
return []
|
|
733
|
+
return self.kuavo_eef_control.srv_get_gesture_names()
|
|
734
|
+
|
|
735
|
+
def control_leju_claw(self, postions:list, velocities:list=[90, 90], torques:list=[1.0, 1.0]) ->bool:
|
|
736
|
+
"""
|
|
737
|
+
Control leju claw
|
|
738
|
+
Arguments:
|
|
739
|
+
- postions: list of positions for left and right claw
|
|
740
|
+
- velocities: list of velocities for left and right claw
|
|
741
|
+
- torques: list of torques for left and right claw
|
|
742
|
+
"""
|
|
743
|
+
if self.kuavo_eef_control is None:
|
|
744
|
+
SDKLogger.warn("End effectors control is not initialized.")
|
|
745
|
+
return False
|
|
746
|
+
SDKLogger.debug(f"Control leju claw: {postions}, {velocities}, {torques}")
|
|
747
|
+
if len(postions) != 2 or len(velocities) != 2 or len(torques) != 2:
|
|
748
|
+
raise ValueError("Position, velocity, and torque lists must have a length of 2.")
|
|
749
|
+
return self.kuavo_eef_control.srv_control_leju_claw(postions, velocities, torques)
|
|
750
|
+
|
|
751
|
+
def control_robot_head(self, yaw:float, pitch:float)->bool:
|
|
752
|
+
"""
|
|
753
|
+
Control robot head
|
|
754
|
+
Arguments:
|
|
755
|
+
- yaw: yaw angle, radian
|
|
756
|
+
- pitch: pitch angle, radian
|
|
757
|
+
"""
|
|
758
|
+
SDKLogger.debug(f"Control robot head: {yaw}, {pitch}")
|
|
759
|
+
return self.kuavo_head_control.pub_control_robot_head(yaw, pitch)
|
|
760
|
+
|
|
761
|
+
def control_robot_arm_joint_positions(self, joint_data:list)->bool:
|
|
762
|
+
"""
|
|
763
|
+
Control robot arm joint positions
|
|
764
|
+
Arguments:
|
|
765
|
+
- joint_data: list of joint data (degrees)
|
|
766
|
+
"""
|
|
767
|
+
return self.kuavo_arm_control.pub_control_robot_arm_traj(joint_data)
|
|
768
|
+
|
|
769
|
+
def control_robot_arm_joint_trajectory(self, times:list, joint_q:list)->bool:
|
|
770
|
+
"""
|
|
771
|
+
Control robot arm joint trajectory
|
|
772
|
+
Arguments:
|
|
773
|
+
- times: list of times (seconds)
|
|
774
|
+
- joint_q: list of joint data (degrees)
|
|
775
|
+
"""
|
|
776
|
+
if len(times) != len(joint_q):
|
|
777
|
+
raise ValueError("Times and joint_q must have the same length.")
|
|
778
|
+
elif len(times) == 0:
|
|
779
|
+
raise ValueError("Times and joint_q must not be empty.")
|
|
780
|
+
|
|
781
|
+
return self.kuavo_arm_control.pub_arm_target_poses(times=times, joint_q=joint_q)
|
|
782
|
+
|
|
783
|
+
def control_robot_end_effector_pose(self, left_pose: KuavoPose, right_pose: KuavoPose, frame: KuavoManipulationMpcFrame)->bool:
|
|
784
|
+
"""
|
|
785
|
+
Control robot end effector pose
|
|
786
|
+
Arguments:
|
|
787
|
+
- left_pose: left end effector pose
|
|
788
|
+
- right_pose: right end effector pose
|
|
789
|
+
- frame: frame of the end effector pose, 0: keep current frame, 1: world frame, 2: local frame, 3: VR frame, 4: manipulation world frame
|
|
790
|
+
"""
|
|
791
|
+
return self.kuavo_arm_control.pub_end_effector_pose_cmd(left_pose, right_pose, frame)
|
|
792
|
+
|
|
793
|
+
def change_manipulation_mpc_frame(self, frame: KuavoManipulationMpcFrame)->bool:
|
|
794
|
+
"""
|
|
795
|
+
Change manipulation mpc frame
|
|
796
|
+
Arguments:
|
|
797
|
+
- frame: frame of the manipulation mpc
|
|
798
|
+
"""
|
|
799
|
+
return self.kuavo_arm_control.srv_change_manipulation_mpc_frame(frame)
|
|
800
|
+
|
|
801
|
+
def change_manipulation_mpc_ctrl_mode(self, ctrl_mode: KuavoManipulationMpcCtrlMode)->bool:
|
|
802
|
+
"""
|
|
803
|
+
Change manipulation mpc control mode
|
|
804
|
+
Arguments:
|
|
805
|
+
- control_mode: control mode of the manipulation mpc
|
|
806
|
+
"""
|
|
807
|
+
return self.kuavo_arm_control.srv_change_manipulation_mpc_ctrl_mode(ctrl_mode)
|
|
808
|
+
|
|
809
|
+
def change_manipulation_mpc_control_flow(self, ctrl_flow: KuavoManipulationMpcControlFlow)->bool:
|
|
810
|
+
"""
|
|
811
|
+
Change manipulation mpc wbc arm traj control mode, control signal will be sent to wbc directly
|
|
812
|
+
Arguments:
|
|
813
|
+
- control_mode: control mode of the manipulation mpc wbc arm traj
|
|
814
|
+
"""
|
|
815
|
+
return self.kuavo_arm_control.srv_change_manipulation_mpc_control_flow(ctrl_flow)
|
|
816
|
+
|
|
817
|
+
def get_manipulation_mpc_ctrl_mode(self)->KuavoManipulationMpcCtrlMode:
|
|
818
|
+
"""
|
|
819
|
+
Get manipulation mpc control mode
|
|
820
|
+
"""
|
|
821
|
+
return self.kuavo_arm_control.srv_get_manipulation_mpc_ctrl_mode()
|
|
822
|
+
|
|
823
|
+
def get_manipulation_mpc_frame(self)-> KuavoManipulationMpcFrame:
|
|
824
|
+
"""
|
|
825
|
+
Get manipulation mpc frame
|
|
826
|
+
"""
|
|
827
|
+
return self.kuavo_arm_control.srv_get_manipulation_mpc_frame()
|
|
828
|
+
|
|
829
|
+
def get_manipulation_mpc_control_flow(self)->KuavoManipulationMpcControlFlow:
|
|
830
|
+
"""
|
|
831
|
+
Get manipulation mpc wbc arm traj control mode
|
|
832
|
+
"""
|
|
833
|
+
return self.kuavo_arm_control.srv_get_manipulation_mpc_control_flow()
|
|
834
|
+
|
|
835
|
+
def change_robot_arm_ctrl_mode(self, mode:KuavoArmCtrlMode)->bool:
|
|
836
|
+
"""
|
|
837
|
+
Change robot arm control mode
|
|
838
|
+
Arguments:
|
|
839
|
+
- mode: arm control mode
|
|
840
|
+
"""
|
|
841
|
+
SDKLogger.debug(f"[WebSocket] Change robot arm control mode: {mode}")
|
|
842
|
+
return self.kuavo_arm_control.srv_change_arm_ctrl_mode(mode)
|
|
843
|
+
|
|
844
|
+
def get_robot_arm_ctrl_mode(self)->int:
|
|
845
|
+
"""
|
|
846
|
+
Get robot arm control mode
|
|
847
|
+
"""
|
|
848
|
+
return self.kuavo_arm_control.srv_get_arm_ctrl_mode()
|
|
849
|
+
|
|
850
|
+
def arm_ik(self, left_pose: KuavoPose, right_pose: KuavoPose,
|
|
851
|
+
left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
|
|
852
|
+
right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
|
|
853
|
+
arm_q0: list = None, params: KuavoIKParams=None) -> list:
|
|
854
|
+
return self.kuavo_arm_ik_fk.arm_ik(left_pose, right_pose, left_elbow_pos_xyz, right_elbow_pos_xyz, arm_q0, params)
|
|
855
|
+
|
|
856
|
+
def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
|
|
857
|
+
return self.kuavo_arm_ik_fk.arm_fk(q)
|
|
858
|
+
|
|
859
|
+
""" Motion """
|
|
860
|
+
def robot_stance(self)->bool:
|
|
861
|
+
return self.kuavo_motion_control.pub_stance_command()
|
|
862
|
+
|
|
863
|
+
def robot_trot(self)->bool:
|
|
864
|
+
return self.kuavo_motion_control.pub_trot_command()
|
|
865
|
+
|
|
866
|
+
def robot_walk(self, linear_x:float, linear_y:float, angular_z:float)->bool:
|
|
867
|
+
return self.kuavo_motion_control.pub_cmd_vel(linear_x, linear_y, angular_z)
|
|
868
|
+
|
|
869
|
+
def control_torso_height(self, height:float, pitch:float=0.0)->bool:
|
|
870
|
+
msg = {
|
|
871
|
+
"linear": {"x": 0.0, "y": 0.0, "z": float(height)},
|
|
872
|
+
"angular": {"x": 0.0, "y": float(pitch), "z": 0.0}
|
|
873
|
+
}
|
|
874
|
+
return self.kuavo_motion_control.pub_cmd_pose(roslibpy.Message(msg))
|
|
875
|
+
|
|
876
|
+
def control_command_pose_world(self, target_pose_x:float, target_pose_y:float, target_pose_z:float, target_pose_yaw:float)->bool:
|
|
877
|
+
"""
|
|
878
|
+
odom下的机器人cmd_pose_world
|
|
879
|
+
"""
|
|
880
|
+
msg = {
|
|
881
|
+
"linear": {"x": float(target_pose_x), "y": float(target_pose_y), "z": float(target_pose_z)},
|
|
882
|
+
"angular": {"x": 0.0, "y": 0.0, "z": float(target_pose_yaw)}
|
|
883
|
+
}
|
|
884
|
+
return self.kuavo_motion_control.pub_cmd_pose_world(roslibpy.Message(msg))
|
|
885
|
+
|
|
886
|
+
def control_command_pose(self, target_pose_x:float, target_pose_y:float, target_pose_z:float, target_pose_yaw:float)->bool:
|
|
887
|
+
"""
|
|
888
|
+
base_link下的机器人cmd_pose
|
|
889
|
+
"""
|
|
890
|
+
msg = {
|
|
891
|
+
"linear": {"x": float(target_pose_x), "y": float(target_pose_y), "z": float(target_pose_z)},
|
|
892
|
+
"angular": {"x": 0.0, "y": 0.0, "z": float(target_pose_yaw)}
|
|
893
|
+
}
|
|
894
|
+
return self.kuavo_motion_control.pub_cmd_pose(roslibpy.Message(msg))
|
|
895
|
+
|
|
896
|
+
def step_control(self, body_poses:list, dt:float, is_left_first_default:bool=True, collision_check:bool=True)->bool:
|
|
897
|
+
"""
|
|
898
|
+
Step control
|
|
899
|
+
Arguments:
|
|
900
|
+
- body_poses: list of body poses (x, y, z, yaw), meters and degrees
|
|
901
|
+
- dt: time step (seconds)
|
|
902
|
+
- is_left_first_default: whether to start with left foot
|
|
903
|
+
- collision_check: whether to check for collisions
|
|
904
|
+
"""
|
|
905
|
+
if len(body_poses) == 0:
|
|
906
|
+
raise ValueError("Body poses must not be empty.")
|
|
907
|
+
if dt <= 0.0:
|
|
908
|
+
raise ValueError("Time step must be greater than 0.0.")
|
|
909
|
+
for bp in body_poses:
|
|
910
|
+
if len(bp) != 4:
|
|
911
|
+
raise ValueError("Body pose must have 4 elements: [x, y, z, yaw]")
|
|
912
|
+
|
|
913
|
+
msg = get_multiple_steps_msg(body_poses, dt, is_left_first_default, collision_check)
|
|
914
|
+
return self.kuavo_motion_control.pub_step_ctrl(msg)
|
|
915
|
+
|
|
916
|
+
|
|
917
|
+
def euler_to_rotation_matrix(yaw, pitch, roll):
|
|
918
|
+
# 计算各轴的旋转矩阵
|
|
919
|
+
R_yaw = np.array([[np.cos(yaw), -np.sin(yaw), 0],
|
|
920
|
+
[np.sin(yaw), np.cos(yaw), 0],
|
|
921
|
+
[0, 0, 1]])
|
|
922
|
+
|
|
923
|
+
R_pitch = np.array([[np.cos(pitch), 0, np.sin(pitch)],
|
|
924
|
+
[0, 1, 0],
|
|
925
|
+
[-np.sin(pitch), 0, np.cos(pitch)]])
|
|
926
|
+
|
|
927
|
+
R_roll = np.array([[1, 0, 0],
|
|
928
|
+
[0, np.cos(roll), -np.sin(roll)],
|
|
929
|
+
[0, np.sin(roll), np.cos(roll)]])
|
|
930
|
+
|
|
931
|
+
# 按照 Yaw-Pitch-Roll 的顺序组合旋转矩阵
|
|
932
|
+
R = np.dot(R_roll, np.dot(R_pitch, R_yaw))
|
|
933
|
+
return R
|
|
934
|
+
|
|
935
|
+
def get_foot_pose_traj_msg(time_traj:list, foot_idx_traj:list, foot_traj:list, torso_traj:list):
|
|
936
|
+
num = len(time_traj)
|
|
937
|
+
|
|
938
|
+
msg = {
|
|
939
|
+
"timeTrajectory": time_traj,
|
|
940
|
+
"footIndexTrajectory": foot_idx_traj,
|
|
941
|
+
"footPoseTrajectory": []
|
|
942
|
+
}
|
|
943
|
+
|
|
944
|
+
for i in range(num):
|
|
945
|
+
foot_pose = {
|
|
946
|
+
"footPose": foot_traj[i],
|
|
947
|
+
"torsoPose": torso_traj[i]
|
|
948
|
+
}
|
|
949
|
+
msg["footPoseTrajectory"].append(foot_pose)
|
|
950
|
+
|
|
951
|
+
|
|
952
|
+
return msg
|
|
953
|
+
|
|
954
|
+
def generate_steps(torso_pos, torso_yaw, foot_bias):
|
|
955
|
+
l_foot_bias = np.array([0, foot_bias, -torso_pos[2]])
|
|
956
|
+
r_foot_bias = np.array([0, -foot_bias, -torso_pos[2]])
|
|
957
|
+
R_z = np.array([
|
|
958
|
+
[np.cos(torso_yaw), -np.sin(torso_yaw), 0],
|
|
959
|
+
[np.sin(torso_yaw), np.cos(torso_yaw), 0],
|
|
960
|
+
[0, 0, 1]
|
|
961
|
+
])
|
|
962
|
+
l_foot = torso_pos + R_z.dot(l_foot_bias)
|
|
963
|
+
r_foot = torso_pos + R_z.dot(r_foot_bias)
|
|
964
|
+
return l_foot, r_foot
|
|
965
|
+
|
|
966
|
+
def get_multiple_steps_msg(body_poses:list, dt:float, is_left_first:bool=True, collision_check:bool=True):
|
|
967
|
+
num_steps = 2*len(body_poses)
|
|
968
|
+
time_traj = []
|
|
969
|
+
foot_idx_traj = []
|
|
970
|
+
foot_traj = []
|
|
971
|
+
torso_traj = []
|
|
972
|
+
l_foot_rect_last = RotatingRectangle(center=(0, 0.1), width=0.24, height=0.1, angle=0)
|
|
973
|
+
r_foot_rect_last = RotatingRectangle(center=(0,-0.1), width=0.24, height=0.1, angle=0)
|
|
974
|
+
torso_pose_last = np.array([0, 0, 0, 0])
|
|
975
|
+
for i in range(num_steps):
|
|
976
|
+
time_traj.append(dt * (i+1))
|
|
977
|
+
body_pose = body_poses[i//2]
|
|
978
|
+
torso_pos = np.asarray(body_pose[:3])
|
|
979
|
+
torso_yaw = np.radians(body_pose[3])
|
|
980
|
+
l_foot, r_foot = generate_steps(torso_pos, torso_yaw, 0.1)
|
|
981
|
+
l_foot = [*l_foot[:3], torso_yaw]
|
|
982
|
+
r_foot = [*r_foot[:3], torso_yaw]
|
|
983
|
+
|
|
984
|
+
if(i%2 == 0):
|
|
985
|
+
torso_pose = np.array([*body_pose[:3], torso_yaw])
|
|
986
|
+
R_wl = euler_to_rotation_matrix(torso_pose_last[3], 0, 0)
|
|
987
|
+
delta_pos = R_wl.T @ (torso_pose[:3] - torso_pose_last[:3])
|
|
988
|
+
# print("delta_pos:", delta_pos)
|
|
989
|
+
if(torso_yaw > 0.0 or delta_pos[1] > 0.0):
|
|
990
|
+
is_left_first = True
|
|
991
|
+
else:
|
|
992
|
+
is_left_first = False
|
|
993
|
+
|
|
994
|
+
if(collision_check and i%2 == 0):
|
|
995
|
+
l_foot_rect_next = RotatingRectangle(center=(l_foot[0],l_foot[1]), width=0.24, height=0.1, angle=torso_yaw)
|
|
996
|
+
r_foot_rect_next = RotatingRectangle(center=(r_foot[0],r_foot[1]), width=0.24, height=0.1, angle=torso_yaw)
|
|
997
|
+
l_collision = l_foot_rect_next.is_collision(r_foot_rect_last)
|
|
998
|
+
r_collision = r_foot_rect_next.is_collision(l_foot_rect_last)
|
|
999
|
+
if l_collision and r_collision:
|
|
1000
|
+
SDKLogger.error("[Control] Detect collision, Please adjust your body_poses input!!!")
|
|
1001
|
+
break
|
|
1002
|
+
elif l_collision:
|
|
1003
|
+
SDKLogger.warn("[Control] Left foot is in collision, switch to right foot")
|
|
1004
|
+
is_left_first = False
|
|
1005
|
+
elif r_collision:
|
|
1006
|
+
SDKLogger.warn("[Control] Right foot is in collision, switch to left foot")
|
|
1007
|
+
is_left_first = True
|
|
1008
|
+
l_foot_rect_last = l_foot_rect_next
|
|
1009
|
+
r_foot_rect_last = r_foot_rect_next
|
|
1010
|
+
if(i%2 == 0):
|
|
1011
|
+
torso_traj.append((torso_pose_last + torso_pose)/2.0)
|
|
1012
|
+
if is_left_first:
|
|
1013
|
+
foot_idx_traj.append(0)
|
|
1014
|
+
foot_traj.append(l_foot)
|
|
1015
|
+
else:
|
|
1016
|
+
foot_idx_traj.append(1)
|
|
1017
|
+
foot_traj.append(r_foot)
|
|
1018
|
+
else:
|
|
1019
|
+
torso_traj.append(torso_pose)
|
|
1020
|
+
if is_left_first:
|
|
1021
|
+
foot_idx_traj.append(1)
|
|
1022
|
+
foot_traj.append(r_foot)
|
|
1023
|
+
else:
|
|
1024
|
+
foot_idx_traj.append(0)
|
|
1025
|
+
foot_traj.append(l_foot)
|
|
1026
|
+
torso_pose_last = torso_traj[-1]
|
|
1027
|
+
# print("time_traj:", time_traj)
|
|
1028
|
+
# print("foot_idx_traj:", foot_idx_traj)
|
|
1029
|
+
# print("foot_traj:", foot_traj)
|
|
1030
|
+
# print("torso_traj:", torso_traj)
|
|
1031
|
+
return get_foot_pose_traj_msg(time_traj, foot_idx_traj, foot_traj, torso_traj)
|
|
1032
|
+
""" ------------------------------------------------------------------------------"""
|
|
1033
|
+
|
|
1034
|
+
|
|
1035
|
+
# if __name__ == "__main__":
|
|
1036
|
+
# control = KuavoRobotControl()
|
|
1037
|
+
# control.change_manipulation_mpc_frame(KuavoManipulationMpcFrame.KeepCurrentFrame)
|
|
1038
|
+
# control.change_manipulation_mpc_ctrl_mode(KuavoManipulationMpcCtrlMode.ArmOnly)
|
|
1039
|
+
# control.change_manipulation_mpc_control_flow(KuavoManipulationMpcControlFlow.DirectToWbc)
|
|
1040
|
+
# print(control.get_manipulation_mpc_ctrl_mode())
|
|
1041
|
+
# print(control.get_manipulation_mpc_frame())
|
|
1042
|
+
# print(control.get_manipulation_mpc_control_flow())
|
|
1043
|
+
# control.change_manipulation_mpc_frame(KuavoManipulationMpcFrame.WorldFrame)
|
|
1044
|
+
# control.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ExternalControl)
|
|
1045
|
+
# control.control_robot_end_effector_pose(KuavoPose(position=[0.3, 0.4, 0.9], orientation=[0.0, 0.0, 0.0, 1.0]), KuavoPose(position=[0.3, -0.5, 1.0], orientation=[0.0, 0.0, 0.0, 1.0]), KuavoManipulationMpcFrame.WorldFrame)
|