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