kuavo-humanoid-sdk 1.1.2a924__py3-none-any.whl → 1.1.3a1226__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 kuavo-humanoid-sdk might be problematic. Click here for more details.

Files changed (45) hide show
  1. kuavo_humanoid_sdk/common/global_config.py +15 -0
  2. kuavo_humanoid_sdk/common/websocket_kuavo_sdk.py +23 -0
  3. kuavo_humanoid_sdk/interfaces/data_types.py +46 -0
  4. kuavo_humanoid_sdk/kuavo/__init__.py +3 -0
  5. kuavo_humanoid_sdk/kuavo/core/audio.py +33 -0
  6. kuavo_humanoid_sdk/kuavo/core/core.py +16 -6
  7. kuavo_humanoid_sdk/kuavo/core/ros/audio.py +87 -0
  8. kuavo_humanoid_sdk/kuavo/core/ros/control.py +645 -19
  9. kuavo_humanoid_sdk/kuavo/core/ros/param.py +142 -4
  10. kuavo_humanoid_sdk/kuavo/core/ros/state.py +329 -15
  11. kuavo_humanoid_sdk/kuavo/core/ros/tools.py +149 -0
  12. kuavo_humanoid_sdk/kuavo/core/ros/vision.py +272 -0
  13. kuavo_humanoid_sdk/kuavo/core/ros_env.py +229 -1
  14. kuavo_humanoid_sdk/kuavo/dexterous_hand.py +6 -2
  15. kuavo_humanoid_sdk/kuavo/leju_claw.py +6 -2
  16. kuavo_humanoid_sdk/kuavo/robot.py +43 -22
  17. kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
  18. kuavo_humanoid_sdk/kuavo/robot_info.py +7 -2
  19. kuavo_humanoid_sdk/kuavo/robot_state.py +6 -2
  20. kuavo_humanoid_sdk/kuavo/robot_tool.py +62 -0
  21. kuavo_humanoid_sdk/kuavo/robot_vision.py +87 -0
  22. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetection.py +306 -0
  23. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetectionArray.py +437 -0
  24. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/__init__.py +9 -0
  25. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_armHandPose.py +2 -2
  26. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_handPose.py +2 -2
  27. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_ikSolveError.py +13 -13
  28. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_ikSolveParam.py +2 -2
  29. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_robotArmQVVD.py +2 -2
  30. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_twoArmHandPose.py +13 -13
  31. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_twoArmHandPoseCmd.py +15 -15
  32. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SpeechSynthesis.py +270 -0
  33. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/__init__.py +5 -0
  34. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/srv/_changeArmCtrlModeKuavo.py +5 -5
  35. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/srv/_fkSrv.py +13 -13
  36. kuavo_humanoid_sdk/msg/{motion_capture_ik/srv/_changeArmCtrlMode.py → kuavo_msgs/srv/_playmusic.py} +97 -98
  37. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/srv/_twoArmHandPoseCmdSrv.py +23 -23
  38. {kuavo_humanoid_sdk-1.1.2a924.dist-info → kuavo_humanoid_sdk-1.1.3a1226.dist-info}/METADATA +2 -1
  39. {kuavo_humanoid_sdk-1.1.2a924.dist-info → kuavo_humanoid_sdk-1.1.3a1226.dist-info}/RECORD +41 -33
  40. kuavo_humanoid_sdk/msg/motion_capture_ik/msg/__init__.py +0 -9
  41. kuavo_humanoid_sdk/msg/motion_capture_ik/msg/_headBodyPose.py +0 -145
  42. kuavo_humanoid_sdk/msg/motion_capture_ik/msg/_robotHandPosition.py +0 -225
  43. kuavo_humanoid_sdk/msg/motion_capture_ik/srv/__init__.py +0 -4
  44. {kuavo_humanoid_sdk-1.1.2a924.dist-info → kuavo_humanoid_sdk-1.1.3a1226.dist-info}/WHEEL +0 -0
  45. {kuavo_humanoid_sdk-1.1.2a924.dist-info → kuavo_humanoid_sdk-1.1.3a1226.dist-info}/top_level.txt +0 -0
@@ -1,19 +1,28 @@
1
+ from kuavo_humanoid_sdk.common.global_config import GlobalConfig
1
2
  import os
2
- import rospy
3
+ import roslibpy
3
4
  import numpy as np
4
5
  from typing import Tuple
5
6
  from kuavo_humanoid_sdk.common.logger import SDKLogger
7
+ from kuavo_humanoid_sdk.common.websocket_kuavo_sdk import WebSocketKuavoSDK
6
8
  from kuavo_humanoid_sdk.interfaces.data_types import KuavoArmCtrlMode, KuavoIKParams, KuavoPose
7
9
  from kuavo_humanoid_sdk.kuavo.core.ros.sat_utils import RotatingRectangle
8
10
  from kuavo_humanoid_sdk.kuavo.core.ros.param import EndEffectorType
9
- from geometry_msgs.msg import Twist
10
- from sensor_msgs.msg import JointState, Joy
11
- from kuavo_humanoid_sdk.msg.kuavo_msgs.msg import (gestureTask,robotHandPosition, robotHeadMotionData, armTargetPoses, switchGaitByName,
12
- footPose, footPoseTargetTrajectories, dexhandCommand)
13
- from kuavo_humanoid_sdk.msg.kuavo_msgs.srv import (gestureExecute, gestureExecuteRequest,gestureList, gestureListRequest,
11
+
12
+ try:
13
+ import rospy
14
+ from geometry_msgs.msg import Twist
15
+ from sensor_msgs.msg import JointState, Joy
16
+ from kuavo_humanoid_sdk.msg.kuavo_msgs.msg import (gestureTask,robotHandPosition, robotHeadMotionData, armTargetPoses, switchGaitByName,
17
+ footPose, footPoseTargetTrajectories, dexhandCommand)
18
+ from kuavo_humanoid_sdk.msg.kuavo_msgs.srv import (gestureExecute, gestureExecuteRequest,gestureList, gestureListRequest,
14
19
  controlLejuClaw, controlLejuClawRequest, changeArmCtrlMode, changeArmCtrlModeRequest)
15
- from kuavo_humanoid_sdk.msg.motion_capture_ik.msg import twoArmHandPoseCmd, ikSolveParam
16
- from kuavo_humanoid_sdk.msg.motion_capture_ik.srv import twoArmHandPoseCmdSrv, fkSrv
20
+ from kuavo_humanoid_sdk.msg.kuavo_msgs.msg import twoArmHandPoseCmd, ikSolveParam
21
+ from kuavo_humanoid_sdk.msg.kuavo_msgs.srv import twoArmHandPoseCmdSrv, fkSrv
22
+ except:
23
+ pass
24
+
25
+
17
26
 
18
27
  class ControlEndEffector:
19
28
  def __init__(self, eef_type: str = EndEffectorType.QIANGNAO):
@@ -175,7 +184,205 @@ class ControlEndEffector:
175
184
  SDKLogger.error(f"Service `control_robot_leju_claw` call failed: {e}")
176
185
  return False
177
186
 
178
- """ Control Robot Arm"""
187
+ class ControlEndEffectorWebsocket:
188
+ def __init__(self, eef_type: str = EndEffectorType.QIANGNAO):
189
+ self._eef_type = eef_type
190
+ self._pubs = []
191
+ websocket = WebSocketKuavoSDK()
192
+ if self._eef_type == EndEffectorType.QIANGNAO:
193
+ self._pub_ctrl_robot_hand = roslibpy.Topic(websocket.client, '/control_robot_hand_position', 'kuavo_msgs/robotHandPosition')
194
+ # publisher, name, require
195
+ self._pubs.append((self._pub_ctrl_robot_hand, True))
196
+ elif self._eef_type == EndEffectorType.QIANGNAO_TOUCH:
197
+ self._pub_ctrl_robot_hand = roslibpy.Topic(websocket.client, '/control_robot_hand_position', 'kuavo_msgs/robotHandPosition')
198
+ self._pub_dexhand_command = roslibpy.Topic(websocket.client, '/dexhand/command', 'kuavo_msgs/dexhandCommand')
199
+ self._pub_dexhand_right_command = roslibpy.Topic(websocket.client, '/dexhand/right/command', 'kuavo_msgs/dexhandCommand')
200
+ self._pub_dexhand_left_command = roslibpy.Topic(websocket.client, '/dexhand/left/command', 'kuavo_msgs/dexhandCommand')
201
+ # publisher, name, require
202
+ self._pubs.append((self._pub_dexhand_command, True))
203
+ self._pubs.append((self._pub_dexhand_right_command, True))
204
+ self._pubs.append((self._pub_dexhand_left_command, True))
205
+
206
+ def connect(self, timeout:float=1.0)-> bool:
207
+ return True
208
+
209
+ def pub_control_robot_dexhand(self, left_position:list, right_position:list)->bool:
210
+ if not self._eef_type.startswith(EndEffectorType.QIANGNAO): # qiangnao, qiangnao_touch
211
+ SDKLogger.warning(f"{self._eef_type} not support control dexhand")
212
+ return False
213
+ try:
214
+ hand_pose_msg = {
215
+ "left_hand_position": bytes(left_position),
216
+ "right_hand_position": bytes(right_position)
217
+ }
218
+ self._pub_ctrl_robot_hand.publish(roslibpy.Message(hand_pose_msg))
219
+ SDKLogger.debug(f"publish robot dexhand: {left_position}, {right_position}")
220
+ return True
221
+ except Exception as e:
222
+ SDKLogger.error(f"publish robot dexhand: {e}")
223
+ return False
224
+
225
+ def pub_dexhand_command(self, data:list, ctrl_mode, hand_side)->bool:
226
+ """
227
+ ctrl_mode: 0 --> POSITION, 1 --> VELOCITY
228
+ hand_side: 0 --> left, 1 --> right, 2-->dual
229
+ """
230
+ if not self._eef_type == EndEffectorType.QIANGNAO_TOUCH:
231
+ SDKLogger.warning(f"{self._eef_type} not support pub_left_dexhand_command")
232
+ return False
233
+ try:
234
+ if hand_side != 2 and len(data) != 6:
235
+ SDKLogger.warning("Data length should be 6")
236
+ return False
237
+ if hand_side == 2 and len(data) != 12:
238
+ SDKLogger.warning("Data length should be 12")
239
+ return False
240
+ if ctrl_mode not in [dexhandCommand.POSITION_CONTROL, dexhandCommand.VELOCITY_CONTROL]:
241
+ SDKLogger.error(f"Invalid mode for pub_left_dexhand_command: {ctrl_mode}")
242
+ return False
243
+
244
+ msg = {
245
+ "data": [int(d) for d in data], # Convert data to integers
246
+ "control_mode": ctrl_mode
247
+ }
248
+ if hand_side == 0:
249
+ self._pub_dexhand_left_command.publish(roslibpy.Message(msg))
250
+ elif hand_side == 1:
251
+ self._pub_dexhand_right_command.publish(roslibpy.Message(msg))
252
+ else:
253
+ self._pub_dexhand_command.publish(roslibpy.Message(msg))
254
+ return True
255
+ except Exception as e:
256
+ SDKLogger.error(f"Failed to publish left dexhand command: {e}")
257
+ return False
258
+
259
+ def srv_execute_gesture(self, gestures:list)->bool:
260
+ if not self._eef_type.startswith(EndEffectorType.QIANGNAO): # qiangnao, qiangnao_touch
261
+ SDKLogger.warning(f"{self._eef_type} not support control dexhand")
262
+ return False
263
+ try:
264
+ websocket = WebSocketKuavoSDK()
265
+ service = roslibpy.Service(websocket.client, 'gesture/execute', 'kuavo_msgs/gestureExecute')
266
+ request = {
267
+ "gestures": [
268
+ {
269
+ "gesture_name": gs["gesture_name"],
270
+ "hand_side": gs["hand_side"]
271
+ } for gs in gestures
272
+ ]
273
+ }
274
+ response = service.call(request)
275
+ if not response.get('result', False):
276
+ SDKLogger.error(f"Failed to execute gesture '{gestures}': {response.get('message', '')}")
277
+ return response.get('result', False)
278
+ except Exception as e:
279
+ SDKLogger.error(f"Service call failed: {e}")
280
+ return False
281
+
282
+ def srv_get_gesture_names(self)->list:
283
+ if not self._eef_type.startswith(EndEffectorType.QIANGNAO): # qiangnao, qiangnao_touch
284
+ SDKLogger.warning(f"{self._eef_type} not support control dexhand")
285
+ return []
286
+ try:
287
+ websocket = WebSocketKuavoSDK()
288
+ service = roslibpy.Service(websocket.client, 'gesture/list', 'kuavo_msgs/gestureList')
289
+ request = {}
290
+ response = service.call(request)
291
+ gestures = []
292
+ for gesture_info in response.get('gesture_infos', []):
293
+ gestures.append(gesture_info['gesture_name'])
294
+ for alias in gesture_info.get('alias', []):
295
+ gestures.append(alias)
296
+ return list(set(gestures))
297
+ except Exception as e:
298
+ SDKLogger.error(f"Service call failed: {e}")
299
+ return []
300
+
301
+ def srv_control_leju_claw(self, postions:list, velocities:list, torques:list) ->bool:
302
+ if self._eef_type != 'lejuclaw':
303
+ SDKLogger.warning(f"{self._eef_type} not support control lejuclaw.")
304
+ return False
305
+ try:
306
+ websocket = WebSocketKuavoSDK()
307
+ service = roslibpy.Service(websocket.client, 'control_robot_leju_claw', 'kuavo_msgs/controlLejuClaw')
308
+ request = {
309
+ "data": {
310
+ "position": postions,
311
+ "velocity": velocities,
312
+ "effort": torques
313
+ }
314
+ }
315
+ response = service.call(request)
316
+ if not response.get('result', False):
317
+ SDKLogger.error(f"Failed to control leju claw: {response.get('message', '')}")
318
+ return response.get('result', False)
319
+ except Exception as e:
320
+ SDKLogger.error(f"Service `control_robot_leju_claw` call failed: {e}")
321
+ return False
322
+
323
+ class ControlRobotArmWebsocket:
324
+ def __init__(self):
325
+ websocket = WebSocketKuavoSDK()
326
+ self._pub_ctrl_arm_traj = roslibpy.Topic(websocket.client, '/kuavo_arm_traj', 'sensor_msgs/JointState')
327
+ self._pub_ctrl_arm_traj.advertise()
328
+ self._pub_ctrl_arm_target_poses = roslibpy.Topic(websocket.client, '/kuavo_arm_target_poses', 'kuavo_msgs/armTargetPoses')
329
+ self._pub_ctrl_arm_target_poses.advertise()
330
+ def connect(self, timeout:float=1.0)-> bool:
331
+ return True
332
+
333
+ def pub_control_robot_arm_traj(self, joint_q: list)->bool:
334
+ try:
335
+ msg = {
336
+ "name": ["arm_joint_" + str(i) for i in range(0, 14)],
337
+ "position": [float(180.0 / np.pi * q) for q in joint_q] # convert to degree
338
+ }
339
+ self._pub_ctrl_arm_traj.publish(roslibpy.Message(msg))
340
+ return True
341
+ except Exception as e:
342
+ SDKLogger.error(f"publish robot arm traj: {e}")
343
+ return False
344
+
345
+ def pub_arm_target_poses(self, times:list, joint_q:list):
346
+ try:
347
+ msg_values = []
348
+ for i in range(len(joint_q)):
349
+ degs = [float(q) for q in joint_q[i]]
350
+ msg_values.extend(degs)
351
+ msg = {
352
+ "times": [float(q) for q in times],
353
+ "values": msg_values
354
+ }
355
+ self._pub_ctrl_arm_target_poses.publish(roslibpy.Message(msg))
356
+ return True
357
+ except Exception as e:
358
+ SDKLogger.error(f"publish arm target poses: {e}")
359
+
360
+ return False
361
+
362
+ def srv_change_arm_ctrl_mode(self, mode: KuavoArmCtrlMode)->bool:
363
+ try:
364
+ websocket = WebSocketKuavoSDK()
365
+ service = roslibpy.Service(websocket.client, '/arm_traj_change_mode', 'kuavo_msgs/changeArmCtrlMode')
366
+ request = {
367
+ "control_mode": mode.value
368
+ }
369
+ response = service.call(request)
370
+ return response.get('result', False)
371
+ except Exception as e:
372
+ SDKLogger.error(f"Service call failed: {e}")
373
+ return False
374
+
375
+ def srv_get_arm_ctrl_mode(self)-> KuavoArmCtrlMode:
376
+ try:
377
+ websocket = WebSocketKuavoSDK()
378
+ service = roslibpy.Service(websocket.client, '/humanoid_get_arm_ctrl_mode', 'kuavo_msgs/changeArmCtrlMode')
379
+ request = {}
380
+ response = service.call(request)
381
+ return KuavoArmCtrlMode(response.get('control_mode', 0))
382
+ except Exception as e:
383
+ SDKLogger.error(f"Service call failed: {e}")
384
+ return None
385
+
179
386
  class ControlRobotArm:
180
387
  def __init__(self):
181
388
  self._pub_ctrl_arm_traj = rospy.Publisher('/kuavo_arm_traj', JointState, queue_size=10)
@@ -277,6 +484,26 @@ class ControlRobotHead:
277
484
  SDKLogger.error(f"[Error] publish robot head: {e}")
278
485
  return False
279
486
 
487
+ """ Control Robot Head """
488
+ class ControlRobotHeadWebsocket:
489
+ def __init__(self):
490
+ websocket = WebSocketKuavoSDK()
491
+ self._pub_ctrl_robot_head = roslibpy.Topic(websocket.client, '/robot_head_motion_data', 'kuavo_msgs/robotHeadMotionData')
492
+
493
+ def connect(self, timeout:float=1.0)->bool:
494
+ return True
495
+
496
+ def pub_control_robot_head(self, yaw:float, pitch:float)->bool:
497
+ try:
498
+ msg = {
499
+ "joint_data": [float(yaw), float(pitch)]
500
+ }
501
+ self._pub_ctrl_robot_head.publish(roslibpy.Message(msg))
502
+ return True
503
+ except Exception as e:
504
+ SDKLogger.error(f"[Error] publish robot head: {e}")
505
+ return False
506
+
280
507
  """ Control Robot Motion """
281
508
 
282
509
  # JoyButton constants
@@ -299,6 +526,7 @@ AXIS_RIGHT_RT = 5 # 1 -> (-1)
299
526
  AXIS_LEFT_RIGHT_TRIGGER = 6
300
527
  AXIS_FORWARD_BACK_TRIGGER = 7
301
528
 
529
+
302
530
  class ControlRobotMotion:
303
531
  def __init__(self):
304
532
  self._pub_cmd_vel = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
@@ -339,7 +567,7 @@ class ControlRobotMotion:
339
567
  SDKLogger.error(f"[Error] publish cmd vel: {e}")
340
568
  return False
341
569
 
342
- def pub_cmd_pose(self, twist:Twist)->bool:
570
+ def pub_cmd_pose(self, twist)->bool:
343
571
  try:
344
572
  self._pub_cmd_pose.publish(twist)
345
573
  return True
@@ -347,7 +575,7 @@ class ControlRobotMotion:
347
575
  SDKLogger.error(f"[Error] publish cmd pose: {e}")
348
576
  return False
349
577
 
350
- def _create_joy_msg(self)->Joy:
578
+ def _create_joy_msg(self):
351
579
  joy_msg = Joy()
352
580
  joy_msg.axes = [0.0] * 8 # Initialize 8 axes
353
581
  joy_msg.buttons = [0] * 16 # Initialize 16 buttons
@@ -393,17 +621,114 @@ class ControlRobotMotion:
393
621
  # return self._pub_joy_command(BUTTON_B, "trot")
394
622
  return self._pub_switch_gait_by_name("walk")
395
623
 
396
- def pub_step_ctrl(self, msg:footPoseTargetTrajectories)->bool:
624
+ def pub_step_ctrl(self, msg)->bool:
397
625
  try:
398
626
  self._pub_step_ctrl.publish(msg)
399
627
  return True
400
628
  except Exception as e:
401
629
  SDKLogger.error(f"[Error] publish step ctrl: {e}")
402
630
  return False
403
-
404
- """
405
- Kuavo Robot Arm IK&FK
406
- """
631
+
632
+
633
+ class ControlRobotMotionWebsocket:
634
+ def __init__(self):
635
+ websocket = WebSocketKuavoSDK()
636
+ self._pub_cmd_vel = roslibpy.Topic(websocket.client, '/cmd_vel', 'geometry_msgs/Twist')
637
+ self._pub_cmd_pose = roslibpy.Topic(websocket.client, '/cmd_pose', 'geometry_msgs/Twist')
638
+ self._pub_joy = roslibpy.Topic(websocket.client, '/joy', 'sensor_msgs/Joy')
639
+ self._pub_switch_gait = roslibpy.Topic(websocket.client, '/humanoid_switch_gait_by_name', 'kuavo_msgs/switchGaitByName')
640
+ self._pub_step_ctrl = roslibpy.Topic(websocket.client, '/humanoid_mpc_foot_pose_target_trajectories', 'kuavo_msgs/footPoseTargetTrajectories')
641
+
642
+ def connect(self, timeout:float=2.0)-> bool:
643
+ return True
644
+
645
+ def pub_cmd_vel(self, linear_x: float, linear_y: float, angular_z: float)->bool:
646
+ try:
647
+ msg = {
648
+ "linear": {"x": float(linear_x), "y": float(linear_y), "z": 0.0},
649
+ "angular": {"x": 0.0, "y": 0.0, "z": float(angular_z)}
650
+ }
651
+ self._pub_cmd_vel.publish(roslibpy.Message(msg))
652
+ return True
653
+ except Exception as e:
654
+ SDKLogger.error(f"[Error] publish cmd vel: {e}")
655
+ return False
656
+
657
+ def pub_cmd_pose(self, height:float, pitch:float)->bool:
658
+ # com_msg = Twist()
659
+ # com_msg.linear.z = height
660
+ # com_msg.angular.y = pitch
661
+ try:
662
+ msg = {
663
+ "linear": {"x": 0, "y": 0, "z": float(height)},
664
+ "angular": {"x": 0, "y": float(pitch), "z": 0}
665
+ }
666
+ self._pub_cmd_pose.publish(roslibpy.Message(msg))
667
+ return True
668
+ except Exception as e:
669
+ SDKLogger.error(f"[Error] publish cmd pose: {e}")
670
+ return False
671
+
672
+ def _pub_joy_command(self, button_index: int, command_name: str) -> bool:
673
+ try:
674
+ msg = {
675
+ "axes": [0.0] * 8,
676
+ "buttons": [0] * 16
677
+ }
678
+ msg["buttons"][button_index] = 1
679
+ self._pub_joy.publish(roslibpy.Message(msg))
680
+ SDKLogger.debug(f"Published {command_name} command")
681
+ return True
682
+ except Exception as e:
683
+ SDKLogger.error(f"[Error] publish {command_name}: {e}")
684
+ return False
685
+
686
+ def _pub_switch_gait_by_name(self, gait_name: str) -> bool:
687
+ try:
688
+ msg = {
689
+ "gait_name": gait_name
690
+ }
691
+ self._pub_switch_gait.publish(roslibpy.Message(msg))
692
+ return True
693
+ except Exception as e:
694
+ SDKLogger.error(f"[Error] publish switch gait {gait_name}: {e}")
695
+ return False
696
+
697
+ def pub_walk_command(self) -> bool:
698
+ return self._pub_switch_gait_by_name("walk")
699
+
700
+ def pub_stance_command(self) -> bool:
701
+ try:
702
+ self.pub_cmd_vel(linear_x=0.0, linear_y=0.0, angular_z=0.0)
703
+ return self._pub_switch_gait_by_name("stance")
704
+ except Exception as e:
705
+ SDKLogger.error(f"[Error] publish stance: {e}")
706
+ return False
707
+
708
+ def pub_trot_command(self) -> bool:
709
+ return self._pub_switch_gait_by_name("walk")
710
+
711
+ def pub_step_ctrl(self, msg)->bool:
712
+ try:
713
+ websocket_msg = {
714
+ "timeTrajectory": msg.timeTrajectory,
715
+ "footIndexTrajectory": msg.footIndexTrajectory,
716
+ "footPoseTrajectory": [
717
+ {
718
+ "footPose": list(fp.footPose),
719
+ "torsoPose": list(fp.torsoPose)
720
+ } for fp in msg.footPoseTrajectory
721
+ ]
722
+ }
723
+ SDKLogger.debug(f"websocket_msg {websocket_msg}")
724
+ self._pub_step_ctrl.publish(roslibpy.Message(websocket_msg))
725
+ SDKLogger.debug(f"after publish")
726
+ return True
727
+ except Exception as e:
728
+ SDKLogger.error(f"[Error] publish step ctrl: {e}")
729
+ return False
730
+
731
+
407
732
  class KuavoRobotArmIKFK:
408
733
  def __init__(self):
409
734
  pass
@@ -448,7 +773,7 @@ class KuavoRobotArmIKFK:
448
773
  def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
449
774
  return self._srv_arm_fk(q)
450
775
 
451
- def _srv_arm_ik(self, eef_pose_msg:twoArmHandPoseCmd)->list:
776
+ def _srv_arm_ik(self, eef_pose_msg)->list:
452
777
  try:
453
778
  rospy.wait_for_service('/ik/two_arm_hand_pose_cmd_srv',timeout=1.0)
454
779
  ik_srv = rospy.ServiceProxy('/ik/two_arm_hand_pose_cmd_srv', twoArmHandPoseCmdSrv)
@@ -480,6 +805,88 @@ class KuavoRobotArmIKFK:
480
805
  except Exception as e:
481
806
  print(f"Failed to call ik/fk_srv: {e}")
482
807
  return None
808
+
809
+ class KuavoRobotArmIKFKWebsocket:
810
+ def __init__(self):
811
+ pass
812
+
813
+ def arm_ik(self,
814
+ left_pose: KuavoPose,
815
+ right_pose: KuavoPose,
816
+ left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
817
+ right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
818
+ arm_q0: list = None,
819
+ params: KuavoIKParams=None) -> list:
820
+ try:
821
+ websocket = WebSocketKuavoSDK()
822
+ service = roslibpy.Service(websocket.client, '/ik/two_arm_hand_pose_cmd_srv', 'motion_capture_ik/twoArmHandPoseCmdSrv')
823
+
824
+ request = {
825
+ "twoArmHandPoseCmdRequest": {
826
+ "hand_poses": {
827
+ "header": {
828
+ "seq": 0,
829
+ "stamp": {
830
+ "secs": 0,
831
+ "nsecs": 0
832
+ },
833
+ "frame_id": ""
834
+ },
835
+ "left_pose": {
836
+ "pos_xyz": left_pose.position,
837
+ "quat_xyzw": left_pose.orientation,
838
+ "elbow_pos_xyz": left_elbow_pos_xyz,
839
+ },
840
+ "right_pose": {
841
+ "pos_xyz": right_pose.position,
842
+ "quat_xyzw": right_pose.orientation,
843
+ "elbow_pos_xyz": right_elbow_pos_xyz,
844
+ }
845
+ },
846
+ "use_custom_ik_param": params is not None,
847
+ "joint_angles_as_q0": arm_q0 is not None,
848
+ "ik_param": {
849
+ "major_optimality_tol": params.major_optimality_tol if params else 0.0,
850
+ "major_feasibility_tol": params.major_feasibility_tol if params else 0.0,
851
+ "minor_feasibility_tol": params.minor_feasibility_tol if params else 0.0,
852
+ "major_iterations_limit": params.major_iterations_limit if params else 0,
853
+ "oritation_constraint_tol": params.oritation_constraint_tol if params else 0.0,
854
+ "pos_constraint_tol": params.pos_constraint_tol if params else 0.0,
855
+ "pos_cost_weight": params.pos_cost_weight if params else 0.0
856
+ }
857
+ }
858
+ }
859
+
860
+ response = service.call(request)
861
+ if response.get('success', False):
862
+ return response['hand_poses']['left_pose']['joint_angles'] + response['hand_poses']['right_pose']['joint_angles']
863
+ return None
864
+ except Exception as e:
865
+ SDKLogger.error(f"Service call failed: {e}")
866
+ return None
867
+
868
+ def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
869
+ try:
870
+ websocket = WebSocketKuavoSDK()
871
+ service = roslibpy.Service(websocket.client, '/ik/fk_srv', 'motion_capture_ik/fkSrv')
872
+ request = {"q": q}
873
+ response = service.call(request)
874
+
875
+ if response.get('success', False):
876
+ left_pose = KuavoPose(
877
+ position=response['hand_poses']['left_pose']['pos_xyz'],
878
+ orientation=response['hand_poses']['left_pose']['quat_xyzw']
879
+ )
880
+ right_pose = KuavoPose(
881
+ position=response['hand_poses']['right_pose']['pos_xyz'],
882
+ orientation=response['hand_poses']['right_pose']['quat_xyzw']
883
+ )
884
+ return left_pose, right_pose
885
+ return None
886
+ except Exception as e:
887
+ SDKLogger.error(f"Service call failed: {e}")
888
+ return None
889
+
483
890
  """
484
891
  Kuavo Robot Control
485
892
  """
@@ -698,6 +1105,226 @@ class KuavoRobotControl:
698
1105
  msg = get_multiple_steps_msg(body_poses, dt, is_left_first_default, collision_check)
699
1106
  return self.kuavo_motion_control.pub_step_ctrl(msg)
700
1107
  """ ------------------------------------------------------------------------------"""
1108
+
1109
+
1110
+ class KuavoRobotControlWebsocket:
1111
+ _instance = None
1112
+
1113
+ def __new__(cls, *args, **kwargs):
1114
+ if not cls._instance:
1115
+ cls._instance = super().__new__(cls)
1116
+ return cls._instance
1117
+
1118
+ def __init__(self):
1119
+ if not hasattr(self, '_initialized'):
1120
+ try:
1121
+ self._initialized = True
1122
+ self.kuavo_eef_control = None
1123
+ self.kuavo_head_control = ControlRobotHeadWebsocket()
1124
+ self.kuavo_arm_control = ControlRobotArmWebsocket()
1125
+ self.kuavo_motion_control = ControlRobotMotionWebsocket()
1126
+ self.kuavo_arm_ik_fk = KuavoRobotArmIKFKWebsocket()
1127
+ except Exception as e:
1128
+ SDKLogger.error(f"Failed to initialize KuavoRobotControlWebsocket: {e}")
1129
+ raise
1130
+
1131
+ def initialize(self, eef_type:str=None, debug:bool=False, timeout:float=1.0)-> Tuple[bool, str]:
1132
+ try:
1133
+ # init eef control
1134
+ if eef_type is None:
1135
+ self.kuavo_eef_control = None
1136
+ else:
1137
+ self.kuavo_eef_control = ControlEndEffectorWebsocket(eef_type=eef_type)
1138
+
1139
+ connect_success = True
1140
+ err_msg = ''
1141
+ if not self.kuavo_arm_control.connect(timeout):
1142
+ connect_success = False
1143
+ err_msg = "Failed to connect to arm control topics, \n"
1144
+ if not self.kuavo_head_control.connect(timeout):
1145
+ connect_success = False
1146
+ err_msg += "Failed to connect to head control topics, \n"
1147
+ if not self.kuavo_motion_control.connect(timeout):
1148
+ err_msg += "Failed to connect to motion control topics, \n"
1149
+ connect_success = False
1150
+
1151
+ if self.kuavo_eef_control is not None and not self.kuavo_eef_control.connect(timeout):
1152
+ connect_success = False
1153
+ err_msg += "Failed to connect to end effector control topics."
1154
+
1155
+ if connect_success:
1156
+ err_msg = 'success'
1157
+ return connect_success, err_msg
1158
+ except Exception as e:
1159
+ SDKLogger.error(f"Failed to initialize KuavoRobotControlWebsocket: {e}")
1160
+ return False, str(e)
1161
+
1162
+ """ End Effector Control"""
1163
+ def control_robot_dexhand(self, left_position:list, right_position:list)->bool:
1164
+ """
1165
+ Control robot dexhand
1166
+ Args:
1167
+ left_position: list of 6 floats between 0 and 100
1168
+ right_position: list of 6 floats between 0 and 100
1169
+ """
1170
+ if self.kuavo_eef_control is None:
1171
+ SDKLogger.error("End effector control is not initialized.")
1172
+ return False
1173
+
1174
+ if len(left_position) != 6 or len(right_position) != 6:
1175
+ raise ValueError("Position lists must have a length of 6.")
1176
+
1177
+ for position in left_position + right_position:
1178
+ if position < 0.0 or position > 100.0:
1179
+ raise ValueError("All position values must be in the range [0.0, 100.0].")
1180
+
1181
+ SDKLogger.debug(f"Control robot dexhand: {left_position}, {right_position}")
1182
+ return self.kuavo_eef_control.pub_control_robot_dexhand(left_position, right_position)
1183
+
1184
+ def robot_dexhand_command(self, data, ctrl_mode, hand_side):
1185
+ """
1186
+ Publish dexhand command
1187
+ Args:
1188
+ - data: list of 6 floats between 0 and 100
1189
+ - ctrl_mode: int between 0(position), 1(velocity)
1190
+ - hand_side: int between 0(left), 1(right), 2(dual)
1191
+ """
1192
+ if self.kuavo_eef_control is None:
1193
+ SDKLogger.error("End effector control is not initialized.")
1194
+ return False
1195
+ return self.kuavo_eef_control.pub_dexhand_command(data, ctrl_mode, hand_side)
1196
+
1197
+ def execute_gesture(self, gestures:list)->bool:
1198
+ """
1199
+ Execute gestures
1200
+ Arguments:
1201
+ - gestures: list of dicts with keys 'gesture_name' and 'hand_side'
1202
+ e.g. [{'gesture_name': 'fist', 'hand_side': 0},]
1203
+ """
1204
+ if self.kuavo_eef_control is None:
1205
+ SDKLogger.warn("End effectors control is not initialized.")
1206
+ return False
1207
+ return self.kuavo_eef_control.srv_execute_gesture(gestures)
1208
+
1209
+ def get_gesture_names(self)->list:
1210
+ """
1211
+ Get the names of all gestures.
1212
+ """
1213
+ if self.kuavo_eef_control is None:
1214
+ SDKLogger.warn("End effectors control is not initialized.")
1215
+ return []
1216
+ return self.kuavo_eef_control.srv_get_gesture_names()
1217
+
1218
+ def control_leju_claw(self, postions:list, velocities:list=[90, 90], torques:list=[1.0, 1.0]) ->bool:
1219
+ """
1220
+ Control leju claw
1221
+ Arguments:
1222
+ - postions: list of positions for left and right claw
1223
+ - velocities: list of velocities for left and right claw
1224
+ - torques: list of torques for left and right claw
1225
+ """
1226
+ if self.kuavo_eef_control is None:
1227
+ SDKLogger.warn("End effectors control is not initialized.")
1228
+ return False
1229
+ SDKLogger.debug(f"Control leju claw: {postions}, {velocities}, {torques}")
1230
+ if len(postions) != 2 or len(velocities) != 2 or len(torques) != 2:
1231
+ raise ValueError("Position, velocity, and torque lists must have a length of 2.")
1232
+ return self.kuavo_eef_control.srv_control_leju_claw(postions, velocities, torques)
1233
+
1234
+ def control_robot_head(self, yaw:float, pitch:float)->bool:
1235
+ """
1236
+ Control robot head
1237
+ Arguments:
1238
+ - yaw: yaw angle, radian
1239
+ - pitch: pitch angle, radian
1240
+ """
1241
+ SDKLogger.debug(f"Control robot head: {yaw}, {pitch}")
1242
+ return self.kuavo_head_control.pub_control_robot_head(yaw, pitch)
1243
+
1244
+ def control_robot_arm_traj(self, joint_data:list)->bool:
1245
+ """
1246
+ Control robot arm trajectory
1247
+ Arguments:
1248
+ - joint_data: list of joint data (degrees)
1249
+ """
1250
+ return self.kuavo_arm_control.pub_control_robot_arm_traj(joint_data)
1251
+
1252
+ def control_robot_arm_target_poses(self, times:list, joint_q:list)->bool:
1253
+ """
1254
+ Control robot arm target poses
1255
+ Arguments:
1256
+ - times: list of times (seconds)
1257
+ - joint_q: list of joint data (degrees)
1258
+ """
1259
+ if len(times) != len(joint_q):
1260
+ raise ValueError("Times and joint_q must have the same length.")
1261
+ elif len(times) == 0:
1262
+ raise ValueError("Times and joint_q must not be empty.")
1263
+
1264
+ return self.kuavo_arm_control.pub_arm_target_poses(times=times, joint_q=joint_q)
1265
+
1266
+ def change_robot_arm_ctrl_mode(self, mode:KuavoArmCtrlMode)->bool:
1267
+ """
1268
+ Change robot arm control mode
1269
+ Arguments:
1270
+ - mode: arm control mode
1271
+ """
1272
+ SDKLogger.debug(f"[WebSocket] Change robot arm control mode: {mode}")
1273
+ return self.kuavo_arm_control.srv_change_arm_ctrl_mode(mode)
1274
+
1275
+ def get_robot_arm_ctrl_mode(self)->int:
1276
+ """
1277
+ Get robot arm control mode
1278
+ """
1279
+ return self.kuavo_arm_control.srv_get_arm_ctrl_mode()
1280
+
1281
+ def arm_ik(self, left_pose: KuavoPose, right_pose: KuavoPose,
1282
+ left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
1283
+ right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
1284
+ arm_q0: list = None, params: KuavoIKParams=None) -> list:
1285
+ return self.kuavo_arm_ik_fk.arm_ik(left_pose, right_pose, left_elbow_pos_xyz, right_elbow_pos_xyz, arm_q0, params)
1286
+
1287
+ def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
1288
+ return self.kuavo_arm_ik_fk.arm_fk(q)
1289
+
1290
+ """ Motion """
1291
+ def robot_stance(self)->bool:
1292
+ return self.kuavo_motion_control.pub_stance_command()
1293
+
1294
+ def robot_trot(self)->bool:
1295
+ return self.kuavo_motion_control.pub_trot_command()
1296
+
1297
+ def robot_walk(self, linear_x:float, linear_y:float, angular_z:float)->bool:
1298
+ return self.kuavo_motion_control.pub_cmd_vel(linear_x, linear_y, angular_z)
1299
+
1300
+ def control_torso_height(self, height:float, pitch:float=0.0)->bool:
1301
+ return self.kuavo_motion_control.pub_cmd_pose(height, pitch)
1302
+
1303
+ def step_control(self, body_poses:list, dt:float, is_left_first_default:bool=True, collision_check:bool=True)->bool:
1304
+ """
1305
+ Step control
1306
+ Arguments:
1307
+ - body_poses: list of body poses (x, y, z, yaw), meters and degrees
1308
+ - dt: time step (seconds)
1309
+ - is_left_first_default: whether to start with left foot
1310
+ - collision_check: whether to check for collisions
1311
+ """
1312
+ if len(body_poses) == 0:
1313
+ raise ValueError("Body poses must not be empty.")
1314
+ if dt <= 0.0:
1315
+ raise ValueError("Time step must be greater than 0.0.")
1316
+ for bp in body_poses:
1317
+ if len(bp) != 4:
1318
+ raise ValueError("Body pose must have 4 elements: [x, y, z, yaw]")
1319
+
1320
+ msg = get_multiple_steps_msg(body_poses, dt, is_left_first_default, collision_check)
1321
+ return self.kuavo_motion_control.pub_step_ctrl(msg)
1322
+
1323
+ # if GlobalConfig.use_websocket:
1324
+ # kuavo_robot_control = KuavoRobotControlWebsocket()
1325
+ # else:
1326
+ # kuavo_robot_control = KuavoRobotControl()
1327
+
701
1328
  def euler_to_rotation_matrix(yaw, pitch, roll):
702
1329
  # 计算各轴的旋转矩阵
703
1330
  R_yaw = np.array([[np.cos(yaw), -np.sin(yaw), 0],
@@ -810,5 +1437,4 @@ def get_multiple_steps_msg(body_poses:list, dt:float, is_left_first:bool=True, c
810
1437
  # print("foot_idx_traj:", foot_idx_traj)
811
1438
  # print("foot_traj:", foot_traj)
812
1439
  # print("torso_traj:", torso_traj)
813
- return get_foot_pose_traj_msg(time_traj, foot_idx_traj, foot_traj, torso_traj)
814
- """ ------------------------------------------------------------------------------"""
1440
+ return get_foot_pose_traj_msg(time_traj, foot_idx_traj, foot_traj, torso_traj)