kuavo-humanoid-sdk 1.2.1b3269__20250911204115-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 (184) 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 +16 -0
  9. kuavo_humanoid_sdk/kuavo/core/audio.py +32 -0
  10. kuavo_humanoid_sdk/kuavo/core/core.py +666 -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/llm_doubao.py +608 -0
  14. kuavo_humanoid_sdk/kuavo/core/microphone.py +192 -0
  15. kuavo_humanoid_sdk/kuavo/core/navigation.py +70 -0
  16. kuavo_humanoid_sdk/kuavo/core/ros/audio.py +110 -0
  17. kuavo_humanoid_sdk/kuavo/core/ros/control.py +1524 -0
  18. kuavo_humanoid_sdk/kuavo/core/ros/microphone.py +38 -0
  19. kuavo_humanoid_sdk/kuavo/core/ros/navigation.py +217 -0
  20. kuavo_humanoid_sdk/kuavo/core/ros/observation.py +94 -0
  21. kuavo_humanoid_sdk/kuavo/core/ros/param.py +201 -0
  22. kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
  23. kuavo_humanoid_sdk/kuavo/core/ros/state.py +652 -0
  24. kuavo_humanoid_sdk/kuavo/core/ros/tools.py +220 -0
  25. kuavo_humanoid_sdk/kuavo/core/ros/vision.py +234 -0
  26. kuavo_humanoid_sdk/kuavo/core/ros_env.py +238 -0
  27. kuavo_humanoid_sdk/kuavo/demo_climbstair.py +249 -0
  28. kuavo_humanoid_sdk/kuavo/dexterous_hand.py +238 -0
  29. kuavo_humanoid_sdk/kuavo/leju_claw.py +235 -0
  30. kuavo_humanoid_sdk/kuavo/logger_client.py +80 -0
  31. kuavo_humanoid_sdk/kuavo/robot.py +561 -0
  32. kuavo_humanoid_sdk/kuavo/robot_arm.py +299 -0
  33. kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
  34. kuavo_humanoid_sdk/kuavo/robot_blockly.py +1162 -0
  35. kuavo_humanoid_sdk/kuavo/robot_climbstair.py +1607 -0
  36. kuavo_humanoid_sdk/kuavo/robot_head.py +74 -0
  37. kuavo_humanoid_sdk/kuavo/robot_info.py +134 -0
  38. kuavo_humanoid_sdk/kuavo/robot_microphone.py +19 -0
  39. kuavo_humanoid_sdk/kuavo/robot_navigation.py +135 -0
  40. kuavo_humanoid_sdk/kuavo/robot_observation.py +64 -0
  41. kuavo_humanoid_sdk/kuavo/robot_speech.py +24 -0
  42. kuavo_humanoid_sdk/kuavo/robot_state.py +310 -0
  43. kuavo_humanoid_sdk/kuavo/robot_tool.py +109 -0
  44. kuavo_humanoid_sdk/kuavo/robot_vision.py +81 -0
  45. kuavo_humanoid_sdk/kuavo_strategy/__init__.py +2 -0
  46. kuavo_humanoid_sdk/kuavo_strategy/grasp_box/grasp_box_strategy.py +1325 -0
  47. kuavo_humanoid_sdk/kuavo_strategy/kuavo_strategy.py +106 -0
  48. kuavo_humanoid_sdk/kuavo_strategy_v2/common/data_type.py +340 -0
  49. kuavo_humanoid_sdk/kuavo_strategy_v2/common/events/base_event.py +215 -0
  50. kuavo_humanoid_sdk/kuavo_strategy_v2/common/robot_sdk.py +25 -0
  51. kuavo_humanoid_sdk/kuavo_strategy_v2/pick_place_box/case.py +331 -0
  52. kuavo_humanoid_sdk/kuavo_strategy_v2/pick_place_box/strategy.py +504 -0
  53. kuavo_humanoid_sdk/kuavo_strategy_v2/utils/logger_setup.py +40 -0
  54. kuavo_humanoid_sdk/kuavo_strategy_v2/utils/utils.py +88 -0
  55. kuavo_humanoid_sdk/msg/__init__.py +4 -0
  56. kuavo_humanoid_sdk/msg/kuavo_msgs/__init__.py +7 -0
  57. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetection.py +306 -0
  58. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetectionArray.py +437 -0
  59. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AudioReceiverData.py +122 -0
  60. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_FTsensorData.py +260 -0
  61. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_JoySticks.py +191 -0
  62. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_Metadata.py +199 -0
  63. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_MmDetectionMsg.py +264 -0
  64. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_RobotActionState.py +112 -0
  65. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_TFArray.py +323 -0
  66. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_TaskPoint.py +175 -0
  67. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/__init__.py +62 -0
  68. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armCollisionCheckInfo.py +160 -0
  69. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPose.py +161 -0
  70. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPoseFree.py +171 -0
  71. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armPoseWithTimeStamp.py +168 -0
  72. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armTargetPoses.py +171 -0
  73. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_bezierCurveCubicPoint.py +178 -0
  74. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_dexhandCommand.py +229 -0
  75. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_dexhandTouchState.py +256 -0
  76. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_endEffectorData.py +227 -0
  77. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose.py +123 -0
  78. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose6D.py +123 -0
  79. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose6DTargetTrajectories.py +320 -0
  80. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseTargetTrajectories.py +301 -0
  81. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseWithVision.py +136 -0
  82. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseWithVisionArray.py +231 -0
  83. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses.py +149 -0
  84. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses6D.py +149 -0
  85. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_fullBodyTargetTrajectories.py +258 -0
  86. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gaitTimeName.py +147 -0
  87. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gestureInfo.py +218 -0
  88. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gestureTask.py +149 -0
  89. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_handPose.py +136 -0
  90. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_headBodyPose.py +145 -0
  91. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_ikSolveError.py +171 -0
  92. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_ikSolveParam.py +140 -0
  93. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_imuData.py +165 -0
  94. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointBezierTrajectory.py +201 -0
  95. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointCmd.py +390 -0
  96. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointData.py +205 -0
  97. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_kuavoModeSchedule.py +224 -0
  98. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_lejuClawCommand.py +320 -0
  99. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_lejuClawState.py +341 -0
  100. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_motorParam.py +122 -0
  101. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_picoPoseInfo.py +143 -0
  102. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_picoPoseInfoList.py +220 -0
  103. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_planArmState.py +120 -0
  104. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_qv.py +121 -0
  105. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotArmQVVD.py +177 -0
  106. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotBodyMatrices.py +332 -0
  107. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotHandPosition.py +225 -0
  108. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotHeadMotionData.py +128 -0
  109. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotState.py +222 -0
  110. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_sensorsData.py +655 -0
  111. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_switchGaitByName.py +200 -0
  112. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_tagDataArray.py +216 -0
  113. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_touchSensorStatus.py +162 -0
  114. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPose.py +273 -0
  115. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmd.py +316 -0
  116. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmdFree.py +338 -0
  117. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseFree.py +299 -0
  118. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_yoloDetection.py +251 -0
  119. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_yoloOutputData.py +168 -0
  120. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_CreatePath.py +581 -0
  121. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_ExecuteArmAction.py +281 -0
  122. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetAllMaps.py +241 -0
  123. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetCurrentMap.py +225 -0
  124. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetTargetPartPoseInCamera.py +298 -0
  125. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_InitialPoseWithTaskPoint.py +281 -0
  126. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_LoadMap.py +281 -0
  127. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_NavigateToTaskPoint.py +281 -0
  128. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_RepublishTFs.py +373 -0
  129. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetInitialPose.py +394 -0
  130. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetJoyTopic.py +282 -0
  131. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetLEDMode.py +468 -0
  132. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetLEDMode_free.py +289 -0
  133. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SpeechSynthesis.py +270 -0
  134. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_TaskPointOperation.py +536 -0
  135. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/__init__.py +43 -0
  136. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_adjustZeroPoint.py +277 -0
  137. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeArmCtrlMode.py +275 -0
  138. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeArmCtrlModeKuavo.py +236 -0
  139. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeMotorParam.py +299 -0
  140. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeTorsoCtrlMode.py +274 -0
  141. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_controlLejuClaw.py +408 -0
  142. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_enableHandTouchSensor.py +304 -0
  143. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_fkSrv.py +395 -0
  144. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_footPose6DTargetTrajectoriesSrv.py +426 -0
  145. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_footPoseTargetTrajectoriesSrv.py +409 -0
  146. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureExecute.py +339 -0
  147. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureExecuteState.py +257 -0
  148. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureList.py +418 -0
  149. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getCurrentGaitName.py +253 -0
  150. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getMotorParam.py +299 -0
  151. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getMotorZeroPoints.py +286 -0
  152. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_handForceLevel.py +330 -0
  153. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_jointMoveTo.py +302 -0
  154. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryBezierCurve.py +422 -0
  155. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryCubicSpline.py +490 -0
  156. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_playmusic.py +268 -0
  157. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setHwIntialState.py +304 -0
  158. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setMmCtrlFrame.py +273 -0
  159. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setMotorEncoderRoundService.py +283 -0
  160. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setTagId.py +275 -0
  161. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_singleStepControl.py +444 -0
  162. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_twoArmHandPoseCmdFreeSrv.py +716 -0
  163. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_twoArmHandPoseCmdSrv.py +664 -0
  164. kuavo_humanoid_sdk/msg/motion_capture_ik/__init__.py +7 -0
  165. kuavo_humanoid_sdk/msg/ocs2_msgs/__init__.py +7 -0
  166. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/__init__.py +12 -0
  167. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_constraint.py +142 -0
  168. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_controller_data.py +121 -0
  169. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_lagrangian_metrics.py +148 -0
  170. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mode_schedule.py +150 -0
  171. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_flattened_controller.py +666 -0
  172. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_input.py +122 -0
  173. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_observation.py +209 -0
  174. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_performance_indices.py +140 -0
  175. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_solver_data.py +886 -0
  176. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_state.py +122 -0
  177. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_target_trajectories.py +239 -0
  178. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_multiplier.py +148 -0
  179. kuavo_humanoid_sdk/msg/ocs2_msgs/srv/__init__.py +1 -0
  180. kuavo_humanoid_sdk/msg/ocs2_msgs/srv/_reset.py +376 -0
  181. kuavo_humanoid_sdk-1.2.1b3269.dist-info/METADATA +296 -0
  182. kuavo_humanoid_sdk-1.2.1b3269.dist-info/RECORD +184 -0
  183. kuavo_humanoid_sdk-1.2.1b3269.dist-info/WHEEL +6 -0
  184. kuavo_humanoid_sdk-1.2.1b3269.dist-info/top_level.txt +1 -0
@@ -0,0 +1,666 @@
1
+ #!/usr/bin/env python3
2
+ # coding: utf-8
3
+ """
4
+ This layer is responsible for robot state transitions.
5
+ The robot has three states:
6
+ - stance: Standing still state
7
+ - walk: Walking state
8
+ - trot: Trotting state
9
+
10
+ State transitions are managed by a state machine that ensures valid transitions between states.
11
+ The state machine enforces the following transitions:
12
+ - stance <-> walk
13
+ - stance <-> trot
14
+ - walk <-> trot
15
+
16
+ Each state has an entry callback that handles initialization when entering that state.
17
+ """
18
+
19
+
20
+ import time
21
+ import math
22
+ import threading
23
+ import numpy as np
24
+ from typing import Tuple
25
+ from transitions import Machine, State
26
+
27
+ from kuavo_humanoid_sdk.interfaces.data_types import KuavoArmCtrlMode, KuavoIKParams, KuavoPose, KuavoManipulationMpcFrame, KuavoManipulationMpcCtrlMode, KuavoManipulationMpcControlFlow
28
+ from kuavo_humanoid_sdk.kuavo.core.ros.control import KuavoRobotControl
29
+ from kuavo_humanoid_sdk.kuavo.core.ros.state import KuavoRobotStateCore
30
+ from kuavo_humanoid_sdk.kuavo.core.ros.param import make_robot_param
31
+ from kuavo_humanoid_sdk.common.logger import SDKLogger
32
+ from kuavo_humanoid_sdk.kuavo.logger_client import get_logger
33
+ # Define robot states
34
+ ROBOT_STATES = [
35
+ State(name='stance', on_enter=['_on_enter_stance']),
36
+ State(name='walk', on_enter=['_on_enter_walk']),
37
+ State(name='trot', on_enter=['_on_enter_trot']),
38
+ State(name='custom_gait', on_enter=['_on_enter_custom_gait']),
39
+ State(name='command_pose_world', on_enter=['_on_enter_command_pose_world']),
40
+ State(name='command_pose', on_enter=['_on_enter_command_pose']),
41
+ ]
42
+
43
+ # Define state transitions
44
+ ROBOT_TRANSITIONS = [
45
+ {'trigger': 'to_stance', 'source': ['walk', 'trot', 'custom_gait', 'command_pose_world', 'command_pose'], 'dest': 'stance'},
46
+ {'trigger': 'to_walk', 'source': ['stance', 'trot', 'custom_gait'], 'dest': 'walk'},
47
+ {'trigger': 'to_trot', 'source': ['stance', 'walk', 'custom_gait'], 'dest': 'trot'},
48
+ {'trigger': 'to_custom_gait', 'source': ['stance', 'custom_gait'], 'dest': 'custom_gait'},
49
+ {'trigger': 'to_command_pose_world', 'source': ['stance', 'command_pose_world'], 'dest': 'command_pose_world'},
50
+ {'trigger': 'to_command_pose', 'source': ['stance', 'command_pose'], 'dest': 'command_pose'},
51
+ ]
52
+
53
+ class KuavoRobotCore:
54
+ _instance = None
55
+
56
+ def __new__(cls):
57
+ if cls._instance is None:
58
+ cls._instance = super(KuavoRobotCore, cls).__new__(cls)
59
+ return cls._instance
60
+
61
+ def __init__(self):
62
+ if not hasattr(self, '_initialized'):
63
+ self.logger = get_logger() # ✅ 初始化日志客户端(全局唯一)
64
+ self.machine = Machine(
65
+ model=self,
66
+ states=ROBOT_STATES,
67
+ transitions=ROBOT_TRANSITIONS,
68
+ initial='stance',
69
+ send_event=True
70
+ )
71
+
72
+ self._control = KuavoRobotControl()
73
+ self._rb_state = KuavoRobotStateCore()
74
+
75
+ # manipulation mpc
76
+ self._manipulation_mpc_frame = KuavoManipulationMpcFrame.KeepCurrentFrame
77
+ self._manipulation_mpc_ctrl_mode = KuavoManipulationMpcCtrlMode.NoControl
78
+ self._manipulation_mpc_control_flow = KuavoManipulationMpcControlFlow.ThroughFullBodyMpc
79
+
80
+ self._arm_ctrl_mode = KuavoArmCtrlMode.AutoSwing
81
+
82
+ # register gait changed callback
83
+ self._rb_state.register_gait_changed_callback(self._humanoid_gait_changed)
84
+ # initialized
85
+ self._initialized = True
86
+
87
+ def initialize(self, debug: bool=False)->bool:
88
+ """
89
+ raise RuntimeError if initialize failed.
90
+ """
91
+ try:
92
+ # init state by gait_name
93
+ gait_name = self._rb_state.gait_name()
94
+ if gait_name is not None:
95
+ to_method = f'to_{gait_name}'
96
+ if hasattr(self, to_method):
97
+ SDKLogger.debug(f"[Core] initialize state: {gait_name}")
98
+ # Call the transition method if it exists
99
+ getattr(self, to_method)()
100
+ else:
101
+ SDKLogger.warn(f"[Core] gait_name is None, use default `stance`")
102
+ # init arm control mode
103
+ arm_ctrl_mode = self._rb_state.arm_control_mode
104
+ if arm_ctrl_mode is not None:
105
+ self._arm_ctrl_mode = arm_ctrl_mode
106
+ SDKLogger.debug(f"[Core] initialize arm control mode: {arm_ctrl_mode}")
107
+
108
+ # init manipulation mpc
109
+ manipulation_mpc_frame = self._rb_state.manipulation_mpc_frame
110
+ if manipulation_mpc_frame is not None:
111
+ self._manipulation_mpc_frame = manipulation_mpc_frame
112
+ SDKLogger.debug(f"[Core] initialize manipulation mpc frame: {manipulation_mpc_frame}")
113
+ manipulation_mpc_ctrl_mode = self._rb_state.manipulation_mpc_ctrl_mode
114
+ if manipulation_mpc_ctrl_mode is not None:
115
+ self._manipulation_mpc_ctrl_mode = manipulation_mpc_ctrl_mode
116
+ SDKLogger.debug(f"[Core] initialize manipulation mpc ctrl mode: {manipulation_mpc_ctrl_mode}")
117
+ manipulation_mpc_control_flow = self._rb_state.manipulation_mpc_control_flow
118
+ if manipulation_mpc_control_flow is not None:
119
+ self._manipulation_mpc_control_flow = manipulation_mpc_control_flow
120
+ SDKLogger.debug(f"[Core] initialize manipulation mpc control flow: {manipulation_mpc_control_flow}")
121
+
122
+ except Exception as e:
123
+ raise RuntimeError(f"[Core] initialize failed: \n"
124
+ f"{e}, please check the robot is launched, "
125
+ f"e.g. `roslaunch humanoid_controllers load_kuavo_real.launch`")
126
+ self._rb_info = make_robot_param()
127
+ success, err_msg = self._control.initialize(eef_type=self._rb_info["end_effector_type"], debug=debug)
128
+ if not success:
129
+ raise RuntimeError(f"[Core] initialize failed: \n{err_msg}, please check the robot is launched, "
130
+ f"e.g. `roslaunch humanoid_controllers load_kuavo_real.launch`")
131
+ return True
132
+
133
+ """ ----------------------- Machine State -----------------------"""
134
+ def _on_enter_stance(self, event):
135
+ previous_state = event.transition.source
136
+ if self.state == previous_state:
137
+ SDKLogger.debug(f"[Core] [StateMachine] State unchanged: already in stance state")
138
+ return
139
+
140
+ SDKLogger.debug(f"[Core] [StateMachine] Entering stance state, from {previous_state}")
141
+ if previous_state == 'walk':
142
+ self._control.robot_walk(0.0, 0.0, 0.0) # stop walk state
143
+ start_time = time.time()
144
+ # slow down walk
145
+ try:
146
+ while time.time() - start_time < 1.5:
147
+ self._control.robot_walk(0.0, 0.0, 0.0)
148
+ # linear_x, linear_y, angular_z
149
+ if (abs(self._rb_state.odom_data.linear[0]) < 0.05 and abs(self._rb_state.odom_data.linear[1]) < 0.08
150
+ and abs(self._rb_state.odom_data.angular[2]) < 0.05):
151
+ SDKLogger.debug(f"walk stop, time_cost:{time.time() - start_time}, odom_data:{self._rb_state.odom_data.linear}")
152
+ break
153
+ # SDKLogger.debug(f"kuavo robot linear: {self._rb_state.odom_data.linear}")
154
+ time.sleep(0.1)
155
+ except KeyboardInterrupt:
156
+ pass
157
+ self._control.robot_stance()
158
+ else:
159
+ self._control.robot_stance()
160
+ time.sleep(0.5)
161
+
162
+ def _on_enter_walk(self, event):
163
+ previous_state = event.transition.source
164
+ if self.state == previous_state:
165
+ SDKLogger.debug(f"[Core] [StateMachine] State unchanged: already in walk state")
166
+ return
167
+ SDKLogger.debug(f"[Core] [StateMachine] Entering walk state, from {previous_state}")
168
+
169
+ def _on_enter_trot(self, event):
170
+ previous_state = event.transition.source
171
+ if self.state == previous_state:
172
+ SDKLogger.debug(f"[Core] [StateMachine] State unchanged: already in trot state")
173
+ return
174
+ SDKLogger.debug(f"[Core] [StateMachine] Entering trot state, from {previous_state}")
175
+ self._control.robot_trot()
176
+
177
+ def _on_enter_custom_gait(self, event):
178
+ previous_state = event.transition.source
179
+ if self.state == previous_state:
180
+ SDKLogger.debug(f"[Core] [StateMachine] State unchanged: already in custom_gait state")
181
+ return
182
+ SDKLogger.debug(f"[Core] [StateMachine] Entering custom_gait state, from {previous_state}")
183
+
184
+ def _on_enter_command_pose_world(self, event):
185
+ previous_state = event.transition.source
186
+ if self.state == previous_state:
187
+ SDKLogger.debug(f"[Core] [StateMachine] State unchanged: already in command_pose_world state")
188
+ return
189
+ SDKLogger.debug(f"[Core] [StateMachine] Entering command_pose_world state, from {previous_state}")
190
+
191
+ def _on_enter_command_pose(self, event):
192
+ previous_state = event.transition.source
193
+ if self.state == previous_state:
194
+ SDKLogger.debug(f"[Core] [StateMachine] State unchanged: already in command_pose state")
195
+ return
196
+ SDKLogger.debug(f"[Core] [StateMachine] Entering command_pose state, from {previous_state}")
197
+
198
+ """ -------------------------------------------------------------"""
199
+
200
+ """ --------------------------- Control -------------------------"""
201
+ def walk(self, linear_x:float, linear_y:float, angular_z:float)-> bool:
202
+ if self.state != 'walk':
203
+ self.to_walk()
204
+
205
+ # +-0.4, +-0.2, +-0.4 => linear_x, linear_y, angular_z
206
+ limited_linear_x = min(0.4, abs(linear_x)) * (1 if linear_x >= 0 else -1)
207
+ limited_linear_y = min(0.2, abs(linear_y)) * (1 if linear_y >= 0 else -1)
208
+ limited_angular_z = min(0.4, abs(angular_z)) * (1 if angular_z >= 0 else -1)
209
+ return self._control.robot_walk(limited_linear_x, limited_linear_y, limited_angular_z)
210
+
211
+ def squat(self, height:float, pitch:float)->bool:
212
+ if self.state != 'stance':
213
+ SDKLogger.warn(f"[Core] control torso height failed, robot is not in stance state({self.state})!")
214
+ return False
215
+
216
+ MIN_HEIGHT = -0.35
217
+ MAX_HEIGHT = 0.0
218
+ MIN_PITCH = -0.4
219
+ MAX_PITCH = 0.4
220
+
221
+ # Limit height range
222
+ limited_height = min(MAX_HEIGHT, max(MIN_HEIGHT, height))
223
+ if height > MAX_HEIGHT or height < MIN_HEIGHT:
224
+ SDKLogger.warn(f"[Core] height {height} exceeds limit [{MIN_HEIGHT}, {MAX_HEIGHT}], will be limited")
225
+
226
+ # Limit pitch range
227
+ limited_pitch = min(MAX_PITCH, max(MIN_PITCH, pitch))
228
+ if abs(pitch) > MAX_PITCH:
229
+ SDKLogger.warn(f"[Core] pitch {pitch} exceeds limit [{MIN_PITCH}, {MAX_PITCH}], will be limited")
230
+
231
+ # 结合当前高度做过滤
232
+ target_height = self._rb_info['init_stand_height'] + limited_height
233
+ # 躯干上升运动变化不宜过大, 目标高度减去实时躯干高度大于阈值
234
+ HEIGHT_CHANGE_THRESHOLD = 0.25
235
+ if (self._rb_state.com_height < target_height) and (target_height - self._rb_state.com_height) >= HEIGHT_CHANGE_THRESHOLD:
236
+ limited_height = (self._rb_state.com_height + HEIGHT_CHANGE_THRESHOLD) - self._rb_info['init_stand_height']
237
+ print(f"\033[33mWarning! Height change too large, limiting to safe range,reset height to {limited_height}\033[0m")
238
+
239
+ return self._control.control_torso_height(limited_height, limited_pitch)
240
+
241
+ def step_control(self, target_pose:list, dt:float=0.4, is_left_first_default:bool=True, collision_check:bool=True)->bool:
242
+ """
243
+ Control the robot's motion by step.
244
+ Raises:
245
+ ValueError: If target_pose length is not 4.
246
+ RuntimeError: If the robot is not in stance state when trying to control step motion.
247
+ """
248
+ if len(target_pose) != 4:
249
+ raise ValueError(f"[Core] target_pose length must be 4, but got {len(target_pose)}")
250
+
251
+ # Wait up to 1.0s for stance state
252
+ wait_time = 0
253
+ while self._rb_state.gait_name() != 'stance' and wait_time < 1.0:
254
+ time.sleep(0.1)
255
+ wait_time += 0.1
256
+
257
+ if self._rb_state.gait_name() != 'stance':
258
+ raise RuntimeError(f"[Core] control robot step failed, robot is not in stance state, {self._rb_state.gait_name()}!")
259
+
260
+ if self.state != 'stance':
261
+ raise RuntimeError(f"[Core] control robot step failed, robot is not in stance state({self.state})!")
262
+
263
+ com_height = self._rb_state.com_height
264
+ # print(f"[Core] Current COM height: {com_height:.2f}m")
265
+ # Check height limits based on current COM height
266
+ MIN_COM_HEIGHT = self._rb_info['init_stand_height'] - 0.15 # Minimum allowed COM height in meters
267
+ MAX_COM_HEIGHT = self._rb_info['init_stand_height'] + 0.02 # Maximum allowed COM height in meters
268
+
269
+ if com_height < MIN_COM_HEIGHT:
270
+ print(f"\033[31m[Core] Torso height too low, control failed: current COM height {com_height:.2f}m is below the minimum allowed height {MIN_COM_HEIGHT}m\033[0m")
271
+ return False
272
+
273
+ # Validate COM height constraints
274
+ if target_pose[2] < 0 and com_height < MIN_COM_HEIGHT:
275
+ print(f"\033[33mWarning! Cannot squat lower: COM height {com_height:.2f}m below minimum {MIN_COM_HEIGHT}m\033[0m")
276
+ return False
277
+
278
+ if target_pose[2] > 0 and com_height > MAX_COM_HEIGHT:
279
+ print(f"\033[33mWarning! Cannot stand higher: COM height {com_height:.2f}m above maximum {MAX_COM_HEIGHT}m\033[0m")
280
+ return False
281
+
282
+ # Ensure target height is within allowed range if height change requested
283
+ if target_pose[2] != 0:
284
+ target_height = com_height + target_pose[2]
285
+ if target_height < MIN_COM_HEIGHT:
286
+ SDKLogger.warn(f"[Core] Target height {target_height:.2f}m below minimum {MIN_COM_HEIGHT}m, limiting")
287
+ target_pose[2] = MIN_COM_HEIGHT - com_height
288
+ elif target_height > MAX_COM_HEIGHT:
289
+ SDKLogger.warn(f"[Core] Target height {target_height:.2f}m above maximum {MAX_COM_HEIGHT}m, limiting")
290
+ target_pose[2] = MAX_COM_HEIGHT - com_height
291
+
292
+ if com_height > (self._rb_info['init_stand_height']-0.03):
293
+ max_x_step = 0.20
294
+ max_y_step = 0.20
295
+ max_yaw_step = 90
296
+ else:
297
+ max_x_step = 0.15
298
+ max_y_step = 0.15
299
+ max_yaw_step = 45
300
+
301
+ body_poses = []
302
+
303
+ # 计算目标点到原点的距离和朝向
304
+ target_dist_x = abs(target_pose[0])
305
+ target_dist_y = abs(target_pose[1])
306
+ target_yaw = target_pose[3] * 180 / math.pi # Convert yaw from radians to degrees
307
+
308
+ # 计算需要的步数(考虑x位移、y位移和转角)
309
+ steps_for_x = int(np.ceil(target_dist_x / max_x_step))
310
+ steps_for_y = int(np.ceil(target_dist_y / max_y_step))
311
+ steps_for_yaw = int(np.ceil(abs(target_yaw) / max_yaw_step))
312
+ steps_needed = max(steps_for_x, steps_for_y, steps_for_yaw)
313
+ # print(f"[Core] Steps needed - X: {steps_for_x}, Y: {steps_for_y}, Yaw: {steps_for_yaw}, Total: {steps_needed}")
314
+
315
+ # 计算每一步的增量
316
+ dx = target_pose[0] / steps_needed
317
+ dy = target_pose[1] / steps_needed
318
+ dyaw = target_yaw / steps_needed
319
+
320
+ # 分解为多个小步,沿着直线路径前进并逐步调整朝向
321
+ for i in range(steps_needed):
322
+ x = dx * (i+1)
323
+ y = dy * (i+1)
324
+ z = target_pose[2]
325
+ yaw = dyaw * (i+1)
326
+ body_poses.append([x, y, 0.0, yaw])
327
+
328
+ # print("target_pose:", target_pose)
329
+ # print("body_poses:", body_poses)
330
+
331
+ if not self._control.step_control(body_poses, dt, is_left_first_default, collision_check):
332
+ return False
333
+
334
+ # # Wait for gait to switch to custom_gait
335
+ # start_time = time.time()
336
+ # SDKLogger.warning("-------------------STEP CONTROL -----------------------------")
337
+ # while not self._rb_state.is_gait('custom_gait'):
338
+ # if time.time() - start_time > 1.0: # 1.0s timeout
339
+ # SDKLogger.warn("[Core] Timeout waiting for gait to switch to custom_gait")
340
+ # return False
341
+ # time.sleep(0.01)
342
+ # SDKLogger.warning("-------------------STEP CONTROL -----------------------------")
343
+
344
+ return True
345
+
346
+ def control_command_pose(self, target_pose_x:float, target_pose_y:float, target_pose_z:float, target_pose_yaw:float)->bool:
347
+ """
348
+ Control robot pose in base_link frame
349
+
350
+ Arguments:
351
+ - target_pose_x: x position (meters)
352
+ - target_pose_y: y position (meters)
353
+ - target_pose_z: z position (meters)
354
+ - target_pose_yaw: yaw angle (radians)
355
+
356
+ Returns:
357
+ bool: True if command was sent successfully, False otherwise
358
+
359
+ Raises:
360
+ RuntimeError: If robot is not in stance state
361
+ """
362
+ if self.state != 'stance':
363
+ raise RuntimeError(f"[Core] control_command_pose failed: robot must be in stance state, current state: {self.state}")
364
+
365
+ # Add any parameter validation if needed
366
+ # e.g., limit ranges for safety
367
+ self.to_command_pose()
368
+ return self._control.control_command_pose(target_pose_x, target_pose_y, target_pose_z, target_pose_yaw)
369
+
370
+ def control_command_pose_world(self, target_pose_x:float, target_pose_y:float, target_pose_z:float, target_pose_yaw:float)->bool:
371
+ """
372
+ Control robot pose in odom (world) frame
373
+
374
+ Arguments:
375
+ - target_pose_x: x position (meters)
376
+ - target_pose_y: y position (meters)
377
+ - target_pose_z: z position (meters)
378
+ - target_pose_yaw: yaw angle (radians)
379
+
380
+ Returns:
381
+ bool: True if command was sent successfully, False otherwise
382
+
383
+ Raises:
384
+ RuntimeError: If robot is not in stance state
385
+ """
386
+ # if self.state != 'stance':
387
+ # raise RuntimeError(f"[Core] control_command_pose_world failed: robot must be in stance state, current state: {self.state}")
388
+
389
+ # Add any parameter validation if needed
390
+ # e.g., limit ranges for safety
391
+ self.to_command_pose_world()
392
+ return self._control.control_command_pose_world(target_pose_x, target_pose_y, target_pose_z, target_pose_yaw)
393
+
394
+ def control_robot_arm_target_poses(self, times: list, joint_q: list) -> bool:
395
+ if self.state != 'stance':
396
+ raise RuntimeError("[Core] control_robot_arm_target_poses failed: robot must be in stance state")
397
+
398
+ if self._arm_ctrl_mode != KuavoArmCtrlMode.ExternalControl:
399
+ SDKLogger.debug("[Core] control_robot_arm_target_poses, current arm mode != ExternalControl, change it.")
400
+ if not self.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ExternalControl):
401
+ SDKLogger.warn("[Core] control_robot_arm_target_poses failed, change robot arm ctrl mode failed!")
402
+ return False
403
+
404
+ return self._control.control_robot_arm_target_poses(times, joint_q)
405
+ def execute_gesture(self, gestures:list)->bool:
406
+ return self._control.execute_gesture(gestures)
407
+
408
+ def get_gesture_names(self)->list:
409
+ return self._control.get_gesture_names()
410
+
411
+ def control_robot_dexhand(self, left_position:list, right_position:list)->bool:
412
+ return self._control.control_robot_dexhand(left_position, right_position)
413
+
414
+ def robot_dexhand_command(self, data, ctrl_mode, hand_side):
415
+ return self._control.robot_dexhand_command(data, ctrl_mode, hand_side)
416
+
417
+
418
+ def control_leju_claw(self, postions:list, velocities:list=[90, 90], torques:list=[1.0, 1.0]) ->bool:
419
+ return self._control.control_leju_claw(postions, velocities, torques)
420
+
421
+ def control_robot_head(self, yaw:float, pitch:float)->bool:
422
+ # Convert radians to degrees
423
+ yaw_deg = yaw * 180 / math.pi
424
+ pitch_deg = pitch * 180 / math.pi
425
+ return self._control.control_robot_head(yaw_deg, pitch_deg)
426
+
427
+ def enable_head_tracking(self, target_id: int)->bool:
428
+ return self._control.enable_head_tracking(target_id)
429
+
430
+ def disable_head_tracking(self)->bool:
431
+ return self._control.disable_head_tracking()
432
+
433
+ def control_robot_arm_joint_positions(self, joint_data:list)->bool:
434
+ if self.state != 'stance':
435
+ raise RuntimeError(f"[Core] control_robot_arm_joint_positions failed: robot must be in stance state, current state: {self.state}")
436
+
437
+ if self._control.is_arm_collision_mode() and self._control.is_arm_collision():
438
+ raise RuntimeError(f"Arm collision detected, cannot publish arm trajectory")
439
+ # change to external control mode
440
+ if self._arm_ctrl_mode != KuavoArmCtrlMode.ExternalControl:
441
+ SDKLogger.debug("[Core] control_robot_arm_joint_positions, current arm mode != ExternalControl, change it.")
442
+ if not self.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ExternalControl):
443
+ SDKLogger.warn("[Core] control_robot_arm_joint_positions failed, change robot arm ctrl mode failed!")
444
+ return False
445
+ return self._control.control_robot_arm_joint_positions(joint_data)
446
+
447
+ def control_robot_arm_joint_trajectory(self, times:list, joint_q:list)->bool:
448
+ if self.state != 'stance':
449
+ raise RuntimeError("[Core] control_robot_arm_joint_trajectory failed: robot must be in stance state")
450
+
451
+ if self._control.is_arm_collision_mode() and self._control.is_arm_collision():
452
+ raise RuntimeError(f"Arm collision detected, cannot publish arm trajectory")
453
+
454
+ if self._arm_ctrl_mode != KuavoArmCtrlMode.ExternalControl:
455
+ SDKLogger.debug("[Core] control_robot_arm_joint_trajectory, current arm mode != ExternalControl, change it.")
456
+ if not self.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ExternalControl):
457
+ SDKLogger.warn("[Core] control_robot_arm_joint_trajectory failed, change robot arm ctrl mode failed!")
458
+ return False
459
+
460
+ return self._control.control_robot_arm_joint_trajectory(times, joint_q)
461
+
462
+ def control_robot_end_effector_pose(self, left_pose: KuavoPose, right_pose: KuavoPose, frame: KuavoManipulationMpcFrame)->bool:
463
+ if self._arm_ctrl_mode != KuavoArmCtrlMode.ExternalControl:
464
+ SDKLogger.debug("[Core] control_robot_end_effector_pose, current arm mode != ExternalControl, change it.")
465
+ if not self.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ExternalControl):
466
+ SDKLogger.warn("[Core] control_robot_end_effector_pose failed, change robot arm ctrl mode failed!")
467
+ return False
468
+
469
+ if self._manipulation_mpc_ctrl_mode == KuavoManipulationMpcCtrlMode.NoControl:
470
+ SDKLogger.debug("[Core] control_robot_end_effector_pose, manipulation mpc ctrl mode is NoControl, change it.")
471
+ if not self.change_manipulation_mpc_ctrl_mode(KuavoManipulationMpcCtrlMode.ArmOnly):
472
+ SDKLogger.warn("[Core] control_robot_end_effector_pose failed, change manipulation mpc ctrl mode failed!")
473
+ return False
474
+
475
+ return self._control.control_robot_end_effector_pose(left_pose, right_pose, frame)
476
+
477
+ def control_hand_wrench(self, left_wrench: list, right_wrench: list) -> bool:
478
+ return self._control.control_hand_wrench(left_wrench, right_wrench)
479
+
480
+ def change_manipulation_mpc_frame(self, frame: KuavoManipulationMpcFrame)->bool:
481
+ timeout = 1.0
482
+ count = 0
483
+ while self._rb_state.manipulation_mpc_frame != frame:
484
+ SDKLogger.debug(f"[Core] Change manipulation mpc frame from {self._rb_state.manipulation_mpc_frame} to {frame}, retry: {count}")
485
+ self._control.change_manipulation_mpc_frame(frame)
486
+ if self._rb_state.manipulation_mpc_frame == frame:
487
+ break
488
+ if timeout <= 0:
489
+ SDKLogger.warn("[Core] Change manipulation mpc frame timeout!")
490
+ return False
491
+ timeout -= 0.1
492
+ time.sleep(0.1)
493
+ count += 1
494
+ if not hasattr(self, '_manipulation_mpc_frame_lock'):
495
+ self._manipulation_mpc_frame_lock = threading.Lock()
496
+ with self._manipulation_mpc_frame_lock:
497
+ self._manipulation_mpc_frame = frame
498
+ return True
499
+
500
+ def change_manipulation_mpc_ctrl_mode(self, control_mode: KuavoManipulationMpcCtrlMode)->bool:
501
+ timeout = 1.0
502
+ count = 0
503
+ while self._rb_state.manipulation_mpc_ctrl_mode != control_mode:
504
+ SDKLogger.debug(f"[Core] Change manipulation mpc ctrl mode from {self._rb_state.manipulation_mpc_ctrl_mode} to {control_mode}, retry: {count}")
505
+ self._control.change_manipulation_mpc_ctrl_mode(control_mode)
506
+ if self._rb_state.manipulation_mpc_ctrl_mode == control_mode:
507
+ break
508
+ if timeout <= 0:
509
+ SDKLogger.warn("[Core] Change manipulation mpc ctrl mode timeout!")
510
+ return False
511
+ timeout -= 0.1
512
+ time.sleep(0.1)
513
+ count += 1
514
+ if not hasattr(self, '_manipulation_mpc_ctrl_mode_lock'):
515
+ self._manipulation_mpc_ctrl_mode_lock = threading.Lock()
516
+ with self._manipulation_mpc_ctrl_mode_lock:
517
+ self._manipulation_mpc_ctrl_mode = control_mode
518
+ return True
519
+
520
+ def change_manipulation_mpc_control_flow(self, control_flow: KuavoManipulationMpcControlFlow)->bool:
521
+ timeout = 1.0
522
+ count = 0
523
+ while self._rb_state.manipulation_mpc_control_flow != control_flow:
524
+ SDKLogger.debug(f"[Core] Change manipulation mpc control flow from {self._rb_state.manipulation_mpc_control_flow} to {control_flow}, retry: {count}")
525
+ self._control.change_manipulation_mpc_control_flow(control_flow)
526
+ if self._rb_state.manipulation_mpc_control_flow == control_flow:
527
+ break
528
+ if timeout <= 0:
529
+ SDKLogger.warn("[Core] Change manipulation mpc control flow timeout!")
530
+ return False
531
+ timeout -= 0.1
532
+ time.sleep(0.1)
533
+ count += 1
534
+ if not hasattr(self, '_manipulation_mpc_control_flow_lock'):
535
+ self._manipulation_mpc_control_flow_lock = threading.Lock()
536
+ with self._manipulation_mpc_control_flow_lock:
537
+ self._manipulation_mpc_control_flow = control_flow
538
+ return True
539
+
540
+ def change_robot_arm_ctrl_mode(self, mode:KuavoArmCtrlMode)->bool:
541
+
542
+ if self._control.is_arm_collision_mode() and self.is_arm_collision():
543
+ SDKLogger.warn("[Core] change_robot_arm_ctrl_mode failed, arm collision detected!")
544
+ return False
545
+
546
+ count = 0
547
+ if self._rb_state.arm_control_mode != mode:
548
+ SDKLogger.debug(f"[Core] Change robot arm control from {self._rb_state.arm_control_mode} to {mode}, retry: {count}")
549
+ self._control.change_robot_arm_ctrl_mode(mode)
550
+
551
+ if not hasattr(self, '_arm_ctrl_mode_lock'):
552
+ self._arm_ctrl_mode_lock = threading.Lock()
553
+ with self._arm_ctrl_mode_lock:
554
+ # 手臂控制模式切换成功,更新当前手臂控制模式
555
+ self._arm_ctrl_mode = mode # update arm ctrl mode
556
+
557
+ return True
558
+
559
+ def robot_arm_reset(self)->bool:
560
+ if self.state != 'stance':
561
+ SDKLogger.warn("[Core] robot arm reset failed, robot is not in stance state!")
562
+ return
563
+
564
+ # init_pos = [0.0]*14
565
+ # if not self.control_robot_arm_joint_trajectory([1.5], [init_pos]):
566
+ # SDKLogger.warn("[Core] robot arm reset failed, control robot arm traj failed!")
567
+ # return False
568
+
569
+ return self.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.AutoSwing)
570
+
571
+ def robot_manipulation_mpc_reset(self)->bool:
572
+ if self._manipulation_mpc_ctrl_mode != KuavoManipulationMpcCtrlMode.NoControl:
573
+ SDKLogger.debug("[Core] robot manipulation mpc reset, current manipulation mpc ctrl mode != NoControl, change it.")
574
+ if not self.change_manipulation_mpc_ctrl_mode(KuavoManipulationMpcCtrlMode.NoControl):
575
+ SDKLogger.warn("[Core] robot manipulation mpc reset failed, change manipulation mpc ctrl mode failed!")
576
+ return False
577
+ if self._manipulation_mpc_control_flow != KuavoManipulationMpcControlFlow.ThroughFullBodyMpc:
578
+ SDKLogger.debug("[Core] robot manipulation mpc reset, current manipulation mpc control flow != ThroughFullBodyMpc, change it.")
579
+ if not self.change_manipulation_mpc_control_flow(KuavoManipulationMpcControlFlow.ThroughFullBodyMpc):
580
+ SDKLogger.warn("[Core] robot manipulation mpc reset failed, change manipulation mpc control flow failed!")
581
+ return False
582
+ return True
583
+ """ ------------------------------------------------------------------------"""
584
+ """ 电机参数设置 """
585
+ def change_motor_param(self, motor_param:list)-> Tuple[bool, str]:
586
+ return self._control.change_motor_param(motor_param)
587
+
588
+ def get_motor_param(self)-> Tuple[bool, list]:
589
+ success, param, _ = self._control.get_motor_param()
590
+ return success, param
591
+
592
+ """ ------------------------------------------------------------------------"""
593
+ """ Arm Forward kinematics && Arm Inverse kinematics """
594
+ def arm_ik(self,
595
+ l_eef_pose: KuavoPose,
596
+ r_eef_pose: KuavoPose,
597
+ l_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
598
+ r_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
599
+ arm_q0: list = None,
600
+ params: KuavoIKParams=None) -> list:
601
+ return self._control.arm_ik(l_eef_pose, r_eef_pose, l_elbow_pos_xyz, r_elbow_pos_xyz, arm_q0, params)
602
+
603
+ def arm_ik_free(self,
604
+ l_eef_pose: KuavoPose,
605
+ r_eef_pose: KuavoPose,
606
+ l_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
607
+ r_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
608
+ arm_q0: list = None,
609
+ params: KuavoIKParams=None) -> list:
610
+ return self._control.arm_ik_free(l_eef_pose, r_eef_pose, l_elbow_pos_xyz, r_elbow_pos_xyz, arm_q0, params)
611
+
612
+ def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
613
+ return self._control.arm_fk(q)
614
+
615
+ """ ------------------------------------------------------------------------"""
616
+ """ Base Pitch Limit Control """
617
+ def enable_base_pitch_limit(self, enable: bool) -> Tuple[bool, str]:
618
+ return self._control.enable_base_pitch_limit(enable)
619
+ """ ------------------------------------------------------------------------"""
620
+ """ Callbacks """
621
+ def _humanoid_gait_changed(self, current_time: float, gait_name: str):
622
+ if self.state != gait_name:
623
+ # Check if to_$gait_name method exists
624
+ to_method = f'to_{gait_name}'
625
+ if hasattr(self, to_method):
626
+ SDKLogger.debug(f"[Core] Received gait change notification: {gait_name} at time {current_time}")
627
+ # Call the transition method if it exists
628
+ getattr(self, to_method)()
629
+
630
+ def is_arm_collision(self)->bool:
631
+ return self._control.is_arm_collision()
632
+
633
+ def release_arm_collision_mode(self):
634
+
635
+ self._control.release_arm_collision_mode()
636
+
637
+
638
+ def wait_arm_collision_complete(self):
639
+ self._control.wait_arm_collision_complete()
640
+
641
+ def set_arm_collision_mode(self, enable: bool):
642
+ self._control.set_arm_collision_mode(enable)
643
+
644
+ if __name__ == "__main__":
645
+ DEBUG_MODE = 0
646
+ core = KuavoRobotCore()
647
+ core.initialize()
648
+
649
+ if DEBUG_MODE == 0:
650
+ time.sleep(1.0)
651
+ core.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ExternalControl)
652
+ core.change_manipulation_mpc_frame(KuavoManipulationMpcFrame.VRFrame)
653
+ core.change_manipulation_mpc_ctrl_mode(KuavoManipulationMpcCtrlMode.ArmOnly)
654
+ core.change_manipulation_mpc_control_flow(KuavoManipulationMpcControlFlow.DirectToWbc)
655
+ core.robot_manipulation_mpc_reset()
656
+ elif DEBUG_MODE == 1:
657
+ core.to_stance()
658
+ print("state now is to_stance:", core.state)
659
+ core.control_command_pose_world(0.0, 1.0, 0.0, 1.57)
660
+ print("state now is control_command_pose_world:", core.state)
661
+ elif DEBUG_MODE == 2:
662
+ core.to_trot()
663
+ print("state now is to_trot:", core.state)
664
+ time.sleep(3.0)
665
+ core.to_stance()
666
+ print("state now is to_stance:", core.state)