kuavo-humanoid-sdk 1.2.1b1708__20250813145316-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 (158) hide show
  1. kuavo_humanoid_sdk/__init__.py +6 -0
  2. kuavo_humanoid_sdk/common/logger.py +45 -0
  3. kuavo_humanoid_sdk/interfaces/__init__.py +4 -0
  4. kuavo_humanoid_sdk/interfaces/data_types.py +288 -0
  5. kuavo_humanoid_sdk/interfaces/end_effector.py +62 -0
  6. kuavo_humanoid_sdk/interfaces/robot.py +22 -0
  7. kuavo_humanoid_sdk/interfaces/robot_info.py +56 -0
  8. kuavo_humanoid_sdk/kuavo/__init__.py +11 -0
  9. kuavo_humanoid_sdk/kuavo/core/audio.py +32 -0
  10. kuavo_humanoid_sdk/kuavo/core/core.py +634 -0
  11. kuavo_humanoid_sdk/kuavo/core/dex_hand_control.py +114 -0
  12. kuavo_humanoid_sdk/kuavo/core/leju_claw_control.py +67 -0
  13. kuavo_humanoid_sdk/kuavo/core/ros/audio.py +92 -0
  14. kuavo_humanoid_sdk/kuavo/core/ros/control.py +1453 -0
  15. kuavo_humanoid_sdk/kuavo/core/ros/observation.py +94 -0
  16. kuavo_humanoid_sdk/kuavo/core/ros/param.py +183 -0
  17. kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
  18. kuavo_humanoid_sdk/kuavo/core/ros/state.py +634 -0
  19. kuavo_humanoid_sdk/kuavo/core/ros/tools.py +220 -0
  20. kuavo_humanoid_sdk/kuavo/core/ros/vision.py +234 -0
  21. kuavo_humanoid_sdk/kuavo/core/ros_env.py +238 -0
  22. kuavo_humanoid_sdk/kuavo/dexterous_hand.py +201 -0
  23. kuavo_humanoid_sdk/kuavo/leju_claw.py +235 -0
  24. kuavo_humanoid_sdk/kuavo/robot.py +514 -0
  25. kuavo_humanoid_sdk/kuavo/robot_arm.py +248 -0
  26. kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
  27. kuavo_humanoid_sdk/kuavo/robot_head.py +50 -0
  28. kuavo_humanoid_sdk/kuavo/robot_info.py +113 -0
  29. kuavo_humanoid_sdk/kuavo/robot_observation.py +64 -0
  30. kuavo_humanoid_sdk/kuavo/robot_state.py +307 -0
  31. kuavo_humanoid_sdk/kuavo/robot_tool.py +109 -0
  32. kuavo_humanoid_sdk/kuavo/robot_vision.py +81 -0
  33. kuavo_humanoid_sdk/kuavo_strategy/__init__.py +2 -0
  34. kuavo_humanoid_sdk/kuavo_strategy/grasp_box/grasp_box_strategy.py +1325 -0
  35. kuavo_humanoid_sdk/kuavo_strategy/kuavo_strategy.py +106 -0
  36. kuavo_humanoid_sdk/kuavo_strategy_v2/common/data_type.py +340 -0
  37. kuavo_humanoid_sdk/kuavo_strategy_v2/common/events/base_event.py +215 -0
  38. kuavo_humanoid_sdk/kuavo_strategy_v2/common/robot_sdk.py +25 -0
  39. kuavo_humanoid_sdk/kuavo_strategy_v2/pick_place_box/case.py +331 -0
  40. kuavo_humanoid_sdk/kuavo_strategy_v2/pick_place_box/strategy.py +504 -0
  41. kuavo_humanoid_sdk/kuavo_strategy_v2/utils/logger_setup.py +40 -0
  42. kuavo_humanoid_sdk/kuavo_strategy_v2/utils/utils.py +88 -0
  43. kuavo_humanoid_sdk/msg/__init__.py +4 -0
  44. kuavo_humanoid_sdk/msg/kuavo_msgs/__init__.py +7 -0
  45. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetection.py +306 -0
  46. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetectionArray.py +437 -0
  47. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AudioReceiverData.py +122 -0
  48. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_JoySticks.py +191 -0
  49. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_Metadata.py +199 -0
  50. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_MmDetectionMsg.py +264 -0
  51. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_RobotActionState.py +112 -0
  52. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_TFArray.py +323 -0
  53. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/__init__.py +59 -0
  54. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armCollisionCheckInfo.py +160 -0
  55. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPose.py +160 -0
  56. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPoseFree.py +171 -0
  57. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armPoseWithTimeStamp.py +168 -0
  58. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armTargetPoses.py +151 -0
  59. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_bezierCurveCubicPoint.py +178 -0
  60. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_dexhandCommand.py +229 -0
  61. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_dexhandTouchState.py +256 -0
  62. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_endEffectorData.py +227 -0
  63. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose.py +123 -0
  64. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose6D.py +123 -0
  65. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose6DTargetTrajectories.py +301 -0
  66. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseTargetTrajectories.py +301 -0
  67. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseWithVision.py +136 -0
  68. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseWithVisionArray.py +231 -0
  69. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses.py +149 -0
  70. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses6D.py +149 -0
  71. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_fullBodyTargetTrajectories.py +258 -0
  72. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gaitTimeName.py +147 -0
  73. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gestureInfo.py +218 -0
  74. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gestureTask.py +149 -0
  75. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_handPose.py +136 -0
  76. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_headBodyPose.py +145 -0
  77. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_ikSolveError.py +171 -0
  78. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_ikSolveParam.py +140 -0
  79. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_imuData.py +165 -0
  80. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointBezierTrajectory.py +201 -0
  81. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointCmd.py +390 -0
  82. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointData.py +205 -0
  83. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_lejuClawCommand.py +320 -0
  84. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_lejuClawState.py +341 -0
  85. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_motorParam.py +122 -0
  86. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_picoPoseInfo.py +143 -0
  87. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_picoPoseInfoList.py +220 -0
  88. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_planArmState.py +120 -0
  89. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_qv.py +121 -0
  90. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotArmQVVD.py +177 -0
  91. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotBodyMatrices.py +332 -0
  92. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotHandPosition.py +225 -0
  93. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotHeadMotionData.py +128 -0
  94. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotState.py +222 -0
  95. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_sensorsData.py +495 -0
  96. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_switchGaitByName.py +200 -0
  97. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_tagDataArray.py +216 -0
  98. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_touchSensorStatus.py +162 -0
  99. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPose.py +272 -0
  100. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmd.py +315 -0
  101. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmdFree.py +338 -0
  102. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseFree.py +299 -0
  103. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_yoloDetection.py +251 -0
  104. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_yoloOutputData.py +168 -0
  105. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_ExecuteArmAction.py +281 -0
  106. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetTargetPartPoseInCamera.py +298 -0
  107. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_RepublishTFs.py +373 -0
  108. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetJoyTopic.py +282 -0
  109. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetLEDMode.py +468 -0
  110. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SpeechSynthesis.py +270 -0
  111. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/__init__.py +32 -0
  112. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeArmCtrlMode.py +275 -0
  113. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeArmCtrlModeKuavo.py +236 -0
  114. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeMotorParam.py +299 -0
  115. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeTorsoCtrlMode.py +274 -0
  116. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_controlLejuClaw.py +408 -0
  117. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_enableHandTouchSensor.py +304 -0
  118. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_fkSrv.py +394 -0
  119. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_footPose6DTargetTrajectoriesSrv.py +410 -0
  120. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_footPoseTargetTrajectoriesSrv.py +409 -0
  121. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureExecute.py +339 -0
  122. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureExecuteState.py +257 -0
  123. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureList.py +418 -0
  124. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getCurrentGaitName.py +253 -0
  125. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getMotorParam.py +299 -0
  126. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_handForceLevel.py +330 -0
  127. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_jointMoveTo.py +302 -0
  128. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryBezierCurve.py +421 -0
  129. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryCubicSpline.py +490 -0
  130. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_playmusic.py +268 -0
  131. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setHwIntialState.py +304 -0
  132. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setMmCtrlFrame.py +273 -0
  133. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setMotorEncoderRoundService.py +283 -0
  134. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setTagId.py +275 -0
  135. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_singleStepControl.py +444 -0
  136. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_twoArmHandPoseCmdFreeSrv.py +716 -0
  137. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_twoArmHandPoseCmdSrv.py +662 -0
  138. kuavo_humanoid_sdk/msg/motion_capture_ik/__init__.py +7 -0
  139. kuavo_humanoid_sdk/msg/ocs2_msgs/__init__.py +7 -0
  140. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/__init__.py +12 -0
  141. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_constraint.py +142 -0
  142. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_controller_data.py +121 -0
  143. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_lagrangian_metrics.py +148 -0
  144. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mode_schedule.py +150 -0
  145. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_flattened_controller.py +666 -0
  146. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_input.py +122 -0
  147. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_observation.py +209 -0
  148. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_performance_indices.py +140 -0
  149. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_solver_data.py +886 -0
  150. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_state.py +122 -0
  151. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_target_trajectories.py +239 -0
  152. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_multiplier.py +148 -0
  153. kuavo_humanoid_sdk/msg/ocs2_msgs/srv/__init__.py +1 -0
  154. kuavo_humanoid_sdk/msg/ocs2_msgs/srv/_reset.py +376 -0
  155. kuavo_humanoid_sdk-1.2.1b1708.dist-info/METADATA +291 -0
  156. kuavo_humanoid_sdk-1.2.1b1708.dist-info/RECORD +158 -0
  157. kuavo_humanoid_sdk-1.2.1b1708.dist-info/WHEEL +6 -0
  158. kuavo_humanoid_sdk-1.2.1b1708.dist-info/top_level.txt +1 -0
@@ -0,0 +1,1453 @@
1
+ import os
2
+ import numpy as np
3
+ from typing import Tuple
4
+ from kuavo_humanoid_sdk.common.logger import SDKLogger
5
+ from kuavo_humanoid_sdk.interfaces.data_types import (KuavoArmCtrlMode, KuavoIKParams, KuavoPose,
6
+ KuavoManipulationMpcControlFlow, KuavoManipulationMpcCtrlMode
7
+ ,KuavoManipulationMpcFrame, KuavoMotorParam)
8
+ from kuavo_humanoid_sdk.kuavo.core.ros.sat_utils import RotatingRectangle
9
+ from kuavo_humanoid_sdk.kuavo.core.ros.param import EndEffectorType
10
+
11
+ import rospy
12
+ from geometry_msgs.msg import Twist
13
+ from sensor_msgs.msg import JointState, Joy
14
+ from kuavo_humanoid_sdk.msg.kuavo_msgs.msg import (gestureTask,robotHandPosition, robotHeadMotionData, armTargetPoses, switchGaitByName,
15
+ footPose, footPoseTargetTrajectories, dexhandCommand, motorParam)
16
+ from kuavo_humanoid_sdk.msg.kuavo_msgs.srv import (gestureExecute, gestureExecuteRequest,gestureList, gestureListRequest,
17
+ controlLejuClaw, controlLejuClawRequest, changeArmCtrlMode, changeArmCtrlModeRequest,
18
+ changeTorsoCtrlMode, changeTorsoCtrlModeRequest, setMmCtrlFrame, setMmCtrlFrameRequest,
19
+ setTagId, setTagIdRequest, getMotorParam, getMotorParamRequest,
20
+ changeMotorParam, changeMotorParamRequest)
21
+ from kuavo_humanoid_sdk.msg.kuavo_msgs.msg import twoArmHandPoseCmd, ikSolveParam, armHandPose, armCollisionCheckInfo
22
+ from kuavo_humanoid_sdk.msg.kuavo_msgs.srv import twoArmHandPoseCmdSrv, fkSrv
23
+ from std_srvs.srv import SetBool, SetBoolRequest
24
+ from std_msgs.msg import Float64MultiArray
25
+
26
+
27
+
28
+
29
+ class ControlEndEffector:
30
+ def __init__(self, eef_type: str = EndEffectorType.QIANGNAO):
31
+ self._eef_type = eef_type
32
+ self._pubs = []
33
+ if self._eef_type == EndEffectorType.QIANGNAO:
34
+ self._pub_ctrl_robot_hand = rospy.Publisher('/control_robot_hand_position', robotHandPosition, queue_size=10)
35
+ # publisher, name, require
36
+ self._pubs.append((self._pub_ctrl_robot_hand, False))
37
+ elif self._eef_type == EndEffectorType.QIANGNAO_TOUCH:
38
+ self._pub_ctrl_robot_hand = rospy.Publisher('/control_robot_hand_position', robotHandPosition, queue_size=10)
39
+ self._pub_dexhand_command = rospy.Publisher('/dexhand/command', dexhandCommand, queue_size=10)
40
+ self._pub_dexhand_right_command = rospy.Publisher('/dexhand/right/command', dexhandCommand, queue_size=10)
41
+ self._pub_dexhand_left_command = rospy.Publisher('/dexhand/left/command', dexhandCommand, queue_size=10)
42
+ # publisher, name, require
43
+ self._pubs.append((self._pub_dexhand_command, False))
44
+ self._pubs.append((self._pub_dexhand_right_command, False))
45
+ self._pubs.append((self._pub_dexhand_left_command, False))
46
+
47
+ def connect(self, timeout:float=1.0)-> bool:
48
+ start_time = rospy.Time.now()
49
+
50
+ success = True
51
+ for pub, require in self._pubs:
52
+ while pub.get_num_connections() == 0:
53
+ if (rospy.Time.now() - start_time).to_sec() > timeout:
54
+ if require:
55
+ SDKLogger.error(f"Timeout waiting for {pub.name} connection")
56
+ success = False
57
+ break
58
+ rospy.sleep(0.1)
59
+
60
+ return success
61
+
62
+ """ Control Kuavo Robot Dexhand """
63
+ def pub_control_robot_dexhand(self, left_position:list, right_position:list)->bool:
64
+ if not self._eef_type.startswith(EndEffectorType.QIANGNAO): # qiangnao, qiangnao_touch
65
+ SDKLogger.warning(f"{self._eef_type} not support control dexhand")
66
+ return False
67
+ try :
68
+ hand_pose_msg = robotHandPosition()
69
+ hand_pose_msg.left_hand_position = bytes(left_position)
70
+ hand_pose_msg.right_hand_position = bytes(right_position)
71
+ self._pub_ctrl_robot_hand.publish(hand_pose_msg)
72
+ SDKLogger.debug(f"publish robot dexhand: {left_position}, {right_position}")
73
+ return True
74
+ except Exception as e:
75
+ SDKLogger.error(f"publish robot dexhand: {e}")
76
+ return False
77
+
78
+ def pub_dexhand_command(self, data:list, ctrl_mode, hand_side)->bool:
79
+ """
80
+ ctrl_mode: 0 --> POSITION, 1 --> VELOCITY
81
+ hand_side: 0 --> left, 1 --> right, 2-->dual
82
+ """
83
+ if not self._eef_type == EndEffectorType.QIANGNAO_TOUCH:
84
+ SDKLogger.warning(f"{self._eef_type} not support pub_left_dexhand_command")
85
+ return False
86
+ try:
87
+ if hand_side != 2 and len(data) != 6:
88
+ SDKLogger.warning("Data length should be 6")
89
+ return False
90
+ if hand_side == 2 and len(data) != 12:
91
+ SDKLogger.warning("Data length should be 12")
92
+ return False
93
+ if ctrl_mode not in [dexhandCommand.POSITION_CONTROL, dexhandCommand.VELOCITY_CONTROL]:
94
+ SDKLogger.error(f"Invalid mode for pub_left_dexhand_command: {ctrl_mode}")
95
+ return False
96
+ msg = dexhandCommand()
97
+ msg.data = [int(d) for d in data] # Convert data to integers
98
+ msg.control_mode = ctrl_mode
99
+ if hand_side == 0:
100
+ self._pub_dexhand_left_command.publish(msg)
101
+ elif hand_side == 1:
102
+ self._pub_dexhand_right_command.publish(msg)
103
+ else:
104
+ self._pub_dexhand_command.publish(msg)
105
+ return True
106
+ except Exception as e:
107
+ SDKLogger.error(f"Failed to publish left dexhand command: {e}")
108
+ return False
109
+
110
+ def srv_execute_gesture(self, gestures:list)->bool:
111
+ if not self._eef_type.startswith(EndEffectorType.QIANGNAO): # qiangnao, qiangnao_touch
112
+ SDKLogger.warning(f"{self._eef_type} not support control dexhand")
113
+ return False
114
+ try:
115
+ service_name = 'gesture/execute'
116
+ rospy.wait_for_service(service=service_name, timeout=2.0)
117
+ # create service proxy
118
+ gesture_service = rospy.ServiceProxy(service_name, gestureExecute)
119
+
120
+ # request
121
+ request = gestureExecuteRequest()
122
+ for gs in gestures:
123
+ gesture = gestureTask(gesture_name=gs["gesture_name"], hand_side=gs["hand_side"])
124
+ request.gestures.append(gesture)
125
+
126
+ # call service
127
+ response = gesture_service(request)
128
+ if not response.success:
129
+ SDKLogger.error(f"Failed to execute gesture '{gestures}': {response.message}")
130
+ return response.success
131
+ except rospy.ServiceException as e:
132
+ SDKLogger.error(f"Service call failed: {e}")
133
+ except rospy.ROSException as e:
134
+ SDKLogger.error(f"Service call failed: {e}")
135
+ except Exception as e:
136
+ SDKLogger.error(f"Service call failed: {e}")
137
+ return False
138
+
139
+ def srv_get_gesture_names(self)->list:
140
+ if not self._eef_type.startswith(EndEffectorType.QIANGNAO): # qiangnao, qiangnao_touch
141
+ SDKLogger.warning(f"{self._eef_type} not support control dexhand")
142
+ return []
143
+ try:
144
+ service_name = 'gesture/list'
145
+ rospy.wait_for_service(service=service_name, timeout=2.0)
146
+ gesture_service = rospy.ServiceProxy(service_name, gestureList)
147
+ request = gestureListRequest()
148
+ response = gesture_service(request)
149
+ gestures = []
150
+ for gesture_info in response.gesture_infos:
151
+ gestures.append(gesture_info.gesture_name)
152
+ for alias in gesture_info.alias:
153
+ gestures.append(alias)
154
+ return list(set(gestures))
155
+ except rospy.ServiceException as e:
156
+ SDKLogger.error(f"Service call failed: {e}")
157
+ except Exception as e:
158
+ SDKLogger.error(f"Service call failed: {e}")
159
+ return []
160
+
161
+ def srv_control_leju_claw(self, postions:list, velocities:list, torques:list) ->bool:
162
+ if self._eef_type != 'lejuclaw':
163
+ SDKLogger.warning(f"{self._eef_type} not support control lejuclaw.")
164
+ return False
165
+ try:
166
+ # ros service
167
+ service_name = 'control_robot_leju_claw'
168
+ rospy.wait_for_service(service_name, timeout=2.0)
169
+ control_lejucalw_srv = rospy.ServiceProxy(service_name, controlLejuClaw)
170
+
171
+ # request
172
+ request = controlLejuClawRequest()
173
+ request.data.position = postions
174
+ request.data.velocity = velocities
175
+ request.data.effort = torques
176
+
177
+ response = control_lejucalw_srv(request)
178
+ if not response.success:
179
+ SDKLogger.error(f"Failed to control leju claw: {response.message}")
180
+ return response.success
181
+ except rospy.ServiceException as e:
182
+ SDKLogger.error(f"Service `control_robot_leju_claw` call failed: {e}")
183
+ except rospy.ROSException as e:
184
+ SDKLogger.error(f"Service `control_robot_leju_claw` call failed: {e}")
185
+ except Exception as e:
186
+ SDKLogger.error(f"Service `control_robot_leju_claw` call failed: {e}")
187
+ return False
188
+
189
+ class ControlRobotArm:
190
+ def __init__(self):
191
+
192
+ # 带有碰撞检查的轨迹发布
193
+ self._pub_ctrl_arm_traj_arm_collision = rospy.Publisher('/arm_collision/kuavo_arm_traj', JointState, queue_size=10)
194
+ self._pub_ctrl_arm_target_poses_arm_collision = rospy.Publisher('/arm_collision/kuavo_arm_target_poses', armTargetPoses, queue_size=10)
195
+
196
+ # 判断当前是否发生碰撞
197
+ self._sub_arm_collision_info = rospy.Subscriber('/arm_collision/info', armCollisionCheckInfo, self.callback_arm_collision_info, queue_size=10)
198
+ self._is_collision = False
199
+ self.arm_collision_enable = False
200
+
201
+ # 正常轨迹发布
202
+ self._pub_ctrl_arm_traj = rospy.Publisher('/kuavo_arm_traj', JointState, queue_size=10)
203
+ self._pub_ctrl_arm_target_poses = rospy.Publisher('/kuavo_arm_target_poses', armTargetPoses, queue_size=10)
204
+ self._pub_ctrl_hand_pose_cmd = rospy.Publisher('/mm/two_arm_hand_pose_cmd', twoArmHandPoseCmd, queue_size=10)
205
+ self._pub_hand_wrench = rospy.Publisher('/hand_wrench_cmd', Float64MultiArray, queue_size=10)
206
+
207
+ def is_arm_collision(self)->bool:
208
+ return self._is_collision
209
+
210
+ def is_arm_collision_mode(self)->bool:
211
+ return self.arm_collision_enable
212
+
213
+ def callback_arm_collision_info(self, msg: armCollisionCheckInfo):
214
+ self._is_collision = True
215
+ SDKLogger.info(f"Arm collision detected")
216
+
217
+ def set_arm_collision_mode(self, enable: bool):
218
+ """
219
+ Set arm collision mode
220
+ """
221
+ self.arm_collision_enable = enable
222
+ srv_set_arm_collision_mode_srv = rospy.ServiceProxy('/arm_collision/set_arm_moving_enable', SetBool)
223
+ req = SetBoolRequest()
224
+ req.data = enable
225
+ resp = srv_set_arm_collision_mode_srv(req)
226
+ if not resp.success:
227
+ SDKLogger.error(f"Failed to wait arm collision complete: {resp.message}")
228
+
229
+
230
+
231
+ def release_arm_collision_mode(self):
232
+ self._is_collision = False
233
+
234
+ def wait_arm_collision_complete(self):
235
+ if self._is_collision:
236
+ srv_wait_arm_collision_complete_srv = rospy.ServiceProxy('/arm_collision/wait_complete', SetBool)
237
+ req = SetBoolRequest()
238
+ req.data = True
239
+ resp = srv_wait_arm_collision_complete_srv(req)
240
+ if not resp.success:
241
+ SDKLogger.error(f"Failed to wait arm collision complete: {resp.message}")
242
+
243
+ def connect(self, timeout:float=1.0)-> bool:
244
+ start_time = rospy.Time.now()
245
+ publishers = [
246
+ (self._pub_ctrl_arm_traj, "arm trajectory publisher", False),
247
+ (self._pub_ctrl_arm_target_poses, "arm target poses publisher", False)
248
+ ]
249
+
250
+ success = True
251
+ for pub, name, required in publishers:
252
+ while pub.get_num_connections() == 0:
253
+ if (rospy.Time.now() - start_time).to_sec() > timeout:
254
+ SDKLogger.error(f"Timeout waiting for {name} connection, '{pub.name}'")
255
+ if required:
256
+ success = False
257
+ break
258
+ rospy.sleep(0.1)
259
+ return success
260
+
261
+ def pub_control_robot_arm_traj(self, joint_q: list)->bool:
262
+
263
+ try:
264
+ msg = JointState()
265
+ msg.name = ["arm_joint_" + str(i) for i in range(0, 14)]
266
+ msg.header.stamp = rospy.Time.now()
267
+ msg.position = 180.0 / np.pi * np.array(joint_q) # convert to degree
268
+ if self.arm_collision_enable:
269
+ self._pub_ctrl_arm_traj_arm_collision.publish(msg)
270
+ else:
271
+ self._pub_ctrl_arm_traj.publish(msg)
272
+ return True
273
+ except Exception as e:
274
+ SDKLogger.error(f"publish robot arm traj: {e}")
275
+ return False
276
+
277
+ def pub_arm_target_poses(self, times:list, joint_q:list):
278
+ try:
279
+ msg = armTargetPoses()
280
+ msg.times = times
281
+ for i in range(len(joint_q)):
282
+ degs = [q for q in joint_q[i]]
283
+ msg.values.extend(degs)
284
+ if self.arm_collision_enable:
285
+ self._pub_ctrl_arm_target_poses_arm_collision.publish(msg)
286
+ else:
287
+ self._pub_ctrl_arm_target_poses.publish(msg)
288
+ return True
289
+ except Exception as e:
290
+ SDKLogger.error(f"publish arm target poses: {e}")
291
+ return False
292
+ def pub_end_effector_pose_cmd(self, left_pose: KuavoPose, right_pose: KuavoPose, frame: KuavoManipulationMpcFrame)->bool:
293
+ try:
294
+ msg = twoArmHandPoseCmd()
295
+ left_pose_msg = armHandPose()
296
+ left_pose_msg.pos_xyz = left_pose.position
297
+ left_pose_msg.quat_xyzw = left_pose.orientation
298
+ right_pose_msg = armHandPose()
299
+ right_pose_msg.pos_xyz = right_pose.position
300
+ right_pose_msg.quat_xyzw = right_pose.orientation
301
+ msg.hand_poses.left_pose = left_pose_msg
302
+ msg.hand_poses.right_pose = right_pose_msg
303
+ if frame.value not in [0, 1, 2, 3, 4]:
304
+ SDKLogger.error(f"Invalid frame: {frame}")
305
+ return False
306
+ msg.frame = frame.value
307
+ self._pub_ctrl_hand_pose_cmd.publish(msg)
308
+ return True
309
+ except Exception as e:
310
+ SDKLogger.error(f"publish arm target poses: {e}")
311
+ return False
312
+
313
+ def srv_change_manipulation_mpc_frame(self, frame: KuavoManipulationMpcFrame)->bool:
314
+ try:
315
+ service_name = '/set_mm_ctrl_frame'
316
+ rospy.wait_for_service(service_name, timeout=2.0)
317
+ set_frame_srv = rospy.ServiceProxy(service_name, setMmCtrlFrame)
318
+
319
+ req = setMmCtrlFrameRequest()
320
+ req.frame = frame.value
321
+
322
+ resp = set_frame_srv(req)
323
+ if not resp.result:
324
+ SDKLogger.error(f"Failed to change manipulation mpc frame to {frame}: {resp.message}")
325
+ return resp.result
326
+ except rospy.ServiceException as e:
327
+ SDKLogger.error(f"Service call to {service_name} failed: {e}")
328
+ except rospy.ROSException as e: # For timeout from wait_for_service
329
+ SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
330
+ except Exception as e:
331
+ SDKLogger.error(f"Failed to change manipulation mpc frame: {e}")
332
+ return False
333
+
334
+ def srv_change_manipulation_mpc_ctrl_mode(self, ctrl_mode: KuavoManipulationMpcCtrlMode)->bool:
335
+ try:
336
+ service_name = '/mobile_manipulator_mpc_control'
337
+ rospy.wait_for_service(service_name, timeout=2.0)
338
+ set_mode_srv = rospy.ServiceProxy(service_name, changeTorsoCtrlMode)
339
+
340
+ req = changeTorsoCtrlModeRequest()
341
+ req.control_mode = ctrl_mode.value
342
+
343
+ resp = set_mode_srv(req)
344
+ if not resp.result:
345
+ SDKLogger.error(f"Failed to change manipulation mpc control mode to {ctrl_mode}: {resp.message}")
346
+ return resp.result
347
+ except rospy.ServiceException as e:
348
+ SDKLogger.error(f"Service call to {service_name} failed: {e}")
349
+ except rospy.ROSException as e: # For timeout from wait_for_service
350
+ SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
351
+ except Exception as e:
352
+ SDKLogger.error(f"Failed to change manipulation mpc control mode: {e}")
353
+ return False
354
+
355
+ def srv_change_manipulation_mpc_control_flow(self, ctrl_flow: KuavoManipulationMpcControlFlow)-> bool:
356
+ try:
357
+ service_name = '/enable_mm_wbc_arm_trajectory_control'
358
+ rospy.wait_for_service(service_name, timeout=2.0)
359
+ set_mode_srv = rospy.ServiceProxy(service_name, changeArmCtrlMode)
360
+
361
+ req = changeArmCtrlModeRequest()
362
+ req.control_mode = ctrl_flow.value
363
+
364
+ resp = set_mode_srv(req)
365
+ if not resp.result:
366
+ SDKLogger.error(f"Failed to change manipulation mpc wbc arm trajectory control to {ctrl_flow}: {resp.message}")
367
+ return resp.result
368
+ except rospy.ServiceException as e:
369
+ SDKLogger.error(f"Service call to {service_name} failed: {e}")
370
+ except rospy.ROSException as e: # For timeout from wait_for_service
371
+ SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
372
+ except Exception as e:
373
+ SDKLogger.error(f"Failed to change manipulation mpc control flow: {e}")
374
+ return False
375
+
376
+ def srv_get_manipulation_mpc_ctrl_mode(self, )->KuavoManipulationMpcCtrlMode:
377
+ try:
378
+ service_name = '/mobile_manipulator_get_mpc_control_mode'
379
+ rospy.wait_for_service(service_name, timeout=2.0)
380
+ get_mode_srv = rospy.ServiceProxy(service_name, changeTorsoCtrlMode)
381
+
382
+ req = changeTorsoCtrlModeRequest()
383
+
384
+ resp = get_mode_srv(req)
385
+ if not resp.result:
386
+ SDKLogger.error(f"Failed to get manipulation mpc control mode: {resp.message}")
387
+ return KuavoManipulationMpcCtrlMode.ERROR
388
+ return KuavoManipulationMpcCtrlMode(resp.mode)
389
+ except rospy.ServiceException as e:
390
+ SDKLogger.error(f"Service call to {service_name} failed: {e}")
391
+ except rospy.ROSException as e: # For timeout from wait_for_service
392
+ SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
393
+ except Exception as e:
394
+ SDKLogger.error(f"Failed to get manipulation mpc control mode: {e}")
395
+ return KuavoManipulationMpcCtrlMode.ERROR
396
+
397
+ def srv_get_manipulation_mpc_frame(self, )->KuavoManipulationMpcFrame:
398
+ try:
399
+ service_name = '/get_mm_ctrl_frame'
400
+ rospy.wait_for_service(service_name, timeout=2.0)
401
+ get_frame_srv = rospy.ServiceProxy(service_name, setMmCtrlFrame)
402
+
403
+ req = setMmCtrlFrameRequest()
404
+
405
+ resp = get_frame_srv(req)
406
+ if not resp.result:
407
+ SDKLogger.error(f"Failed to get manipulation mpc frame: {resp.message}")
408
+ return KuavoManipulationMpcFrame.ERROR
409
+ return KuavoManipulationMpcFrame(resp.currentFrame)
410
+ except rospy.ServiceException as e:
411
+ SDKLogger.error(f"Service call to {service_name} failed: {e}")
412
+ except rospy.ROSException as e: # For timeout from wait_for_service
413
+ SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
414
+ except Exception as e:
415
+ SDKLogger.error(f"Failed to get manipulation mpc frame: {e}")
416
+ return KuavoManipulationMpcFrame.ERROR
417
+
418
+ def srv_get_manipulation_mpc_control_flow(self, )->KuavoManipulationMpcControlFlow:
419
+ try:
420
+ service_name = '/get_mm_wbc_arm_trajectory_control'
421
+ rospy.wait_for_service(service_name, timeout=2.0)
422
+ get_mode_srv = rospy.ServiceProxy(service_name, changeArmCtrlMode)
423
+
424
+ req = changeArmCtrlModeRequest()
425
+
426
+ resp = get_mode_srv(req)
427
+ if not resp.result:
428
+ SDKLogger.error(f"Failed to get manipulation mpc wbc arm trajectory control mode: {resp.message}")
429
+ return KuavoManipulationMpcControlFlow.ERROR
430
+ return KuavoManipulationMpcControlFlow(resp.mode)
431
+ except rospy.ServiceException as e:
432
+ SDKLogger.error(f"Service call to {service_name} failed: {e}")
433
+ except rospy.ROSException as e: # For timeout from wait_for_service
434
+ SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
435
+ except Exception as e:
436
+ SDKLogger.error(f"Failed to get manipulation mpc wbc arm trajectory control mode: {e}")
437
+ return KuavoManipulationMpcControlFlow.ERROR
438
+
439
+
440
+ def srv_change_arm_ctrl_mode(self, mode: KuavoArmCtrlMode)->bool:
441
+ try:
442
+ rospy.wait_for_service('/change_arm_ctrl_mode', timeout=2.0)
443
+ change_arm_ctrl_mode_srv = rospy.ServiceProxy('/change_arm_ctrl_mode', changeArmCtrlMode)
444
+ req = changeArmCtrlModeRequest()
445
+ req.control_mode = mode.value
446
+ resp = change_arm_ctrl_mode_srv(req)
447
+ return resp.result
448
+ except rospy.ServiceException as e:
449
+ SDKLogger.error(f"Service call failed: {e}")
450
+ except Exception as e:
451
+ SDKLogger.error(f"[Error] change arm ctrl mode: {e}")
452
+ return False
453
+
454
+ def srv_get_arm_ctrl_mode(self)-> KuavoArmCtrlMode:
455
+ try:
456
+ rospy.wait_for_service('/humanoid_get_arm_ctrl_mode')
457
+ get_arm_ctrl_mode_srv = rospy.ServiceProxy('/humanoid_get_arm_ctrl_mode', changeArmCtrlMode)
458
+ req = changeArmCtrlModeRequest()
459
+ resp = get_arm_ctrl_mode_srv(req)
460
+ return KuavoArmCtrlMode(resp.control_mode)
461
+ except rospy.ServiceException as e:
462
+ SDKLogger.error(f"Service call failed: {e}")
463
+ except Exception as e:
464
+ SDKLogger.error(f"[Error] get arm ctrl mode: {e}")
465
+ return None
466
+
467
+ def pub_hand_wrench_cmd(self, left_wrench, right_wrench):
468
+ """
469
+ 发布末端力控制命令
470
+ 参数:
471
+ left_wrench: 左手6维力控指令 [Fx, Fy, Fz, Tx, Ty, Tz]
472
+ right_wrench: 右手6维力控指令 [Fx, Fy, Fz, Tx, Ty, Tz]
473
+ Fx: 沿X轴的线性力
474
+ Fy: 沿Y轴的线性力
475
+ Fz: 沿Z轴的线性力
476
+ Tx: 绕X轴的力矩
477
+ Ty: 绕Y轴的力矩
478
+ Tz: 绕Z轴的力矩
479
+ """
480
+ if len(left_wrench) != 6 or len(right_wrench) != 6:
481
+ SDKLogger.error("Wrench data must be 6-dimensional")
482
+ return False
483
+
484
+ try:
485
+ msg = Float64MultiArray()
486
+ msg.data = list(left_wrench) + list(right_wrench)
487
+ self._pub_hand_wrench.publish(msg)
488
+ return True
489
+ except Exception as e:
490
+ SDKLogger.error(f"Publish hand wrench failed: {e}")
491
+ return False
492
+
493
+ """ Control Robot Head """
494
+ class ControlRobotHead:
495
+ def __init__(self):
496
+ self._pub_ctrl_robot_head = rospy.Publisher('/robot_head_motion_data', robotHeadMotionData, queue_size=10)
497
+
498
+ def connect(self, timeout:float=1.0)->bool:
499
+ start_time = rospy.Time.now()
500
+ publishers = [
501
+ (self._pub_ctrl_robot_head, "robot head publisher", False) # not need check!
502
+ ]
503
+ for pub, name, required in publishers:
504
+ while pub.get_num_connections() == 0:
505
+ if (rospy.Time.now() - start_time).to_sec() > timeout:
506
+ SDKLogger.error(f"Timeout waiting for {name} connection, '{pub.name}'")
507
+ if required:
508
+ return False
509
+ break
510
+ rospy.sleep(0.1)
511
+ return True
512
+ def pub_control_robot_head(self, yaw:float, pitch:float)->bool:
513
+ try :
514
+ msg = robotHeadMotionData()
515
+ msg.joint_data = [yaw, pitch]
516
+ self._pub_ctrl_robot_head.publish(msg)
517
+ return True
518
+ except Exception as e:
519
+ SDKLogger.error(f"[Error] publish robot head: {e}")
520
+ return False
521
+
522
+ def srv_enable_head_tracking(self, target_id: int)->bool:
523
+ """Enable the head tracking for a specific tag ID.
524
+
525
+ Args:
526
+ target_id: The ID of the tag to track
527
+
528
+ Returns:
529
+ bool: True if successful, False otherwise
530
+ """
531
+ try:
532
+ # 首先设置追踪目标ID
533
+ service_name = '/set_target_tag_id'
534
+ rospy.wait_for_service(service_name, timeout=2.0)
535
+ set_tag_id_srv = rospy.ServiceProxy(service_name, setTagId)
536
+
537
+ req = setTagIdRequest()
538
+ req.tag_id = target_id
539
+
540
+ resp = set_tag_id_srv(req)
541
+ if not resp.success:
542
+ SDKLogger.error(f"Failed to set target tag ID: {resp.message}")
543
+ return False
544
+
545
+ SDKLogger.info(f"Successfully set target tag ID to {target_id}: {resp.message}")
546
+
547
+ # 然后启动连续追踪
548
+ service_name = '/continuous_track'
549
+ rospy.wait_for_service(service_name, timeout=2.0)
550
+ continuous_track_srv = rospy.ServiceProxy(service_name, SetBool)
551
+
552
+ req = SetBoolRequest()
553
+ req.data = True
554
+
555
+ resp = continuous_track_srv(req)
556
+ if not resp.success:
557
+ SDKLogger.error(f"Failed to start continuous tracking: {resp.message}")
558
+ return False
559
+
560
+ SDKLogger.info(f"Successfully started continuous tracking: {resp.message}")
561
+ return True
562
+
563
+ except rospy.ServiceException as e:
564
+ SDKLogger.error(f"Service call failed: {e}")
565
+ except rospy.ROSException as e:
566
+ SDKLogger.error(f"Failed to connect to service: {e}")
567
+ except Exception as e:
568
+ SDKLogger.error(f"Failed to enable head tracking: {e}")
569
+
570
+ return False
571
+
572
+ def srv_disable_head_tracking(self)->bool:
573
+ """Disable the head tracking.
574
+
575
+ Returns:
576
+ bool: True if successful, False otherwise
577
+ """
578
+ try:
579
+ service_name = '/continuous_track'
580
+ rospy.wait_for_service(service_name, timeout=2.0)
581
+ continuous_track_srv = rospy.ServiceProxy(service_name, SetBool)
582
+
583
+ req = SetBoolRequest()
584
+ req.data = False
585
+
586
+ resp = continuous_track_srv(req)
587
+ if not resp.success:
588
+ SDKLogger.error(f"Failed to stop continuous tracking: {resp.message}")
589
+ return False
590
+
591
+ SDKLogger.info(f"Successfully stopped continuous tracking: {resp.message}")
592
+ return True
593
+
594
+ except rospy.ServiceException as e:
595
+ SDKLogger.error(f"Service call failed: {e}")
596
+ except rospy.ROSException as e:
597
+ SDKLogger.error(f"Failed to connect to service: {e}")
598
+ except Exception as e:
599
+ SDKLogger.error(f"Failed to disable head tracking: {e}")
600
+
601
+ return False
602
+
603
+ def srv_enable_head_tracking(self, target_id: int)->bool:
604
+ """Enable the head tracking for a specific tag ID.
605
+
606
+ Args:
607
+ target_id: The ID of the tag to track
608
+
609
+ Returns:
610
+ bool: True if successful, False otherwise
611
+ """
612
+ try:
613
+ # 首先设置追踪目标ID
614
+ service_name = '/set_target_tag_id'
615
+ rospy.wait_for_service(service_name, timeout=2.0)
616
+ set_tag_id_srv = rospy.ServiceProxy(service_name, setTagId)
617
+
618
+ req = setTagIdRequest()
619
+ req.tag_id = target_id
620
+
621
+ resp = set_tag_id_srv(req)
622
+ if not resp.success:
623
+ SDKLogger.error(f"Failed to set target tag ID: {resp.message}")
624
+ return False
625
+
626
+ SDKLogger.info(f"Successfully set target tag ID to {target_id}: {resp.message}")
627
+
628
+ # 然后启动连续追踪
629
+ service_name = '/continuous_track'
630
+ rospy.wait_for_service(service_name, timeout=2.0)
631
+ continuous_track_srv = rospy.ServiceProxy(service_name, SetBool)
632
+
633
+ req = SetBoolRequest()
634
+ req.data = True
635
+
636
+ resp = continuous_track_srv(req)
637
+ if not resp.success:
638
+ SDKLogger.error(f"Failed to start continuous tracking: {resp.message}")
639
+ return False
640
+
641
+ SDKLogger.info(f"Successfully started continuous tracking: {resp.message}")
642
+ return True
643
+
644
+ except rospy.ServiceException as e:
645
+ SDKLogger.error(f"Service call failed: {e}")
646
+ except rospy.ROSException as e:
647
+ SDKLogger.error(f"Failed to connect to service: {e}")
648
+ except Exception as e:
649
+ SDKLogger.error(f"Failed to enable head tracking: {e}")
650
+
651
+ return False
652
+
653
+ def srv_disable_head_tracking(self)->bool:
654
+ """Disable the head tracking.
655
+
656
+ Returns:
657
+ bool: True if successful, False otherwise
658
+ """
659
+ try:
660
+ service_name = '/continuous_track'
661
+ rospy.wait_for_service(service_name, timeout=2.0)
662
+ continuous_track_srv = rospy.ServiceProxy(service_name, SetBool)
663
+
664
+ req = SetBoolRequest()
665
+ req.data = False
666
+
667
+ resp = continuous_track_srv(req)
668
+ if not resp.success:
669
+ SDKLogger.error(f"Failed to stop continuous tracking: {resp.message}")
670
+ return False
671
+
672
+ SDKLogger.info(f"Successfully stopped continuous tracking: {resp.message}")
673
+ return True
674
+
675
+ except rospy.ServiceException as e:
676
+ SDKLogger.error(f"Service call failed: {e}")
677
+ except rospy.ROSException as e:
678
+ SDKLogger.error(f"Failed to connect to service: {e}")
679
+ except Exception as e:
680
+ SDKLogger.error(f"Failed to disable head tracking: {e}")
681
+
682
+ return False
683
+
684
+
685
+ """ Control Robot Motion """
686
+
687
+ # JoyButton constants
688
+ BUTTON_A = 0
689
+ BUTTON_B = 1
690
+ BUTTON_X = 2
691
+ BUTTON_Y = 3
692
+ BUTTON_LB = 4
693
+ BUTTON_RB = 5
694
+ BUTTON_BACK = 6
695
+ BUTTON_START = 7
696
+
697
+ # JoyAxis constants
698
+ AXIS_LEFT_STICK_Y = 0
699
+ AXIS_LEFT_STICK_X = 1
700
+ AXIS_LEFT_LT = 2 # 1 -> (-1)
701
+ AXIS_RIGHT_STICK_YAW = 3
702
+ AXIS_RIGHT_STICK_Z = 4
703
+ AXIS_RIGHT_RT = 5 # 1 -> (-1)
704
+ AXIS_LEFT_RIGHT_TRIGGER = 6
705
+ AXIS_FORWARD_BACK_TRIGGER = 7
706
+
707
+
708
+ class ControlRobotMotion:
709
+ def __init__(self):
710
+ self._pub_cmd_vel = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
711
+ self._pub_cmd_pose = rospy.Publisher('/cmd_pose', Twist, queue_size=10)
712
+ self._pub_cmd_pose_world = rospy.Publisher('/cmd_pose_world', Twist, queue_size=10)
713
+ self._pub_joy = rospy.Publisher('/joy', Joy, queue_size=10)
714
+ self._pub_switch_gait = rospy.Publisher('/humanoid_switch_gait_by_name', switchGaitByName, queue_size=10)
715
+ self._pub_step_ctrl = rospy.Publisher('/humanoid_mpc_foot_pose_target_trajectories', footPoseTargetTrajectories, queue_size=10)
716
+
717
+ def connect(self, timeout:float=3.0)-> bool:
718
+ start_time = rospy.Time.now()
719
+ publishers = [
720
+ # (self._pub_joy, "joy publisher"),
721
+ # pub name required
722
+ (self._pub_cmd_vel, "cmd_vel publisher", False),
723
+ (self._pub_cmd_pose, "cmd_pose publisher", False),
724
+ (self._pub_step_ctrl, "step_ctrl publisher", False),
725
+ (self._pub_switch_gait, "switch_gait publisher", False),
726
+ (self._pub_cmd_pose_world, "cmd_pose_world publisher", False),
727
+ ]
728
+
729
+ success = True
730
+ for pub, name, required in publishers:
731
+ while pub.get_num_connections() == 0:
732
+ if (rospy.Time.now() - start_time).to_sec() > timeout:
733
+ SDKLogger.error(f"Timeout waiting for {name} connection, '{pub.name}'")
734
+ if required:
735
+ success = False
736
+ break
737
+ rospy.sleep(0.1)
738
+ return success
739
+
740
+ def pub_cmd_vel(self, linear_x: float, linear_y: float, angular_z: float)->bool:
741
+ try:
742
+ twist = Twist()
743
+ twist.linear.x = linear_x
744
+ twist.linear.y = linear_y
745
+ twist.angular.z = angular_z
746
+ self._pub_cmd_vel.publish(twist)
747
+ return True
748
+ except Exception as e:
749
+ SDKLogger.error(f"[Error] publish cmd vel: {e}")
750
+ return False
751
+
752
+ def pub_cmd_pose(self, twist)->bool:
753
+ try:
754
+ self._pub_cmd_pose.publish(twist)
755
+ return True
756
+ except Exception as e:
757
+ SDKLogger.error(f"[Error] publish cmd pose: {e}")
758
+ return False
759
+
760
+ def pub_cmd_pose_world(self, twist:Twist)->bool:
761
+ try:
762
+ self._pub_cmd_pose_world.publish(twist)
763
+ return True
764
+ except Exception as e:
765
+ SDKLogger.error(f"[Error] publish cmd pose world: {e}")
766
+ return False
767
+
768
+ def _create_joy_msg(self)->Joy:
769
+ joy_msg = Joy()
770
+ joy_msg.axes = [0.0] * 8 # Initialize 8 axes
771
+ joy_msg.buttons = [0] * 16 # Initialize 16 buttons
772
+ return joy_msg
773
+
774
+ def _pub_joy_command(self, button_index: int, command_name: str) -> bool:
775
+ try:
776
+ joy_msg = self._create_joy_msg()
777
+ joy_msg.buttons[button_index] = 1
778
+ self._pub_joy.publish(joy_msg)
779
+ SDKLogger.debug(f"Published {command_name} command")
780
+ return True
781
+ except Exception as e:
782
+ SDKLogger.error(f"[Error] publish {command_name}: {e}")
783
+ return False
784
+
785
+ def _pub_switch_gait_by_name(self, gait_name: str) -> bool:
786
+ try:
787
+ msg = switchGaitByName()
788
+ msg.header.stamp = rospy.Time.now()
789
+ msg.gait_name = gait_name
790
+ self._pub_switch_gait.publish(msg)
791
+ # print(f"Published {gait_name} gait")
792
+ return True
793
+ except Exception as e:
794
+ SDKLogger.error(f"[Error] publish switch gait {gait_name}: {e}")
795
+ return False
796
+
797
+ def pub_walk_command(self) -> bool:
798
+ # return self._pub_joy_command(BUTTON_Y, "walk")
799
+ return self._pub_switch_gait_by_name("walk")
800
+
801
+ def pub_stance_command(self) -> bool:
802
+ try:
803
+ self.pub_cmd_vel(linear_x=0.0, linear_y=0.0, angular_z=0.0)
804
+ # return self._pub_joy_command(BUTTON_A, "stance")
805
+ return self._pub_switch_gait_by_name("stance")
806
+ except Exception as e:
807
+ SDKLogger.error(f"[Error] publish stance: {e}")
808
+ return False
809
+
810
+ def pub_trot_command(self) -> bool:
811
+ # return self._pub_joy_command(BUTTON_B, "trot")
812
+ return self._pub_switch_gait_by_name("walk")
813
+
814
+ def pub_step_ctrl(self, msg)->bool:
815
+ try:
816
+ self._pub_step_ctrl.publish(msg)
817
+ return True
818
+ except Exception as e:
819
+ SDKLogger.error(f"[Error] publish step ctrl: {e}")
820
+ return False
821
+
822
+ class KuavoRobotArmIKFK:
823
+ def __init__(self):
824
+ pass
825
+ def arm_ik(self,
826
+ left_pose: KuavoPose,
827
+ right_pose: KuavoPose,
828
+ left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
829
+ right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
830
+ arm_q0: list = None,
831
+ params: KuavoIKParams=None) -> list:
832
+ eef_pose_msg = twoArmHandPoseCmd()
833
+ if arm_q0 is None:
834
+ eef_pose_msg.joint_angles_as_q0 = False
835
+ else:
836
+ eef_pose_msg.joint_angles_as_q0 = True
837
+ eef_pose_msg.joint_angles = arm_q0
838
+
839
+ if params is None:
840
+ eef_pose_msg.use_custom_ik_param = False
841
+ else:
842
+ eef_pose_msg.use_custom_ik_param = True
843
+ eef_pose_msg.ik_param.major_optimality_tol = params.major_optimality_tol
844
+ eef_pose_msg.ik_param.major_feasibility_tol = params.major_feasibility_tol
845
+ eef_pose_msg.ik_param.minor_feasibility_tol = params.minor_feasibility_tol
846
+ eef_pose_msg.ik_param.major_iterations_limit = params.major_iterations_limit
847
+ eef_pose_msg.ik_param.oritation_constraint_tol= params.oritation_constraint_tol
848
+ eef_pose_msg.ik_param.pos_constraint_tol = params.pos_constraint_tol
849
+ eef_pose_msg.ik_param.pos_cost_weight = params.pos_cost_weight
850
+
851
+ # left hand
852
+ eef_pose_msg.hand_poses.left_pose.pos_xyz = left_pose.position
853
+ eef_pose_msg.hand_poses.left_pose.quat_xyzw = left_pose.orientation
854
+ eef_pose_msg.hand_poses.left_pose.elbow_pos_xyz = left_elbow_pos_xyz
855
+
856
+ # right hand
857
+ eef_pose_msg.hand_poses.right_pose.pos_xyz = right_pose.position
858
+ eef_pose_msg.hand_poses.right_pose.quat_xyzw = right_pose.orientation
859
+ eef_pose_msg.hand_poses.right_pose.elbow_pos_xyz = right_elbow_pos_xyz
860
+
861
+ return self._srv_arm_ik(eef_pose_msg)
862
+
863
+ def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
864
+ return self._srv_arm_fk(q)
865
+
866
+ def _srv_arm_ik(self, eef_pose_msg)->list:
867
+ try:
868
+ rospy.wait_for_service('/ik/two_arm_hand_pose_cmd_srv',timeout=1.0)
869
+ ik_srv = rospy.ServiceProxy('/ik/two_arm_hand_pose_cmd_srv', twoArmHandPoseCmdSrv)
870
+ res = ik_srv(eef_pose_msg)
871
+ # print(eef_pose_msg)
872
+ if res.success:
873
+ return res.hand_poses.left_pose.joint_angles + res.hand_poses.right_pose.joint_angles
874
+ else:
875
+ return None
876
+ except rospy.ServiceException as e:
877
+ print("Service call failed: %s"%e)
878
+ return None
879
+ except Exception as e:
880
+ print(f"Failed to call ik/fk_srv: {e}")
881
+ return None
882
+ def _srv_arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
883
+ try:
884
+ rospy.wait_for_service('/ik/fk_srv',timeout=1.0)
885
+ ik_srv = rospy.ServiceProxy('/ik/fk_srv', fkSrv)
886
+ res = ik_srv(q)
887
+ if res.success:
888
+ return KuavoPose(position=res.hand_poses.left_pose.pos_xyz, orientation=res.hand_poses.left_pose.quat_xyzw), \
889
+ KuavoPose(position=res.hand_poses.right_pose.pos_xyz, orientation=res.hand_poses.right_pose.quat_xyzw),
890
+ else:
891
+ return None
892
+ except rospy.ServiceException as e:
893
+ print("Service call failed: %s"%e)
894
+ return None
895
+ except Exception as e:
896
+ print(f"Failed to call ik/fk_srv: {e}")
897
+ return None
898
+
899
+
900
+
901
+ """
902
+ Kuavo Robot Control
903
+ """
904
+ class KuavoRobotControl:
905
+ _instance = None
906
+
907
+ def __new__(cls, *args, **kwargs):
908
+ if not cls._instance:
909
+ cls._instance = super().__new__(cls)
910
+ if not rospy.core.is_initialized():
911
+ if not rospy.get_node_uri():
912
+ rospy.init_node(f'kuavo_sdk_node_{os.getpid()}', anonymous=True, disable_signals=True)
913
+ return cls._instance
914
+
915
+ def __init__(self):
916
+ if not hasattr(self, '_initialized'):
917
+ self._initialized = True
918
+ self.kuavo_eef_control = None
919
+ self.kuavo_head_control = ControlRobotHead()
920
+ self.kuavo_arm_control = ControlRobotArm()
921
+ self.kuavo_motion_control = ControlRobotMotion()
922
+ self.kuavo_arm_ik_fk = KuavoRobotArmIKFK()
923
+ # SDKLogger.debug("KuavoRobotControl initialized.")
924
+
925
+ def initialize(self, eef_type:str=None, debug:bool=False, timeout:float=1.0)-> Tuple[bool, str]:
926
+ # init eef control
927
+ if eef_type is None:
928
+ self.kuavo_eef_control = None
929
+ else:
930
+ self.kuavo_eef_control = ControlEndEffector(eef_type=eef_type)
931
+
932
+ connect_success = True
933
+ err_msg = ''
934
+ if not self.kuavo_arm_control.connect(timeout):
935
+ connect_success = False
936
+ err_msg = "Failed to connect to arm control topics, \n"
937
+ if not self.kuavo_head_control.connect(timeout):
938
+ connect_success = False
939
+ err_msg += "Failed to connect to head control topics, \n"
940
+ if not self.kuavo_motion_control.connect(timeout):
941
+ err_msg += "Failed to connect to motion control topics, \n"
942
+ connect_success = False
943
+
944
+ if self.kuavo_eef_control is not None and not self.kuavo_eef_control.connect(timeout):
945
+ connect_success = False
946
+ err_msg += "Failed to connect to end effector control topics."
947
+
948
+ if connect_success:
949
+ err_msg = 'success'
950
+ return connect_success, err_msg
951
+
952
+ """ End Effector Control"""
953
+ def control_robot_dexhand(self, left_position:list, right_position:list)->bool:
954
+ """
955
+ Control robot dexhand
956
+ Args:
957
+ left_position: list of 6 floats between 0 and 100
958
+ right_position: list of 6 floats between 0 and 100
959
+ """
960
+ if self.kuavo_eef_control is None:
961
+ SDKLogger.error("End effector control is not initialized.")
962
+ return False
963
+
964
+ if len(left_position) != 6 or len(right_position) != 6:
965
+ raise ValueError("Position lists must have a length of 6.")
966
+
967
+ for position in left_position + right_position:
968
+ if position < 0.0 or position > 100.0:
969
+ raise ValueError("All position values must be in the range [0.0, 100.0].")
970
+
971
+ SDKLogger.debug(f"Control robot dexhand: {left_position}, {right_position}")
972
+ return self.kuavo_eef_control.pub_control_robot_dexhand(left_position, right_position)
973
+
974
+ def robot_dexhand_command(self, data, ctrl_mode, hand_side):
975
+ """
976
+ Publish dexhand command
977
+ Args:
978
+ - data: list of 6 floats between 0 and 100
979
+ - ctrl_mode: int between 0(position), 1(velocity)
980
+ - hand_side: int between 0(left), 1(right), 2(dual)
981
+ """
982
+ if self.kuavo_eef_control is None:
983
+ SDKLogger.error("End effector control is not initialized.")
984
+ return False
985
+ return self.kuavo_eef_control.pub_dexhand_command(data, ctrl_mode, hand_side)
986
+
987
+ def execute_gesture(self, gestures:list)->bool:
988
+ """
989
+ Execute gestures
990
+ Arguments:
991
+ - gestures: list of dicts with keys 'gesture_name' and 'hand_side'
992
+ e.g. [{'gesture_name': 'fist', 'hand_side': 0},]
993
+ """
994
+ if self.kuavo_eef_control is None:
995
+ SDKLogger.warn("End effectors control is not initialized.")
996
+ return False
997
+ return self.kuavo_eef_control.srv_execute_gesture(gestures)
998
+
999
+ def get_gesture_names(self)->list:
1000
+ """
1001
+ Get the names of all gestures.
1002
+ """
1003
+ if self.kuavo_eef_control is None:
1004
+ SDKLogger.warn("End effectors control is not initialized.")
1005
+ return []
1006
+ return self.kuavo_eef_control.srv_get_gesture_names()
1007
+
1008
+ def control_leju_claw(self, postions:list, velocities:list=[90, 90], torques:list=[1.0, 1.0]) ->bool:
1009
+ """
1010
+ Control leju claw
1011
+ Arguments:
1012
+ - postions: list of positions for left and right claw
1013
+ - velocities: list of velocities for left and right claw
1014
+ - torques: list of torques for left and right claw
1015
+ """
1016
+ if self.kuavo_eef_control is None:
1017
+ SDKLogger.warn("End effectors control is not initialized.")
1018
+ return False
1019
+ SDKLogger.debug(f"Control leju claw: {postions}, {velocities}, {torques}")
1020
+ if len(postions) != 2 or len(velocities) != 2 or len(torques) != 2:
1021
+ raise ValueError("Position, velocity, and torque lists must have a length of 2.")
1022
+ return self.kuavo_eef_control.srv_control_leju_claw(postions, velocities, torques)
1023
+ """--------------------------------------------------------------------------------------------"""
1024
+ def control_robot_head(self, yaw:float, pitch:float)->bool:
1025
+ """
1026
+ Control robot head
1027
+ Arguments:
1028
+ - yaw: yaw angle, radian
1029
+ - pitch: pitch angle, radian
1030
+ """
1031
+ SDKLogger.debug(f"Control robot head: {yaw}, {pitch}")
1032
+ return self.kuavo_head_control.pub_control_robot_head(yaw, pitch)
1033
+
1034
+ def enable_head_tracking(self, target_id: int)->bool:
1035
+ """Enable the head tracking for a specific tag ID.
1036
+
1037
+ Args:
1038
+ target_id: The ID of the tag to track
1039
+
1040
+ Returns:
1041
+ bool: True if successful, False otherwise
1042
+ """
1043
+ SDKLogger.debug(f"Enable head tracking: {target_id}")
1044
+ return self.kuavo_head_control.srv_enable_head_tracking(target_id)
1045
+
1046
+ def disable_head_tracking(self)->bool:
1047
+ """Disable the head tracking.
1048
+
1049
+ Returns:
1050
+ bool: True if successful, False otherwise
1051
+ """
1052
+ SDKLogger.debug(f"Disable head tracking")
1053
+ return self.kuavo_head_control.srv_disable_head_tracking()
1054
+
1055
+ def control_robot_arm_joint_positions(self, joint_data:list)->bool:
1056
+ """
1057
+ Control robot arm joint positions
1058
+ Arguments:
1059
+ - joint_data: list of joint data (degrees)
1060
+ """
1061
+ # SDKLogger.debug(f"[ROS] Control robot arm trajectory: {joint_data}")
1062
+ return self.kuavo_arm_control.pub_control_robot_arm_traj(joint_data)
1063
+
1064
+ def is_arm_collision(self)->bool:
1065
+ """
1066
+ Check if arm collision is happening
1067
+ Returns:
1068
+ bool: True if collision is happening, False otherwise
1069
+ """
1070
+ return self.kuavo_arm_control.is_arm_collision()
1071
+
1072
+ def is_arm_collision_mode(self)->bool:
1073
+ """
1074
+ Check if arm collision mode is enabled
1075
+ Returns:
1076
+ bool: True if collision mode is enabled, False otherwise
1077
+ """
1078
+ return self.kuavo_arm_control.is_arm_collision_mode()
1079
+
1080
+ def release_arm_collision_mode(self):
1081
+ """
1082
+ Release arm collision mode
1083
+ """
1084
+ return self.kuavo_arm_control.release_arm_collision_mode()
1085
+
1086
+ def wait_arm_collision_complete(self):
1087
+ """
1088
+ Wait for arm collision to complete
1089
+ """
1090
+ return self.kuavo_arm_control.wait_arm_collision_complete()
1091
+
1092
+ def set_arm_collision_mode(self, enable: bool):
1093
+ """
1094
+ Set arm collision mode
1095
+ """
1096
+ return self.kuavo_arm_control.set_arm_collision_mode(enable)
1097
+
1098
+ def control_robot_arm_joint_trajectory(self, times:list, joint_q:list)->bool:
1099
+ """
1100
+ Control robot arm joint trajectory
1101
+ Arguments:
1102
+ - times: list of times (seconds)
1103
+ - joint_q: list of joint data (degrees)
1104
+ """
1105
+ if len(times) != len(joint_q):
1106
+ raise ValueError("Times and joint_q must have the same length.")
1107
+ elif len(times) == 0:
1108
+ raise ValueError("Times and joint_q must not be empty.")
1109
+
1110
+ return self.kuavo_arm_control.pub_arm_target_poses(times=times, joint_q=joint_q)
1111
+
1112
+ def control_robot_end_effector_pose(self, left_pose: KuavoPose, right_pose: KuavoPose, frame: KuavoManipulationMpcFrame)->bool:
1113
+ """
1114
+ Control robot end effector pose
1115
+ Arguments:
1116
+ - left_pose: left end effector pose
1117
+ - right_pose: right end effector pose
1118
+ - frame: frame of the end effector pose, 0: keep current frame, 1: world frame, 2: local frame, 3: VR frame, 4: manipulation world frame
1119
+ """
1120
+ return self.kuavo_arm_control.pub_end_effector_pose_cmd(left_pose, right_pose, frame)
1121
+
1122
+ def change_manipulation_mpc_frame(self, frame: KuavoManipulationMpcFrame)->bool:
1123
+ """
1124
+ Change manipulation mpc frame
1125
+ Arguments:
1126
+ - frame: frame of the manipulation mpc
1127
+ """
1128
+ return self.kuavo_arm_control.srv_change_manipulation_mpc_frame(frame)
1129
+
1130
+ def change_manipulation_mpc_ctrl_mode(self, ctrl_mode: KuavoManipulationMpcCtrlMode)->bool:
1131
+ """
1132
+ Change manipulation mpc control mode
1133
+ Arguments:
1134
+ - control_mode: control mode of the manipulation mpc
1135
+ """
1136
+ return self.kuavo_arm_control.srv_change_manipulation_mpc_ctrl_mode(ctrl_mode)
1137
+
1138
+ def change_manipulation_mpc_control_flow(self, ctrl_flow: KuavoManipulationMpcControlFlow)->bool:
1139
+ """
1140
+ Change manipulation mpc wbc arm traj control mode, control signal will be sent to wbc directly
1141
+ Arguments:
1142
+ - control_mode: control mode of the manipulation mpc wbc arm traj
1143
+ """
1144
+ return self.kuavo_arm_control.srv_change_manipulation_mpc_control_flow(ctrl_flow)
1145
+
1146
+ def get_manipulation_mpc_ctrl_mode(self)->KuavoManipulationMpcCtrlMode:
1147
+ """
1148
+ Get manipulation mpc control mode
1149
+ """
1150
+ return self.kuavo_arm_control.srv_get_manipulation_mpc_ctrl_mode()
1151
+
1152
+ def get_manipulation_mpc_frame(self)-> KuavoManipulationMpcFrame:
1153
+ """
1154
+ Get manipulation mpc frame
1155
+ """
1156
+ return self.kuavo_arm_control.srv_get_manipulation_mpc_frame()
1157
+
1158
+ def get_manipulation_mpc_control_flow(self)->KuavoManipulationMpcControlFlow:
1159
+ """
1160
+ Get manipulation mpc wbc arm traj control mode
1161
+ """
1162
+ return self.kuavo_arm_control.srv_get_manipulation_mpc_control_flow()
1163
+
1164
+ def change_robot_arm_ctrl_mode(self, mode:KuavoArmCtrlMode)->bool:
1165
+ """
1166
+ Change robot arm control mode
1167
+ Arguments:
1168
+ - mode: arm control mode
1169
+ """
1170
+ SDKLogger.debug(f"[ROS] Change robot arm control mode: {mode}")
1171
+ return self.kuavo_arm_control.srv_change_arm_ctrl_mode(mode)
1172
+
1173
+ def get_robot_arm_ctrl_mode(self)->int:
1174
+ """
1175
+ Get robot arm control mode
1176
+ """
1177
+ return self.kuavo_arm_control.srv_get_arm_ctrl_mode()
1178
+
1179
+ def arm_ik(self, left_pose: KuavoPose, right_pose: KuavoPose,
1180
+ left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
1181
+ right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
1182
+ arm_q0: list = None, params: KuavoIKParams=None) -> list:
1183
+ return self.kuavo_arm_ik_fk.arm_ik(left_pose, right_pose, left_elbow_pos_xyz, right_elbow_pos_xyz, arm_q0, params)
1184
+
1185
+
1186
+ def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
1187
+ return self.kuavo_arm_ik_fk.arm_fk(q)
1188
+
1189
+ """ Motion """
1190
+ def robot_stance(self)->bool:
1191
+ return self.kuavo_motion_control.pub_stance_command()
1192
+
1193
+ def robot_trot(self)->bool:
1194
+ return self.kuavo_motion_control.pub_trot_command()
1195
+
1196
+ def robot_walk(self, linear_x:float, linear_y:float, angular_z:float)->bool:
1197
+ return self.kuavo_motion_control.pub_cmd_vel(linear_x, linear_y, angular_z)
1198
+
1199
+ def control_torso_height(self, height:float, pitch:float=0.0)->bool:
1200
+ com_msg = Twist()
1201
+ com_msg.linear.z = height
1202
+ com_msg.angular.y = pitch
1203
+ return self.kuavo_motion_control.pub_cmd_pose(com_msg)
1204
+
1205
+ def control_command_pose_world(self, target_pose_x:float, target_pose_y:float, target_pose_z:float, target_pose_yaw:float)->bool:
1206
+ """
1207
+ odom下的机器人cmd_pose_world
1208
+ """
1209
+ com_msg = Twist()
1210
+ com_msg.linear.x = target_pose_x
1211
+ com_msg.linear.y = target_pose_y
1212
+ com_msg.linear.z = target_pose_z
1213
+ com_msg.angular.z = target_pose_yaw
1214
+ return self.kuavo_motion_control.pub_cmd_pose_world(com_msg)
1215
+
1216
+ def control_command_pose(self, target_pose_x:float, target_pose_y:float, target_pose_z:float, target_pose_yaw:float)->bool:
1217
+ """
1218
+ base_link下的机器人cmd_pose
1219
+ """
1220
+ com_msg = Twist()
1221
+ com_msg.linear.x = target_pose_x
1222
+ com_msg.linear.y = target_pose_y
1223
+ com_msg.linear.z = target_pose_z
1224
+ com_msg.angular.z = target_pose_yaw
1225
+ return self.kuavo_motion_control.pub_cmd_pose(com_msg)
1226
+
1227
+ def step_control(self, body_poses:list, dt:float, is_left_first_default:bool=True, collision_check:bool=True)->bool:
1228
+ """
1229
+ Step control
1230
+ Arguments:
1231
+ - body_poses: list of body poses (x, y, z, yaw), meters and degrees
1232
+ - dt: time step (seconds)
1233
+ - is_left_first_default: whether to start with left foot
1234
+ - collision_check: whether to check for collisions
1235
+ """
1236
+ if len(body_poses) == 0:
1237
+ raise ValueError("Body poses must not be empty.")
1238
+ if dt <= 0.0:
1239
+ raise ValueError("Time step must be greater than 0.0.")
1240
+ for bp in body_poses:
1241
+ if len(bp) != 4:
1242
+ raise ValueError("Body pose must have 4 elements: [x, y, z, yaw]")
1243
+
1244
+ msg = get_multiple_steps_msg(body_poses, dt, is_left_first_default, collision_check)
1245
+ return self.kuavo_motion_control.pub_step_ctrl(msg)
1246
+
1247
+ def change_motor_param(self, motor_param:list)->Tuple[bool, str]:
1248
+ """
1249
+ Change motor param
1250
+ """
1251
+ try:
1252
+ service_name = '/hardware/change_motor_param'
1253
+ rospy.wait_for_service(service=service_name, timeout=2.0)
1254
+ change_motor_param_service = rospy.ServiceProxy(service_name, changeMotorParam)
1255
+
1256
+ # request
1257
+ request = changeMotorParamRequest()
1258
+ for param in motor_param:
1259
+ request.data.append(motorParam(Kp=param.Kp, Kd=param.Kd, id=param.id))
1260
+
1261
+ # call service
1262
+ response = change_motor_param_service(request)
1263
+ if not response.success:
1264
+ SDKLogger.error(f"Failed to change motor param: {response.message}")
1265
+ return False, response.message
1266
+ return True, 'success'
1267
+ except rospy.ServiceException as e:
1268
+ SDKLogger.error(f"Service call failed: {e}")
1269
+ except rospy.ROSException as e:
1270
+ SDKLogger.error(f"Service call failed: {e}")
1271
+ except Exception as e:
1272
+ SDKLogger.error(f"Service call failed: {e}")
1273
+ return False, 'failed'
1274
+
1275
+ def get_motor_param(self)->Tuple[bool, list, str]:
1276
+ try:
1277
+ service_name = '/hardware/get_motor_param'
1278
+ rospy.wait_for_service(service=service_name, timeout=2.0)
1279
+ motor_param_service = rospy.ServiceProxy(service_name, getMotorParam)
1280
+
1281
+ # request
1282
+ request = getMotorParamRequest()
1283
+ response = motor_param_service(request)
1284
+ if not response.success:
1285
+ SDKLogger.error(f"Failed to get motor param: {response.message}")
1286
+ return False, None, response.message
1287
+ params = []
1288
+ for param in response.data:
1289
+ params.append(KuavoMotorParam(Kp=param.Kp, Kd=param.Kd, id=param.id))
1290
+ return True, params, 'success'
1291
+ except rospy.ServiceException as e:
1292
+ SDKLogger.error(f"Service call failed: {e}")
1293
+ except rospy.ROSException as e:
1294
+ SDKLogger.error(f"Service call failed: {e}")
1295
+ except Exception as e:
1296
+ SDKLogger.error(f"Service call failed: {e}")
1297
+ return False, None, 'failed'
1298
+
1299
+ def control_hand_wrench(self, left_wrench: list, right_wrench: list) -> bool:
1300
+ return self.kuavo_arm_control.pub_hand_wrench_cmd(left_wrench, right_wrench)
1301
+
1302
+ def enable_base_pitch_limit(self, enable: bool) -> Tuple[bool, str]:
1303
+ res_msg = 'failed'
1304
+ try:
1305
+ service_name = '/humanoid/mpc/enable_base_pitch_limit'
1306
+ rospy.wait_for_service(service=service_name, timeout=2.0)
1307
+ pitch_limit_service = rospy.ServiceProxy(service_name, SetBool)
1308
+
1309
+ # request
1310
+ request = SetBoolRequest()
1311
+ request.data = enable
1312
+ response = pitch_limit_service(request)
1313
+ if not response.success:
1314
+ SDKLogger.error(f"Failed to enable pitch limit: {response.message}")
1315
+ return False, response.message
1316
+ return True, 'success'
1317
+ except rospy.ServiceException as e:
1318
+ SDKLogger.error(f"Service call failed: {e}")
1319
+ res_msg = str(e)
1320
+ except rospy.ROSException as e:
1321
+ SDKLogger.error(f"Service call failed: {e}")
1322
+ res_msg = str(e)
1323
+ except Exception as e:
1324
+ SDKLogger.error(f"Service call failed: {e}")
1325
+ res_msg = str(e)
1326
+ return False, res_msg
1327
+
1328
+ def euler_to_rotation_matrix(yaw, pitch, roll):
1329
+ # 计算各轴的旋转矩阵
1330
+ R_yaw = np.array([[np.cos(yaw), -np.sin(yaw), 0],
1331
+ [np.sin(yaw), np.cos(yaw), 0],
1332
+ [0, 0, 1]])
1333
+
1334
+ R_pitch = np.array([[np.cos(pitch), 0, np.sin(pitch)],
1335
+ [0, 1, 0],
1336
+ [-np.sin(pitch), 0, np.cos(pitch)]])
1337
+
1338
+ R_roll = np.array([[1, 0, 0],
1339
+ [0, np.cos(roll), -np.sin(roll)],
1340
+ [0, np.sin(roll), np.cos(roll)]])
1341
+
1342
+ # 按照 Yaw-Pitch-Roll 的顺序组合旋转矩阵
1343
+ R = np.dot(R_roll, np.dot(R_pitch, R_yaw))
1344
+ return R
1345
+
1346
+ def get_foot_pose_traj_msg(time_traj:list, foot_idx_traj:list, foot_traj:list, torso_traj:list):
1347
+ num = len(time_traj)
1348
+
1349
+ msg = footPoseTargetTrajectories()
1350
+ msg.timeTrajectory = time_traj
1351
+ msg.footIndexTrajectory = foot_idx_traj
1352
+ msg.footPoseTrajectory = []
1353
+
1354
+ for i in range(num):
1355
+ foot_pose_msg = footPose()
1356
+ foot_pose_msg.footPose = foot_traj[i]
1357
+ foot_pose_msg.torsoPose = torso_traj[i]
1358
+ msg.footPoseTrajectory.append(foot_pose_msg)
1359
+
1360
+ return msg
1361
+
1362
+ def generate_steps(torso_pos, torso_yaw, foot_bias):
1363
+ l_foot_bias = np.array([0, foot_bias, -torso_pos[2]])
1364
+ r_foot_bias = np.array([0, -foot_bias, -torso_pos[2]])
1365
+ R_z = np.array([
1366
+ [np.cos(torso_yaw), -np.sin(torso_yaw), 0],
1367
+ [np.sin(torso_yaw), np.cos(torso_yaw), 0],
1368
+ [0, 0, 1]
1369
+ ])
1370
+ l_foot = torso_pos + R_z.dot(l_foot_bias)
1371
+ r_foot = torso_pos + R_z.dot(r_foot_bias)
1372
+ return l_foot, r_foot
1373
+
1374
+ def get_multiple_steps_msg(body_poses:list, dt:float, is_left_first:bool=True, collision_check:bool=True):
1375
+ num_steps = 2*len(body_poses)
1376
+ time_traj = []
1377
+ foot_idx_traj = []
1378
+ foot_traj = []
1379
+ torso_traj = []
1380
+ l_foot_rect_last = RotatingRectangle(center=(0, 0.1), width=0.24, height=0.1, angle=0)
1381
+ r_foot_rect_last = RotatingRectangle(center=(0,-0.1), width=0.24, height=0.1, angle=0)
1382
+ torso_pose_last = np.array([0, 0, 0, 0])
1383
+ for i in range(num_steps):
1384
+ time_traj.append(dt * (i+1))
1385
+ body_pose = body_poses[i//2]
1386
+ torso_pos = np.asarray(body_pose[:3])
1387
+ torso_yaw = np.radians(body_pose[3])
1388
+ l_foot, r_foot = generate_steps(torso_pos, torso_yaw, 0.1)
1389
+ l_foot = [*l_foot[:3], torso_yaw]
1390
+ r_foot = [*r_foot[:3], torso_yaw]
1391
+
1392
+ if(i%2 == 0):
1393
+ torso_pose = np.array([*body_pose[:3], torso_yaw])
1394
+ R_wl = euler_to_rotation_matrix(torso_pose_last[3], 0, 0)
1395
+ delta_pos = R_wl.T @ (torso_pose[:3] - torso_pose_last[:3])
1396
+ # print("delta_pos:", delta_pos)
1397
+ if(torso_yaw > 0.0 or delta_pos[1] > 0.0):
1398
+ is_left_first = True
1399
+ else:
1400
+ is_left_first = False
1401
+
1402
+ if(collision_check and i%2 == 0):
1403
+ l_foot_rect_next = RotatingRectangle(center=(l_foot[0],l_foot[1]), width=0.24, height=0.1, angle=torso_yaw)
1404
+ r_foot_rect_next = RotatingRectangle(center=(r_foot[0],r_foot[1]), width=0.24, height=0.1, angle=torso_yaw)
1405
+ l_collision = l_foot_rect_next.is_collision(r_foot_rect_last)
1406
+ r_collision = r_foot_rect_next.is_collision(l_foot_rect_last)
1407
+ if l_collision and r_collision:
1408
+ SDKLogger.error("[Control] Detect collision, Please adjust your body_poses input!!!")
1409
+ break
1410
+ elif l_collision:
1411
+ SDKLogger.warn("[Control] Left foot is in collision, switch to right foot")
1412
+ is_left_first = False
1413
+ elif r_collision:
1414
+ SDKLogger.warn("[Control] Right foot is in collision, switch to left foot")
1415
+ is_left_first = True
1416
+ l_foot_rect_last = l_foot_rect_next
1417
+ r_foot_rect_last = r_foot_rect_next
1418
+ if(i%2 == 0):
1419
+ torso_traj.append((torso_pose_last + torso_pose)/2.0)
1420
+ if is_left_first:
1421
+ foot_idx_traj.append(0)
1422
+ foot_traj.append(l_foot)
1423
+ else:
1424
+ foot_idx_traj.append(1)
1425
+ foot_traj.append(r_foot)
1426
+ else:
1427
+ torso_traj.append(torso_pose)
1428
+ if is_left_first:
1429
+ foot_idx_traj.append(1)
1430
+ foot_traj.append(r_foot)
1431
+ else:
1432
+ foot_idx_traj.append(0)
1433
+ foot_traj.append(l_foot)
1434
+ torso_pose_last = torso_traj[-1]
1435
+ # print("time_traj:", time_traj)
1436
+ # print("foot_idx_traj:", foot_idx_traj)
1437
+ # print("foot_traj:", foot_traj)
1438
+ # print("torso_traj:", torso_traj)
1439
+ return get_foot_pose_traj_msg(time_traj, foot_idx_traj, foot_traj, torso_traj)
1440
+ """ ------------------------------------------------------------------------------"""
1441
+
1442
+
1443
+ # if __name__ == "__main__":
1444
+ # control = KuavoRobotControl()
1445
+ # control.change_manipulation_mpc_frame(KuavoManipulationMpcFrame.KeepCurrentFrame)
1446
+ # control.change_manipulation_mpc_ctrl_mode(KuavoManipulationMpcCtrlMode.ArmOnly)
1447
+ # control.change_manipulation_mpc_control_flow(KuavoManipulationMpcControlFlow.DirectToWbc)
1448
+ # print(control.get_manipulation_mpc_ctrl_mode())
1449
+ # print(control.get_manipulation_mpc_frame())
1450
+ # print(control.get_manipulation_mpc_control_flow())
1451
+ # control.change_manipulation_mpc_frame(KuavoManipulationMpcFrame.WorldFrame)
1452
+ # control.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ExternalControl)
1453
+ # 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)