kuavo-humanoid-sdk 1.2.2b3208__20250922170818-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 (186) 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/camera.py +105 -0
  18. kuavo_humanoid_sdk/kuavo/core/ros/control.py +1524 -0
  19. kuavo_humanoid_sdk/kuavo/core/ros/microphone.py +38 -0
  20. kuavo_humanoid_sdk/kuavo/core/ros/navigation.py +217 -0
  21. kuavo_humanoid_sdk/kuavo/core/ros/observation.py +94 -0
  22. kuavo_humanoid_sdk/kuavo/core/ros/param.py +201 -0
  23. kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
  24. kuavo_humanoid_sdk/kuavo/core/ros/state.py +652 -0
  25. kuavo_humanoid_sdk/kuavo/core/ros/tools.py +220 -0
  26. kuavo_humanoid_sdk/kuavo/core/ros/vision.py +234 -0
  27. kuavo_humanoid_sdk/kuavo/core/ros_env.py +238 -0
  28. kuavo_humanoid_sdk/kuavo/core/sdk_deprecated.py +41 -0
  29. kuavo_humanoid_sdk/kuavo/demo_climbstair.py +249 -0
  30. kuavo_humanoid_sdk/kuavo/dexterous_hand.py +238 -0
  31. kuavo_humanoid_sdk/kuavo/leju_claw.py +235 -0
  32. kuavo_humanoid_sdk/kuavo/logger_client.py +80 -0
  33. kuavo_humanoid_sdk/kuavo/robot.py +646 -0
  34. kuavo_humanoid_sdk/kuavo/robot_arm.py +411 -0
  35. kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
  36. kuavo_humanoid_sdk/kuavo/robot_blockly.py +1154 -0
  37. kuavo_humanoid_sdk/kuavo/robot_climbstair.py +1607 -0
  38. kuavo_humanoid_sdk/kuavo/robot_head.py +95 -0
  39. kuavo_humanoid_sdk/kuavo/robot_info.py +134 -0
  40. kuavo_humanoid_sdk/kuavo/robot_microphone.py +19 -0
  41. kuavo_humanoid_sdk/kuavo/robot_navigation.py +135 -0
  42. kuavo_humanoid_sdk/kuavo/robot_observation.py +64 -0
  43. kuavo_humanoid_sdk/kuavo/robot_speech.py +24 -0
  44. kuavo_humanoid_sdk/kuavo/robot_state.py +310 -0
  45. kuavo_humanoid_sdk/kuavo/robot_tool.py +109 -0
  46. kuavo_humanoid_sdk/kuavo/robot_vision.py +81 -0
  47. kuavo_humanoid_sdk/kuavo_strategy/__init__.py +2 -0
  48. kuavo_humanoid_sdk/kuavo_strategy/grasp_box/grasp_box_strategy.py +1325 -0
  49. kuavo_humanoid_sdk/kuavo_strategy/kuavo_strategy.py +106 -0
  50. kuavo_humanoid_sdk/kuavo_strategy_v2/common/data_type.py +340 -0
  51. kuavo_humanoid_sdk/kuavo_strategy_v2/common/events/base_event.py +215 -0
  52. kuavo_humanoid_sdk/kuavo_strategy_v2/common/robot_sdk.py +25 -0
  53. kuavo_humanoid_sdk/kuavo_strategy_v2/pick_place_box/case.py +331 -0
  54. kuavo_humanoid_sdk/kuavo_strategy_v2/pick_place_box/strategy.py +504 -0
  55. kuavo_humanoid_sdk/kuavo_strategy_v2/utils/logger_setup.py +40 -0
  56. kuavo_humanoid_sdk/kuavo_strategy_v2/utils/utils.py +88 -0
  57. kuavo_humanoid_sdk/msg/__init__.py +4 -0
  58. kuavo_humanoid_sdk/msg/kuavo_msgs/__init__.py +7 -0
  59. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetection.py +306 -0
  60. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetectionArray.py +437 -0
  61. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AudioReceiverData.py +122 -0
  62. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_FTsensorData.py +260 -0
  63. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_JoySticks.py +191 -0
  64. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_Metadata.py +199 -0
  65. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_MmDetectionMsg.py +264 -0
  66. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_RobotActionState.py +112 -0
  67. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_TFArray.py +323 -0
  68. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_TaskPoint.py +175 -0
  69. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/__init__.py +62 -0
  70. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armCollisionCheckInfo.py +160 -0
  71. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPose.py +161 -0
  72. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPoseFree.py +171 -0
  73. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armPoseWithTimeStamp.py +168 -0
  74. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armTargetPoses.py +171 -0
  75. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_bezierCurveCubicPoint.py +178 -0
  76. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_dexhandCommand.py +229 -0
  77. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_dexhandTouchState.py +256 -0
  78. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_endEffectorData.py +227 -0
  79. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose.py +123 -0
  80. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose6D.py +123 -0
  81. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose6DTargetTrajectories.py +320 -0
  82. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseTargetTrajectories.py +301 -0
  83. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseWithVision.py +136 -0
  84. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseWithVisionArray.py +231 -0
  85. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses.py +149 -0
  86. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses6D.py +149 -0
  87. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_fullBodyTargetTrajectories.py +258 -0
  88. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gaitTimeName.py +147 -0
  89. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gestureInfo.py +218 -0
  90. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gestureTask.py +149 -0
  91. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_handPose.py +136 -0
  92. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_headBodyPose.py +145 -0
  93. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_ikSolveError.py +171 -0
  94. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_ikSolveParam.py +140 -0
  95. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_imuData.py +165 -0
  96. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointBezierTrajectory.py +201 -0
  97. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointCmd.py +390 -0
  98. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointData.py +205 -0
  99. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_kuavoModeSchedule.py +224 -0
  100. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_lejuClawCommand.py +320 -0
  101. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_lejuClawState.py +341 -0
  102. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_motorParam.py +122 -0
  103. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_picoPoseInfo.py +143 -0
  104. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_picoPoseInfoList.py +220 -0
  105. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_planArmState.py +120 -0
  106. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_qv.py +121 -0
  107. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotArmQVVD.py +177 -0
  108. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotBodyMatrices.py +332 -0
  109. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotHandPosition.py +225 -0
  110. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotHeadMotionData.py +128 -0
  111. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotState.py +222 -0
  112. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_sensorsData.py +655 -0
  113. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_switchGaitByName.py +200 -0
  114. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_tagDataArray.py +216 -0
  115. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_touchSensorStatus.py +162 -0
  116. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPose.py +273 -0
  117. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmd.py +316 -0
  118. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmdFree.py +338 -0
  119. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseFree.py +299 -0
  120. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_yoloDetection.py +251 -0
  121. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_yoloOutputData.py +168 -0
  122. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_CreatePath.py +581 -0
  123. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_ExecuteArmAction.py +281 -0
  124. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetAllMaps.py +241 -0
  125. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetCurrentMap.py +225 -0
  126. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetTargetPartPoseInCamera.py +298 -0
  127. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_InitialPoseWithTaskPoint.py +281 -0
  128. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_LoadMap.py +281 -0
  129. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_NavigateToTaskPoint.py +281 -0
  130. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_RepublishTFs.py +373 -0
  131. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetInitialPose.py +394 -0
  132. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetJoyTopic.py +282 -0
  133. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetLEDMode.py +468 -0
  134. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetLEDMode_free.py +289 -0
  135. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SpeechSynthesis.py +270 -0
  136. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_TaskPointOperation.py +536 -0
  137. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/__init__.py +43 -0
  138. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_adjustZeroPoint.py +277 -0
  139. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeArmCtrlMode.py +275 -0
  140. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeArmCtrlModeKuavo.py +236 -0
  141. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeMotorParam.py +299 -0
  142. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeTorsoCtrlMode.py +274 -0
  143. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_controlLejuClaw.py +408 -0
  144. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_enableHandTouchSensor.py +304 -0
  145. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_fkSrv.py +395 -0
  146. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_footPose6DTargetTrajectoriesSrv.py +426 -0
  147. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_footPoseTargetTrajectoriesSrv.py +409 -0
  148. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureExecute.py +339 -0
  149. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureExecuteState.py +257 -0
  150. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureList.py +418 -0
  151. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getCurrentGaitName.py +253 -0
  152. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getMotorParam.py +299 -0
  153. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getMotorZeroPoints.py +286 -0
  154. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_handForceLevel.py +330 -0
  155. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_jointMoveTo.py +302 -0
  156. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryBezierCurve.py +422 -0
  157. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryCubicSpline.py +490 -0
  158. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_playmusic.py +268 -0
  159. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setHwIntialState.py +304 -0
  160. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setMmCtrlFrame.py +273 -0
  161. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setMotorEncoderRoundService.py +283 -0
  162. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setTagId.py +275 -0
  163. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_singleStepControl.py +444 -0
  164. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_twoArmHandPoseCmdFreeSrv.py +716 -0
  165. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_twoArmHandPoseCmdSrv.py +664 -0
  166. kuavo_humanoid_sdk/msg/motion_capture_ik/__init__.py +7 -0
  167. kuavo_humanoid_sdk/msg/ocs2_msgs/__init__.py +7 -0
  168. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/__init__.py +12 -0
  169. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_constraint.py +142 -0
  170. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_controller_data.py +121 -0
  171. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_lagrangian_metrics.py +148 -0
  172. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mode_schedule.py +150 -0
  173. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_flattened_controller.py +666 -0
  174. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_input.py +122 -0
  175. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_observation.py +209 -0
  176. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_performance_indices.py +140 -0
  177. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_solver_data.py +886 -0
  178. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_state.py +122 -0
  179. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_target_trajectories.py +239 -0
  180. kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_multiplier.py +148 -0
  181. kuavo_humanoid_sdk/msg/ocs2_msgs/srv/__init__.py +1 -0
  182. kuavo_humanoid_sdk/msg/ocs2_msgs/srv/_reset.py +376 -0
  183. kuavo_humanoid_sdk-1.2.2b3208.dist-info/METADATA +297 -0
  184. kuavo_humanoid_sdk-1.2.2b3208.dist-info/RECORD +186 -0
  185. kuavo_humanoid_sdk-1.2.2b3208.dist-info/WHEEL +6 -0
  186. kuavo_humanoid_sdk-1.2.2b3208.dist-info/top_level.txt +1 -0
@@ -0,0 +1,1607 @@
1
+ #!/usr/bin/env python3
2
+ # coding: utf-8
3
+ import rospy
4
+ import numpy as np
5
+ from typing import List, Tuple, Optional, Union
6
+ from scipy.interpolate import PchipInterpolator
7
+ from kuavo_msgs.msg import footPose, footPoseTargetTrajectories, footPoses
8
+ from std_srvs.srv import SetBool, SetBoolRequest
9
+
10
+
11
+ # Constants for magic numbers
12
+ class StairClimbingConstants:
13
+ DEFAULT_DT = 1.0 # 上下楼梯的步态周期 (aligned with continuousStairClimber-roban.py)
14
+ DEFAULT_SS_TIME = 0.6 # 上下楼梯的支撑迈步时间 (aligned with continuousStairClimber-roban.py)
15
+ DEFAULT_FOOT_WIDTH = 0.108535 # 脚宽度 (aligned with continuousStairClimber-roban.py)
16
+ DEFAULT_STEP_HEIGHT = 0.08 # 台阶高度 (aligned with continuousStairClimber-roban.py)
17
+ DEFAULT_STEP_LENGTH = 0.25 # 上楼梯的台阶长度 (aligned with continuousStairClimber-roban.py)
18
+ DEFAULT_MAX_STEP_X = 0.28 # Default max step in X direction
19
+ DEFAULT_MAX_STEP_Y = 0.15 # Default max step in Y direction
20
+ DEFAULT_MAX_STEP_YAW = 30.0 # Default max yaw step (degrees)
21
+ DEFAULT_SWING_HEIGHT = 0.10 # Default swing phase height
22
+ DEFAULT_SWING_POINTS = 7 # Default swing trajectory points
23
+ TORSO_HEIGHT_OFFSET = -0.02 # 躯干高度偏移 (aligned with continuousStairClimber-roban.py)
24
+ WALK_DT = 0.6 # 前进/转弯的步态周期 (aligned with continuousStairClimber-roban.py)
25
+ WALK_SS_TIME = 0.4 # 前进/转弯的支撑迈步时间 (aligned with continuousStairClimber-roban.py)
26
+ DOWN_STAIRS_SS_TIME = 0.35 # Down stairs single support time
27
+
28
+
29
+ def set_pitch_limit(enable: bool) -> bool:
30
+ """
31
+ Set base pitch angle limit
32
+ Args:
33
+ enable: bool, True to enable limit, False to disable limit
34
+ Returns:
35
+ bool: Whether the operation was successful
36
+ """
37
+ print(f"call set_pitch_limit:{enable}")
38
+ rospy.wait_for_service("/humanoid/mpc/enable_base_pitch_limit")
39
+ try:
40
+ set_pitch_limit_service = rospy.ServiceProxy(
41
+ "/humanoid/mpc/enable_base_pitch_limit", SetBool
42
+ )
43
+ req = SetBoolRequest()
44
+ req.data = enable
45
+ resp = set_pitch_limit_service(req)
46
+ if resp.success:
47
+ rospy.loginfo(
48
+ f"Successfully {'enabled' if enable else 'disabled'} pitch limit"
49
+ )
50
+ else:
51
+ rospy.logwarn(f"Failed to {'enable' if enable else 'disable'} pitch limit")
52
+ return resp.success
53
+ except rospy.ServiceException as e:
54
+ rospy.logerr(f"Service call failed: {e}")
55
+ return False
56
+
57
+
58
+ def publish_foot_pose_traj(
59
+ time_traj: List[float],
60
+ foot_idx_traj: List[int],
61
+ foot_traj: List[List[float]],
62
+ torso_traj: List[List[float]],
63
+ swing_trajectories: Optional[List] = None,
64
+ verbose: bool = True,
65
+ ) -> None:
66
+ """
67
+ Publish foot pose trajectory
68
+ Args:
69
+ time_traj: Time trajectory
70
+ foot_idx_traj: Foot index trajectory
71
+ foot_traj: Foot trajectory
72
+ torso_traj: Torso trajectory
73
+ swing_trajectories: Swing phase trajectories (optional)
74
+ verbose: Whether to enable detailed logging
75
+ """
76
+ num_points = len(time_traj)
77
+
78
+ if verbose:
79
+ rospy.loginfo(f"[ClimbStair] Publishing trajectory with {num_points} points")
80
+ rospy.logdebug(f"[ClimbStair] Time trajectory: {time_traj}")
81
+ rospy.logdebug(f"[ClimbStair] Foot index trajectory: {foot_idx_traj}")
82
+
83
+ # Log first few trajectory points for debugging
84
+ log_count = min(3, num_points) # Reduced from 5 to 3
85
+ for i in range(log_count):
86
+ rospy.logdebug(
87
+ f"[ClimbStair] Point {i}: time={time_traj[i]:.3f}, foot_idx={foot_idx_traj[i]}, "
88
+ f"foot=[{foot_traj[i][0]:.3f}, {foot_traj[i][1]:.3f}, {foot_traj[i][2]:.3f}, {foot_traj[i][3]:.3f}], "
89
+ f"torso=[{torso_traj[i][0]:.3f}, {torso_traj[i][1]:.3f}, {torso_traj[i][2]:.3f}, {torso_traj[i][3]:.3f}]"
90
+ )
91
+
92
+ if num_points > log_count:
93
+ rospy.logdebug(
94
+ f"[ClimbStair] ... (showing first {log_count} of {num_points} points)"
95
+ )
96
+
97
+ # Create publisher with appropriate queue size
98
+ pub = rospy.Publisher(
99
+ "/humanoid_mpc_foot_pose_target_trajectories",
100
+ footPoseTargetTrajectories,
101
+ queue_size=1,
102
+ latch=True,
103
+ )
104
+ rospy.sleep(0.5) # Reduced sleep time
105
+
106
+ # Build message
107
+ msg = footPoseTargetTrajectories()
108
+ msg.timeTrajectory = time_traj
109
+ msg.footIndexTrajectory = foot_idx_traj
110
+ msg.footPoseTrajectory = []
111
+ msg.additionalFootPoseTrajectory = []
112
+
113
+ # Pre-allocate lists for better performance
114
+ msg.footPoseTrajectory = [footPose() for _ in range(num_points)]
115
+ msg.additionalFootPoseTrajectory = [footPoses() for _ in range(num_points)]
116
+
117
+ for i in range(num_points):
118
+ msg.footPoseTrajectory[i].footPose = foot_traj[i]
119
+ msg.footPoseTrajectory[i].torsoPose = torso_traj[i]
120
+
121
+ # Handle swing trajectories efficiently
122
+ if (
123
+ swing_trajectories is not None
124
+ and i < len(swing_trajectories)
125
+ and swing_trajectories[i] is not None
126
+ ):
127
+ msg.additionalFootPoseTrajectory[i] = swing_trajectories[i]
128
+ if verbose:
129
+ swing_points = (
130
+ len(swing_trajectories[i].data)
131
+ if hasattr(swing_trajectories[i], "data")
132
+ else 0
133
+ )
134
+ rospy.logdebug(
135
+ f"[ClimbStair] Point {i}: Adding swing trajectory with {swing_points} points"
136
+ )
137
+
138
+ if verbose:
139
+ rospy.loginfo(
140
+ "[ClimbStair] Publishing to /humanoid_mpc_foot_pose_target_trajectories"
141
+ )
142
+
143
+ pub.publish(msg)
144
+
145
+ if verbose:
146
+ rospy.loginfo("[ClimbStair] Trajectory published successfully")
147
+
148
+ rospy.sleep(1.0) # Reduced sleep time
149
+
150
+
151
+ class KuavoRobotClimbStair:
152
+ """Kuavo robot stair climbing implementation with SDK interface"""
153
+
154
+ def __init__(
155
+ self,
156
+ stand_height: float = 0.0,
157
+ verbose_logging: bool = True,
158
+ ):
159
+ """
160
+ Initialize the stair climbing system.
161
+
162
+ Args:
163
+ stand_height: Standing height offset
164
+ verbose_logging: Whether to enable verbose logging
165
+ """
166
+
167
+ # Use constants for parameters (aligned with continuousStairClimber-roban.py)
168
+ self.dt = StairClimbingConstants.DEFAULT_DT
169
+ self.ss_time = StairClimbingConstants.DEFAULT_SS_TIME
170
+ self.foot_width = StairClimbingConstants.DEFAULT_FOOT_WIDTH
171
+ self.step_height = StairClimbingConstants.DEFAULT_STEP_HEIGHT
172
+ self.step_length = StairClimbingConstants.DEFAULT_STEP_LENGTH
173
+ self.down_step_length = 0.25 # 下楼梯的迈步距离(独立参数)
174
+ self.up_stairs_double_step_offset = 0.00
175
+ self.down_stairs_double_step_offset = -0.00
176
+ self.temp_x_offset = 0.002 # 临时x方向偏置,每步叠加
177
+ self.walk_dt = StairClimbingConstants.WALK_DT # 前进/转弯的步态周期
178
+ self.walk_ss_time = StairClimbingConstants.WALK_SS_TIME # 前进/转弯的支撑迈步时间
179
+ self.total_step = 0
180
+ self.is_left_foot = False # 当前是否为左脚 (aligned with continuousStairClimber-roban.py)
181
+
182
+ # Global variables from original script
183
+ self.PLOT = False
184
+ self.STAND_HEIGHT = stand_height
185
+ self.verbose_logging = verbose_logging
186
+
187
+ # Trajectory accumulation for continuous planning
188
+ self._clear_trajectory_data()
189
+
190
+ # Pre-compute commonly used values
191
+ self._rotation_matrices_cache = {}
192
+
193
+ rospy.loginfo(
194
+ "[ClimbStair] Initialized with stand_height=%.3f, verbose=%s",
195
+ stand_height,
196
+ verbose_logging,
197
+ )
198
+
199
+ def set_stair_parameters(
200
+ self,
201
+ step_height: float = None,
202
+ step_length: float = None,
203
+ foot_width: float = None,
204
+ stand_height: float = None,
205
+ dt: float = None,
206
+ ss_time: float = None,
207
+ ) -> bool:
208
+ """
209
+ Set stair climbing parameters.
210
+
211
+ Args:
212
+ step_height: Step height (m), must be > 0
213
+ step_length: Step length (m), must be > 0
214
+ foot_width: Foot width (m), must be > 0
215
+ stand_height: Standing height offset (m)
216
+ dt: Gait cycle time (s), must be > 0
217
+ ss_time: Single support time ratio, must be between 0 and 1
218
+
219
+ Returns:
220
+ bool: Whether parameter setting was successful
221
+ """
222
+ # Use current values as defaults if None provided
223
+ step_height = step_height if step_height is not None else self.step_height
224
+ step_length = step_length if step_length is not None else self.step_length
225
+ foot_width = foot_width if foot_width is not None else self.foot_width
226
+ stand_height = stand_height if stand_height is not None else self.STAND_HEIGHT
227
+ dt = dt if dt is not None else self.dt
228
+ ss_time = ss_time if ss_time is not None else self.ss_time
229
+
230
+ # Input validation
231
+ if step_height <= 0 or step_length <= 0 or foot_width <= 0:
232
+ rospy.logerr(
233
+ "[ClimbStair] Invalid parameters: step_height, step_length, foot_width must be positive"
234
+ )
235
+ return False
236
+
237
+ if dt <= 0:
238
+ rospy.logerr("[ClimbStair] Invalid dt: must be positive")
239
+ return False
240
+
241
+ if not (0 < ss_time < 1):
242
+ rospy.logerr("[ClimbStair] Invalid ss_time: must be between 0 and 1")
243
+ return False
244
+
245
+ if step_height > 0.5: # Reasonable safety limit
246
+ rospy.logwarn(
247
+ "[ClimbStair] Step height %.3f seems very high, consider checking",
248
+ step_height,
249
+ )
250
+
251
+ if step_length > 1.0: # Reasonable safety limit
252
+ rospy.logwarn(
253
+ "[ClimbStair] Step length %.3f seems very long, consider checking",
254
+ step_length,
255
+ )
256
+
257
+ # Clear rotation matrix cache as foot_width affects calculations
258
+ self._rotation_matrices_cache.clear()
259
+
260
+ self.step_height = step_height
261
+ self.step_length = step_length
262
+ self.foot_width = foot_width
263
+ self.STAND_HEIGHT = stand_height
264
+ self.dt = dt
265
+ self.ss_time = ss_time
266
+
267
+ if self.verbose_logging:
268
+ rospy.loginfo(
269
+ f"[ClimbStair] Parameters updated - step_height: {step_height:.3f}, "
270
+ f"step_length: {step_length:.3f}, foot_width: {foot_width:.3f}, "
271
+ f"stand_height: {stand_height:.3f}, dt: {dt:.3f}, ss_time: {ss_time:.3f}"
272
+ )
273
+ return True
274
+
275
+ def set_gait_parameters(self, dt: float = None, ss_time: float = None) -> bool:
276
+ """
277
+ Set gait timing parameters.
278
+
279
+ Args:
280
+ dt: Gait cycle time (s), must be > 0. Default is 0.6s for stair climbing
281
+ ss_time: Single support time ratio, must be between 0 and 1. Default is 0.5
282
+
283
+ Returns:
284
+ bool: Whether parameter setting was successful
285
+ """
286
+ # Use current values as defaults if None provided
287
+ dt = dt if dt is not None else self.dt
288
+ ss_time = ss_time if ss_time is not None else self.ss_time
289
+
290
+ # Input validation
291
+ if dt <= 0:
292
+ rospy.logerr("[ClimbStair] Invalid dt: must be positive")
293
+ return False
294
+
295
+ if not (0 < ss_time < 1):
296
+ rospy.logerr("[ClimbStair] Invalid ss_time: must be between 0 and 1")
297
+ return False
298
+
299
+ # Safety warnings for extreme values
300
+ if dt < 0.2:
301
+ rospy.logwarn(
302
+ "[ClimbStair] Very fast gait cycle (dt=%.3f), may cause instability", dt
303
+ )
304
+ elif dt > 2.0:
305
+ rospy.logwarn(
306
+ "[ClimbStair] Very slow gait cycle (dt=%.3f), consider checking", dt
307
+ )
308
+
309
+ if ss_time < 0.3:
310
+ rospy.logwarn(
311
+ "[ClimbStair] Very short single support time (%.3f), may cause instability",
312
+ ss_time,
313
+ )
314
+ elif ss_time > 0.8:
315
+ rospy.logwarn(
316
+ "[ClimbStair] Very long single support time (%.3f), may cause instability",
317
+ ss_time,
318
+ )
319
+
320
+ self.dt = dt
321
+ self.ss_time = ss_time
322
+
323
+ if self.verbose_logging:
324
+ rospy.loginfo(
325
+ f"[ClimbStair] Gait parameters updated - dt: {dt:.3f}s, ss_time: {ss_time:.3f}"
326
+ )
327
+ return True
328
+
329
+ def get_parameters(self) -> dict:
330
+ """
331
+ Get current stair climbing and gait parameters.
332
+
333
+ Returns:
334
+ dict: Dictionary containing all current parameters
335
+ """
336
+ return {
337
+ "step_height": self.step_height,
338
+ "step_length": self.step_length,
339
+ "foot_width": self.foot_width,
340
+ "stand_height": self.STAND_HEIGHT,
341
+ "dt": self.dt,
342
+ "ss_time": self.ss_time,
343
+ "down_step_length": self.down_step_length,
344
+ "up_stairs_double_step_offset": self.up_stairs_double_step_offset,
345
+ "down_stairs_double_step_offset": self.down_stairs_double_step_offset,
346
+ "temp_x_offset": self.temp_x_offset,
347
+ "walk_dt": self.walk_dt,
348
+ "walk_ss_time": self.walk_ss_time,
349
+ }
350
+
351
+ def _clear_trajectory_data(self) -> None:
352
+ """Internal method to clear trajectory data."""
353
+ self.time_traj = []
354
+ self.foot_idx_traj = []
355
+ self.foot_traj = []
356
+ self.torso_traj = []
357
+ self.swing_trajectories = []
358
+
359
+ def clear_trajectory(self) -> None:
360
+ """Clear all accumulated trajectories."""
361
+ self._clear_trajectory_data()
362
+ if self.verbose_logging:
363
+ rospy.loginfo("[ClimbStair] Trajectory cleared")
364
+
365
+ def _get_rotation_matrix(self, yaw: float) -> np.ndarray:
366
+ """Get cached rotation matrix for yaw angle."""
367
+ # Cache rotation matrices to avoid repeated computation
368
+ yaw_key = round(yaw, 6) # Round to avoid floating point precision issues
369
+ if yaw_key not in self._rotation_matrices_cache:
370
+ cos_yaw, sin_yaw = np.cos(yaw), np.sin(yaw)
371
+ self._rotation_matrices_cache[yaw_key] = np.array(
372
+ [[cos_yaw, -sin_yaw, 0], [sin_yaw, cos_yaw, 0], [0, 0, 1]]
373
+ )
374
+ return self._rotation_matrices_cache[yaw_key]
375
+
376
+ def _convert_arrays_to_lists(self, torso_traj: List) -> None:
377
+ """Convert numpy arrays to lists for ROS message compatibility."""
378
+ for i in range(len(torso_traj)):
379
+ if isinstance(torso_traj[i], np.ndarray):
380
+ torso_traj[i] = torso_traj[i].tolist()
381
+
382
+ def execute_trajectory(self) -> bool:
383
+ """Execute the complete accumulated trajectory."""
384
+ if len(self.time_traj) == 0:
385
+ if self.verbose_logging:
386
+ rospy.logwarn("[ClimbStair] No trajectory to publish")
387
+ return False
388
+
389
+ # Convert numpy arrays to lists for ROS message compatibility
390
+ self._convert_arrays_to_lists(self.torso_traj)
391
+
392
+ if self.verbose_logging:
393
+ rospy.loginfo(
394
+ f"[ClimbStair] Publishing complete trajectory with {len(self.time_traj)} points"
395
+ )
396
+
397
+ publish_foot_pose_traj(
398
+ self.time_traj,
399
+ self.foot_idx_traj,
400
+ self.foot_traj,
401
+ self.torso_traj,
402
+ self.swing_trajectories,
403
+ self.verbose_logging,
404
+ )
405
+ return True
406
+
407
+ def generate_steps(
408
+ self,
409
+ torso_pos: Union[np.ndarray, List[float]],
410
+ torso_yaw: float,
411
+ foot_height: float = 0,
412
+ ) -> Tuple[np.ndarray, np.ndarray]:
413
+ """
414
+ Calculate foot placement based on torso position
415
+
416
+ Args:
417
+ torso_pos: Torso position [x, y, z]
418
+ torso_yaw: Torso yaw angle
419
+ foot_height: Foot height offset
420
+
421
+ Returns:
422
+ Tuple of left and right foot positions
423
+ """
424
+ torso_pos = np.asarray(torso_pos)
425
+
426
+ # Use cached rotation matrix for better performance
427
+ R_z = self._get_rotation_matrix(torso_yaw)
428
+
429
+ # Pre-compute foot biases
430
+ foot_height_offset = -torso_pos[2] + foot_height
431
+ l_foot_bias = np.array([0, self.foot_width, foot_height_offset])
432
+ r_foot_bias = np.array([0, -self.foot_width, foot_height_offset])
433
+
434
+ # Compute foot positions
435
+ l_foot = torso_pos + R_z.dot(l_foot_bias)
436
+ r_foot = torso_pos + R_z.dot(r_foot_bias)
437
+
438
+ return l_foot, r_foot
439
+
440
+ def plan_move_to(
441
+ self,
442
+ dx=0.2,
443
+ dy=0.0,
444
+ dyaw=0.0,
445
+ time_traj=None,
446
+ foot_idx_traj=None,
447
+ foot_traj=None,
448
+ torso_traj=None,
449
+ swing_trajectories=None,
450
+ max_step_x=0.28,
451
+ max_step_y=0.15,
452
+ max_step_yaw=30.0,
453
+ ):
454
+ """
455
+ Plan trajectory to move to target position
456
+ """
457
+ if time_traj is None:
458
+ time_traj = []
459
+ if foot_idx_traj is None:
460
+ foot_idx_traj = []
461
+ if foot_traj is None:
462
+ foot_traj = []
463
+ if torso_traj is None:
464
+ torso_traj = []
465
+ if swing_trajectories is None:
466
+ swing_trajectories = []
467
+ current_height = self.STAND_HEIGHT
468
+ # Get the last trajectory point as starting position
469
+ if len(torso_traj) > 0:
470
+ current_torso_pos = np.array(torso_traj[-1])
471
+ current_foot_pos = np.array(foot_traj[-1][0:3])
472
+ current_yaw = current_torso_pos[3]
473
+ current_height = current_foot_pos[2]
474
+ R_z = np.array(
475
+ [
476
+ [np.cos(current_yaw), -np.sin(current_yaw), 0],
477
+ [np.sin(current_yaw), np.cos(current_yaw), 0],
478
+ [0, 0, 1],
479
+ ]
480
+ )
481
+ dx, dy, _ = R_z.dot(np.array([dx, dy, 0]))
482
+ print("new dx, dy, dyaw", dx, dy, dyaw)
483
+
484
+ else:
485
+ current_torso_pos = np.array([0.0, 0.0, 0.0, 0.0])
486
+ current_foot_pos = np.array([0.0, 0.0, self.STAND_HEIGHT])
487
+ current_yaw = 0.0
488
+
489
+ # Calculate required number of steps
490
+ num_steps_x = max(1, int(np.ceil(abs(dx) / max_step_x)))
491
+ num_steps_y = max(1, int(np.ceil(abs(dy) / max_step_y)))
492
+ num_steps_yaw = max(1, int(np.ceil(abs(dyaw) / max_step_yaw)))
493
+ num_steps = max(num_steps_x, num_steps_y, num_steps_yaw)
494
+
495
+ # Calculate actual step size
496
+ actual_step_x = dx / num_steps
497
+ actual_step_y = dy / num_steps
498
+
499
+ # Record initial yaw angle for target calculation (aligned with roban script)
500
+ initial_yaw = current_torso_pos[3]
501
+ target_yaw = initial_yaw + np.radians(dyaw)
502
+
503
+ # is_left_foot = ((self.total_step - 1) % 2 == 0 or dyaw > 0)
504
+ if dyaw > 0:
505
+ self.is_left_foot = True
506
+ # Record starting trajectory length (for debugging)
507
+ # start_traj_len = len(foot_traj) # Currently unused
508
+ num_steps += 1 # First and last steps are half steps
509
+ # 使用类变量中的时间参数 (aligned with continuousStairClimber-roban.py)
510
+ walk_dt = self.walk_dt if hasattr(self, 'walk_dt') else StairClimbingConstants.WALK_DT
511
+ walk_ss_time = self.walk_ss_time if hasattr(self, 'walk_ss_time') else StairClimbingConstants.WALK_SS_TIME
512
+
513
+ for i in range(num_steps):
514
+ self.total_step += 1
515
+ time_traj.append((time_traj[-1] if len(time_traj) > 0 else 0) + walk_dt)
516
+
517
+ # Alternate left and right feet
518
+ self.is_left_foot = not self.is_left_foot
519
+ foot_idx_traj.append(0 if self.is_left_foot else 1)
520
+
521
+ # Calculate current step target yaw angle (linear interpolation, aligned with roban script)
522
+ if abs(dyaw) > 0.1: # Only update yaw angle when significant turning is needed
523
+ progress = (i + 1) / num_steps
524
+ current_torso_yaw = initial_yaw + progress * np.radians(dyaw)
525
+ else:
526
+ current_torso_yaw = initial_yaw # Keep yaw angle unchanged for straight walking
527
+
528
+ # Update torso position
529
+ if i == 0:
530
+ current_torso_pos[0] += actual_step_x / 2
531
+ current_torso_pos[1] += actual_step_y / 2
532
+ current_torso_pos[3] = current_torso_yaw
533
+ # Calculate foot placement offset based on current yaw angle
534
+ desire_torso_pos = [
535
+ current_torso_pos[0] + actual_step_x / 2,
536
+ current_torso_pos[1] + actual_step_y / 2,
537
+ current_torso_pos[2],
538
+ ]
539
+ lf_foot, rf_foot = self.generate_steps(
540
+ desire_torso_pos, current_torso_yaw, current_height
541
+ )
542
+ current_foot_pos = lf_foot if self.is_left_foot else rf_foot
543
+ # elif i == num_steps - 1 or (abs(dyaw)>0 and i == num_steps - 2):
544
+ elif i == num_steps - 1:
545
+ current_torso_pos[0] += actual_step_x / 2
546
+ current_torso_pos[1] += actual_step_y / 2
547
+ current_torso_pos[3] = target_yaw # Last step ensures reaching target yaw angle
548
+ # Calculate foot placement offset based on current yaw angle
549
+ lf_foot, rf_foot = self.generate_steps(
550
+ current_torso_pos[:3], current_torso_pos[3], current_height
551
+ )
552
+ current_foot_pos = lf_foot if self.is_left_foot else rf_foot
553
+ else:
554
+ current_torso_pos[0] += actual_step_x
555
+ current_torso_pos[1] += actual_step_y
556
+ current_torso_pos[3] = current_torso_yaw
557
+ # Calculate foot placement offset based on current yaw angle
558
+ desire_torso_pos = [
559
+ current_torso_pos[0] + actual_step_x / 2,
560
+ current_torso_pos[1] + actual_step_y / 2,
561
+ current_torso_pos[2],
562
+ ]
563
+ lf_foot, rf_foot = self.generate_steps(
564
+ desire_torso_pos, current_torso_yaw, current_height
565
+ )
566
+ current_foot_pos = lf_foot if self.is_left_foot else rf_foot
567
+
568
+ # 叠加临时x方向偏置(每步都叠加,参考continuousStairClimber-roban.py)
569
+ current_torso_pos[0] += self.temp_x_offset * (i + 1)
570
+
571
+ # Add trajectory point
572
+ foot_traj.append(
573
+ [
574
+ current_foot_pos[0],
575
+ current_foot_pos[1],
576
+ current_foot_pos[2],
577
+ current_torso_pos[3],
578
+ ]
579
+ )
580
+ torso_traj.append(current_torso_pos.copy())
581
+ swing_trajectories.append(footPoses())
582
+
583
+ time_traj.append(time_traj[-1] + walk_ss_time)
584
+ foot_idx_traj.append(2)
585
+ foot_traj.append(foot_traj[-1].copy())
586
+ torso_traj.append(torso_traj[-1].copy())
587
+ swing_trajectories.append(footPoses())
588
+
589
+ return time_traj, foot_idx_traj, foot_traj, torso_traj, swing_trajectories
590
+
591
+ def plan_up_stairs(
592
+ self,
593
+ num_steps=5,
594
+ time_traj=None,
595
+ foot_idx_traj=None,
596
+ foot_traj=None,
597
+ torso_traj=None,
598
+ swing_trajectories=None,
599
+ stair_offset=0.0,
600
+ ):
601
+ """Plan up stairs trajectory implementation"""
602
+ if time_traj is None:
603
+ time_traj = []
604
+ if foot_idx_traj is None:
605
+ foot_idx_traj = []
606
+ if foot_traj is None:
607
+ foot_traj = []
608
+ if torso_traj is None:
609
+ torso_traj = []
610
+ if swing_trajectories is None:
611
+ swing_trajectories = []
612
+ torso_yaw = 0.0
613
+
614
+ # Get the last trajectory point as starting position
615
+ start_foot_pos_x = 0.0
616
+ start_foot_pos_z = self.STAND_HEIGHT
617
+ if len(torso_traj) > 0:
618
+ current_torso_pos = np.array(torso_traj[-1][0:3])
619
+ current_foot_pos = np.array(foot_traj[-1][0:3])
620
+ start_foot_pos_x = current_foot_pos[0]
621
+ torso_yaw = torso_traj[-1][3]
622
+ start_foot_pos_z = current_foot_pos[2]
623
+ else:
624
+ current_torso_pos = np.array([0.0, 0.0, 0.0])
625
+ current_foot_pos = np.array([0.0, 0.0, self.STAND_HEIGHT])
626
+
627
+ # Initial position
628
+ torso_height_offset = -0.02 # 躯干高度偏移 (aligned with continuousStairClimber-roban.py)
629
+ current_torso_pos[2] += torso_height_offset
630
+ # 基础offset数组,后续会加上stair_offset (aligned with continuousStairClimber-roban.py)
631
+ base_offset_x = [0.00, self.up_stairs_double_step_offset, self.up_stairs_double_step_offset, self.up_stairs_double_step_offset, 0.0]
632
+ # 所有offset都加上离楼梯的偏置距离
633
+ offset_x = [offset + stair_offset for offset in base_offset_x]
634
+
635
+ # Record previous left and right foot positions
636
+ prev_left_foot = [start_foot_pos_x, self.foot_width, start_foot_pos_z, torso_yaw]
637
+ prev_right_foot = [start_foot_pos_x, -self.foot_width, start_foot_pos_z, torso_yaw]
638
+ initial_index = len(foot_traj)
639
+ # Generate footsteps for each step
640
+ for step in range(num_steps):
641
+ # Update time
642
+ self.total_step += 1
643
+ time_traj.append((time_traj[-1] if len(time_traj) > 0 else 0) + self.dt)
644
+
645
+ # Alternate left and right feet
646
+ self.is_left_foot = not self.is_left_foot
647
+ foot_idx_traj.append(0 if self.is_left_foot else 1)
648
+
649
+ # Calculate torso position (aligned with continuousStairClimber-roban.py)
650
+ if step == 0:
651
+ current_foot_pos[0] = current_torso_pos[0] + self.step_length # 脚掌相对躯干前移
652
+ current_foot_pos[1] = current_torso_pos[1] + self.foot_width if self.is_left_foot else -self.foot_width # 左右偏移
653
+ current_foot_pos[2] = start_foot_pos_z + self.step_height + self.STAND_HEIGHT # 脚掌高度
654
+ current_torso_pos[0] += self.step_length/2
655
+ current_torso_pos[2] += self.step_height/2
656
+
657
+ elif step == num_steps - 1: # 最后一步
658
+ current_torso_pos[0] = current_foot_pos[0] # 最后一步躯干x在双脚上方
659
+ current_foot_pos[1] = current_torso_pos[1] + self.foot_width if self.is_left_foot else -self.foot_width # 左右偏移
660
+ current_torso_pos[2] += self.step_height/2
661
+ else:
662
+ current_torso_pos[0] += self.step_length # 向前移动
663
+ current_torso_pos[2] += self.step_height # 向上移动
664
+
665
+ # 计算落脚点位置
666
+ current_foot_pos[0] = current_torso_pos[0] + self.step_length/2 # 脚掌相对躯干前移
667
+ current_foot_pos[1] = current_torso_pos[1] + self.foot_width if self.is_left_foot else -self.foot_width # 左右偏移
668
+ current_foot_pos[2] += self.step_height
669
+
670
+ # 叠加临时x方向偏置(每步都叠加,参考continuousStairClimber-roban.py)
671
+ current_torso_pos[0] += self.temp_x_offset * (step + 1)
672
+
673
+ if step < len(offset_x) and not step == num_steps - 1: # 脚掌偏移
674
+ current_foot_pos[0] += offset_x[step]
675
+
676
+ # Record current foot position
677
+ current_foot = [*current_foot_pos, torso_yaw]
678
+
679
+ # Generate swing phase trajectory
680
+ if (
681
+ prev_left_foot is not None and prev_right_foot is not None
682
+ ): # Generate swing phase from second step onwards
683
+ prev_foot = prev_left_foot if self.is_left_foot else prev_right_foot
684
+ swing_traj = self.plan_swing_phase(
685
+ prev_foot,
686
+ current_foot,
687
+ swing_height=0.12,
688
+ is_first_step=(step == 0 or step == num_steps - 1),
689
+ )
690
+ swing_trajectories.append(swing_traj)
691
+ else:
692
+ swing_trajectories.append(None)
693
+
694
+ # Update previous foot position
695
+ if self.is_left_foot:
696
+ prev_left_foot = current_foot
697
+ else:
698
+ prev_right_foot = current_foot
699
+
700
+ # Add trajectory point
701
+ foot_traj.append(current_foot)
702
+ torso_traj.append([*current_torso_pos, torso_yaw])
703
+
704
+ last_torso_pose = torso_traj[-1].copy()
705
+ last_foot_pose = foot_traj[-1].copy()
706
+ # 添加支撑相 (aligned with continuousStairClimber-roban.py)
707
+ if step != num_steps - 1:
708
+ pass
709
+ time_traj.append(time_traj[-1] + self.ss_time)
710
+ foot_idx_traj.append(2)
711
+ foot_traj.append(foot_traj[-1].copy())
712
+ last_torso_pose[0] = last_foot_pose[0] - self.step_length*0.0
713
+ torso_traj.append(last_torso_pose)
714
+ swing_trajectories.append(footPoses())
715
+ else: # 最后一步站立恢复站直
716
+ time_traj.append(time_traj[-1] + self.ss_time)
717
+ foot_idx_traj.append(2)
718
+ foot_traj.append(foot_traj[-1].copy())
719
+ last_torso_pose[0] = last_foot_pose[0]
720
+ last_torso_pose[2] = last_foot_pose[2] - self.STAND_HEIGHT
721
+ torso_traj.append(last_torso_pose)
722
+ swing_trajectories.append(footPoses())
723
+
724
+ # Handle rotation offset
725
+ if initial_index > 0:
726
+ init_torso_pos = torso_traj[initial_index - 1]
727
+ # init_foot_pos = foot_traj[initial_index-1] # Currently unused
728
+ for i in range(initial_index, len(foot_traj)):
729
+ diff_yaw = torso_traj[i][3]
730
+ R_z = np.array(
731
+ [
732
+ [np.cos(diff_yaw), -np.sin(diff_yaw), 0],
733
+ [np.sin(diff_yaw), np.cos(diff_yaw), 0],
734
+ [0, 0, 1],
735
+ ]
736
+ )
737
+ d_torso_pos = torso_traj[i][0:3] - init_torso_pos[0:3]
738
+ torso_traj[i][0:2] = (R_z.dot(d_torso_pos) + init_torso_pos[0:3])[:2]
739
+
740
+ d_foot_pos = (
741
+ foot_traj[i][0:3] - init_torso_pos[0:3]
742
+ ) # 计算相对于躯干位置的偏移量
743
+ foot_traj[i][0:2] = (R_z.dot(d_foot_pos) + init_torso_pos[0:3])[:2]
744
+ if swing_trajectories[i] is not None: # 旋转腾空相规划
745
+ for j in range(len(swing_trajectories[i].data)):
746
+ d_foot_pos = (
747
+ swing_trajectories[i].data[j].footPose[0:3]
748
+ - init_torso_pos[0:3]
749
+ )
750
+ swing_trajectories[i].data[j].footPose[0:2] = (
751
+ R_z.dot(d_foot_pos) + init_torso_pos[0:3]
752
+ )[:2]
753
+
754
+ return time_traj, foot_idx_traj, foot_traj, torso_traj, swing_trajectories
755
+
756
+ def plan_down_stairs(
757
+ self,
758
+ num_steps=5,
759
+ time_traj=None,
760
+ foot_idx_traj=None,
761
+ foot_traj=None,
762
+ torso_traj=None,
763
+ swing_trajectories=None,
764
+ ):
765
+ """Plan down stairs trajectory implementation"""
766
+ if time_traj is None:
767
+ time_traj = []
768
+ if foot_idx_traj is None:
769
+ foot_idx_traj = []
770
+ if foot_traj is None:
771
+ foot_traj = []
772
+ if torso_traj is None:
773
+ torso_traj = []
774
+ if swing_trajectories is None:
775
+ swing_trajectories = []
776
+ self.dt = 0.6
777
+ self.step_length = 0.28
778
+ torso_yaw = 0.0
779
+ start_foot_pos_x = 0.0
780
+ start_foot_pos_z = self.STAND_HEIGHT
781
+
782
+ # Get the last trajectory point as starting position
783
+ if len(torso_traj) > 0:
784
+ current_torso_pos = np.array(torso_traj[-1][0:3])
785
+ current_foot_pos = np.array(foot_traj[-1][0:3])
786
+ start_foot_pos_x = current_foot_pos[0]
787
+ torso_yaw = torso_traj[-1][3]
788
+ start_foot_pos_z = current_foot_pos[2]
789
+
790
+ else:
791
+ current_torso_pos = np.array([0.0, 0.0, 0.0])
792
+ current_foot_pos = np.array([0.0, 0.0, self.STAND_HEIGHT])
793
+ start_foot_pos_x = 0.0
794
+ R_z = np.array(
795
+ [
796
+ [np.cos(torso_yaw), -np.sin(torso_yaw), 0],
797
+ [np.sin(torso_yaw), np.cos(torso_yaw), 0],
798
+ [0, 0, 1],
799
+ ]
800
+ )
801
+ # Initial position
802
+ torso_height_offset = -0.0 # 躯干高度偏移
803
+ current_torso_pos[2] += torso_height_offset
804
+ offset_x = [0.0, -0.0, -0.0, -0.0, -0.0]
805
+ # first_step_offset = self.step_length + 0.05
806
+
807
+ # Record previous left and right foot positions
808
+ prev_left_foot = [start_foot_pos_x, 0.1, start_foot_pos_z, torso_yaw]
809
+ prev_right_foot = [start_foot_pos_x, -0.1, start_foot_pos_z, torso_yaw]
810
+ if len(foot_traj) > 0:
811
+ if foot_idx_traj[-2] == 0: # 最后一步是左脚
812
+ prev_left_foot = foot_traj[-2]
813
+ prev_right_foot = foot_traj[-4] if len(foot_traj) > 3 else None
814
+ else: # 最后一步是右脚
815
+ prev_right_foot = foot_traj[-2]
816
+ prev_left_foot = foot_traj[-4] if len(foot_traj) > 3 else None
817
+ initial_index = len(foot_traj)
818
+ print("prev_left_foot: ", prev_left_foot)
819
+ print("prev_right_foot: ", prev_right_foot)
820
+ # 添加下蹲
821
+ if len(time_traj) > 0:
822
+ time_traj.append(time_traj[-1] + 1)
823
+ foot_idx_traj.append(2)
824
+ foot_traj.append(foot_traj[-1].copy())
825
+ torso_traj.append(torso_traj[-1].copy())
826
+ torso_traj[-1][2] = current_torso_pos[2]
827
+ swing_trajectories.append(None)
828
+ else:
829
+ time_traj.append(1)
830
+ foot_idx_traj.append(2)
831
+ foot_traj.append([0, 0, 0, 0])
832
+ torso_traj.append([0, 0, current_torso_pos[2], 0])
833
+ swing_trajectories.append(None)
834
+
835
+ first_step_offset = -0.01
836
+ # Generate footsteps for each step
837
+ for step in range(num_steps):
838
+ # Update time
839
+ self.total_step += 1
840
+ time_traj.append((time_traj[-1] if len(time_traj) > 0 else 0) + self.dt)
841
+
842
+ # Alternate left and right feet
843
+ self.is_left_foot = not self.is_left_foot
844
+ foot_idx_traj.append(0 if self.is_left_foot else 1)
845
+
846
+ # Calculate torso position
847
+ if step == 0:
848
+ # current_torso_pos[0] += self.step_length/2 + first_step_offset
849
+ current_foot_pos[0] = (
850
+ current_torso_pos[0] + self.step_length + first_step_offset
851
+ ) # 脚掌相对躯干前移
852
+ current_torso_pos[0] += self.step_length / 2 + first_step_offset
853
+ # current_torso_pos[0] = current_foot_pos[0] - 0.03 # 躯干落在前脚掌
854
+ current_foot_pos[1] = (
855
+ current_torso_pos[1] + self.foot_width
856
+ if self.is_left_foot
857
+ else -self.foot_width
858
+ ) # Left/right offset
859
+ current_foot_pos[2] -= self.step_height # 脚掌高度
860
+ current_torso_pos[2] -= self.step_height - 0.0 # 脚掌高度
861
+ elif step == num_steps - 1: # Last step
862
+ current_torso_pos[0] = current_foot_pos[
863
+ 0
864
+ ] # Last step: torso x above both feet
865
+ # current_foot_pos[0] = current_torso_pos[0] #
866
+ current_foot_pos[1] = (
867
+ current_torso_pos[1] + self.foot_width
868
+ if self.is_left_foot
869
+ else -self.foot_width
870
+ ) # Left/right offset
871
+ # current_torso_pos[2] += self.step_height # 脚掌高度
872
+ else:
873
+ current_torso_pos[0] += self.step_length # Move forward
874
+ current_torso_pos[2] -= self.step_height # 向下移动
875
+
876
+ # Calculate foot placement position
877
+ current_foot_pos[0] = (
878
+ current_torso_pos[0] + self.step_length / 2
879
+ ) # 脚掌相对躯干前移
880
+ current_foot_pos[1] = (
881
+ current_torso_pos[1] + self.foot_width
882
+ if self.is_left_foot
883
+ else -self.foot_width
884
+ ) # Left/right offset
885
+ current_foot_pos[2] -= self.step_height
886
+
887
+ if step < len(offset_x) and not step == num_steps - 1: # Foot offset
888
+ current_foot_pos[0] += offset_x[step]
889
+
890
+ # Record current foot position
891
+ current_foot = [*current_foot_pos, torso_yaw]
892
+
893
+ # Generate swing phase trajectory
894
+ if (
895
+ prev_left_foot is not None and prev_right_foot is not None
896
+ ): # Generate swing phase from second step onwards
897
+ prev_foot = prev_left_foot if self.is_left_foot else prev_right_foot
898
+ swing_traj = self.plan_swing_phase(
899
+ prev_foot,
900
+ current_foot,
901
+ swing_height=0.05,
902
+ down_stairs=True,
903
+ is_first_step=(step == 0 or step == num_steps - 1),
904
+ )
905
+ swing_trajectories.append(swing_traj)
906
+ else:
907
+ swing_trajectories.append(None)
908
+
909
+ # Update previous foot position
910
+ if self.is_left_foot:
911
+ prev_left_foot = current_foot
912
+ else:
913
+ prev_right_foot = current_foot
914
+
915
+ # Add trajectory point
916
+ # print("step: ", step, "foot: ", foot_idx_traj[-1])
917
+ # print("current_foot: ", current_foot)
918
+ # print("current_torso_pos", current_torso_pos)
919
+ foot_traj.append(current_foot)
920
+ torso_traj.append([*current_torso_pos, torso_yaw])
921
+
922
+ last_torso_pose = torso_traj[-1].copy()
923
+ last_foot_pose = foot_traj[-1].copy()
924
+ # add SS
925
+ self.ss_time = 0.4
926
+ if step != num_steps - 1:
927
+ time_traj.append(time_traj[-1] + self.ss_time)
928
+ foot_idx_traj.append(2)
929
+ foot_traj.append(foot_traj[-1].copy())
930
+ last_torso_pose[0] = last_foot_pose[0]
931
+ torso_traj.append(last_torso_pose)
932
+ swing_trajectories.append(footPoses())
933
+
934
+ else: # Last step: standing recovery to straight position
935
+ time_traj.append(time_traj[-1] + self.ss_time)
936
+ foot_idx_traj.append(2)
937
+ foot_traj.append(foot_traj[-1].copy())
938
+ last_torso_pose[0] = last_foot_pose[0]
939
+ last_torso_pose[2] = last_foot_pose[2] - self.STAND_HEIGHT
940
+ torso_traj.append(last_torso_pose)
941
+ swing_trajectories.append(footPoses())
942
+ # break
943
+
944
+ # Handle rotation offset
945
+ if initial_index > 0:
946
+ init_torso_pos = torso_traj[initial_index - 1]
947
+ # init_foot_pos = foot_traj[initial_index-1] # Currently unused
948
+ for i in range(initial_index, len(foot_traj)):
949
+ diff_yaw = torso_traj[i][3]
950
+ R_z = np.array(
951
+ [
952
+ [np.cos(diff_yaw), -np.sin(diff_yaw), 0],
953
+ [np.sin(diff_yaw), np.cos(diff_yaw), 0],
954
+ [0, 0, 1],
955
+ ]
956
+ )
957
+ d_torso_pos = torso_traj[i][0:3] - init_torso_pos[0:3]
958
+ torso_traj[i][0:2] = (R_z.dot(d_torso_pos) + init_torso_pos[0:3])[:2]
959
+
960
+ d_foot_pos = (
961
+ foot_traj[i][0:3] - init_torso_pos[0:3]
962
+ ) # 计算相对于躯干位置的偏移量
963
+ foot_traj[i][0:2] = (R_z.dot(d_foot_pos) + init_torso_pos[0:3])[:2]
964
+
965
+ if swing_trajectories[i] is not None: # 旋转腾空相规划
966
+ for j in range(len(swing_trajectories[i].data)):
967
+ d_foot_pos = (
968
+ swing_trajectories[i].data[j].footPose[0:3]
969
+ - init_torso_pos[0:3]
970
+ )
971
+ swing_trajectories[i].data[j].footPose[0:2] = (
972
+ R_z.dot(d_foot_pos) + init_torso_pos[0:3]
973
+ )[:2]
974
+ return time_traj, foot_idx_traj, foot_traj, torso_traj, swing_trajectories
975
+
976
+ def plan_swing_phase(
977
+ self,
978
+ prev_foot_pose,
979
+ next_foot_pose,
980
+ swing_height=0.10,
981
+ down_stairs=False,
982
+ is_first_step=False,
983
+ ):
984
+ """
985
+ 使用三角函数+五次多项式插值规划腾空相的轨迹
986
+ """
987
+ return self._trigonometric_quintic_interpolation(
988
+ prev_foot_pose=prev_foot_pose,
989
+ next_foot_pose=next_foot_pose,
990
+ swing_height=swing_height,
991
+ num_points=7,
992
+ is_first_step=is_first_step,
993
+ down_stairs=down_stairs,
994
+ )
995
+
996
+
997
+
998
+ def _trigonometric_quintic_interpolation(self, prev_foot_pose, next_foot_pose, swing_height,
999
+ num_points, is_first_step, down_stairs):
1000
+ """三角函数+五次多项式插值方法(Z方向使用三角函数,XY方向使用摆线)"""
1001
+ additionalFootPoseTrajectory = footPoses()
1002
+
1003
+ # 计算移动距离
1004
+ x_distance = next_foot_pose[0] - prev_foot_pose[0]
1005
+ y_distance = next_foot_pose[1] - prev_foot_pose[1]
1006
+ z_distance = next_foot_pose[2] - prev_foot_pose[2]
1007
+
1008
+ # 下楼梯时使用反向规划(先多项式再三角函数)
1009
+ if down_stairs:
1010
+ return self._trigonometric_quintic_interpolation_downstairs(prev_foot_pose, next_foot_pose, swing_height,
1011
+ num_points, is_first_step)
1012
+
1013
+ # 三角函数参数设置(上楼梯)
1014
+ if is_first_step:
1015
+ # 第一步:更保守的参数
1016
+ trig_ratio = 0.6 # 三角函数部分占比
1017
+ max_height_ratio = 1.0 # 最高点相对于总高度的比例
1018
+ else:
1019
+ # 后续步骤:优化参数
1020
+ trig_ratio = 0.6 # 三角函数部分占比
1021
+ max_height_ratio = 0.9 # 最高点相对于总高度的比例
1022
+
1023
+ # 计算基准高度(取两个落点中较高的点)
1024
+ base_height = max(prev_foot_pose[2], next_foot_pose[2])
1025
+ min_height = min(prev_foot_pose[2], next_foot_pose[2])
1026
+
1027
+ # 三角函数最高点高度参考三次样条:base_height + swing_height
1028
+ max_height = base_height + swing_height
1029
+
1030
+ # 1. 生成三角函数轨迹的4个控制点(Z方向三角函数,XY方向摆线)
1031
+ trig_control_points = []
1032
+
1033
+ # 使用三角函数生成控制点(确保在最高点零加速度)
1034
+ trig_progress = [0.0, 0.33, 0.67, 1.0] # 三角函数内部进度
1035
+
1036
+ for i, progress in enumerate(trig_progress):
1037
+ # 计算平滑进度(使用三次多项式确保在t=1时导数为0)
1038
+ t = progress
1039
+ smooth_progress = 3 * t**2 - 2 * t**3 # 三次多项式,在t=1时导数为0
1040
+
1041
+ # 三角函数方程(Z方向)- 使用正弦函数从起点到最高点
1042
+ # z = start_z + (max_height - start_z) * sin(π/2 * smooth_progress)
1043
+ start_z = prev_foot_pose[2]
1044
+ z = start_z + (max_height - start_z) * np.sin(np.pi/2 * smooth_progress)
1045
+
1046
+ # XY方向使用摆线插值
1047
+ # 摆线参数:t从0到1
1048
+ t_cycloid = progress * trig_ratio # 归一化到三角函数部分的时间
1049
+
1050
+ # 摆线方程:x = t - sin(t), y = 1 - cos(t)
1051
+ # 映射到实际坐标
1052
+ cycloid_x = t_cycloid - np.sin(2 * np.pi * t_cycloid) / (2 * np.pi)
1053
+ cycloid_y = (1 - np.cos(2 * np.pi * t_cycloid)) / 2
1054
+
1055
+ # 映射到实际XY坐标
1056
+ x = prev_foot_pose[0] + x_distance * cycloid_x
1057
+ y = prev_foot_pose[1] + y_distance * cycloid_y
1058
+
1059
+ trig_control_points.append([x, y, z])
1060
+
1061
+ # 2. 生成多项式轨迹的控制点
1062
+ polynomial_control_points = []
1063
+
1064
+ # 控制点1:多项式起点(后移,避免与三角函数末端重合)
1065
+ t_poly_start = trig_ratio + (1 - trig_ratio) * 0.32 # 三角函数占比后32%位置
1066
+
1067
+ # XY方向使用摆线规划
1068
+ cycloid_x_poly_start = t_poly_start - np.sin(2 * np.pi * t_poly_start) / (2 * np.pi)
1069
+ cycloid_y_poly_start = (1 - np.cos(2 * np.pi * t_poly_start)) / 2
1070
+
1071
+ x_poly_start = prev_foot_pose[0] + x_distance * cycloid_x_poly_start
1072
+ y_poly_start = prev_foot_pose[1] + y_distance * cycloid_y_poly_start
1073
+
1074
+ # Z方向平滑下降(从三角函数终点高度开始)
1075
+ z_trig_end = trig_control_points[-1][2] # 三角函数终点高度
1076
+ z_poly_start = z_trig_end + (next_foot_pose[2] - z_trig_end) * 0.15 # 下降15%
1077
+ polynomial_control_points.append([x_poly_start, y_poly_start, z_poly_start])
1078
+
1079
+ # 控制点2:中间点(使用摆线插值)
1080
+ t_mid = trig_ratio + (1 - trig_ratio) * 0.64 # 多项式部分64%位置
1081
+
1082
+ # 摆线插值
1083
+ cycloid_x_mid = t_mid - np.sin(2 * np.pi * t_mid) / (2 * np.pi)
1084
+ cycloid_y_mid = (1 - np.cos(2 * np.pi * t_mid)) / 2
1085
+
1086
+ x_mid = prev_foot_pose[0] + x_distance * cycloid_x_mid
1087
+ y_mid = prev_foot_pose[1] + y_distance * cycloid_y_mid
1088
+ z_mid = next_foot_pose[2] + (z_poly_start - next_foot_pose[2]) * 0.5 # 平滑下降
1089
+ polynomial_control_points.append([x_mid, y_mid, z_mid])
1090
+
1091
+ # 控制点3:目标位置
1092
+ x_end = next_foot_pose[0]
1093
+ y_end = next_foot_pose[1]
1094
+ z_end = next_foot_pose[2]
1095
+ polynomial_control_points.append([x_end, y_end, z_end])
1096
+
1097
+ # 3. 生成完整轨迹(7个控制点:4个三角函数点 + 3个多项式点)
1098
+ full_trajectory = trig_control_points + polynomial_control_points
1099
+
1100
+ # 删除第一个点(三角函数起始点)和最后一个点(多项式终点)
1101
+ full_trajectory = full_trajectory[1:-1]
1102
+
1103
+ # 4. 生成时间序列(调整时间分布,让后半段更均匀)
1104
+ # 时间分配:三角函数部分占trig_ratio,多项式部分占(1-trig_ratio)
1105
+ # 延长三角函数部分时间,让抬腿更慢
1106
+ extended_trig_ratio = trig_ratio * 1.3 # 延长30%
1107
+ trig_times = [extended_trig_ratio * 0.17, extended_trig_ratio * 0.5, extended_trig_ratio] # 去掉起始点0.0
1108
+
1109
+ # 调整多项式部分时间分布,让后半段更均匀
1110
+ polynomial_times = [extended_trig_ratio + (1-extended_trig_ratio) * 0.32,
1111
+ extended_trig_ratio + (1-extended_trig_ratio) * 0.64] # 删除最后一个时间点1.0
1112
+ full_times = trig_times + polynomial_times
1113
+
1114
+ # 5. 生成轨迹消息(确保平滑性)
1115
+ for i, point in enumerate(full_trajectory):
1116
+ step_fp = footPose()
1117
+ x, y, z = point[0], point[1], point[2]
1118
+
1119
+ # Yaw角度使用平滑插值
1120
+ progress = full_times[i]
1121
+ yaw = prev_foot_pose[3] + (next_foot_pose[3] - prev_foot_pose[3]) * progress
1122
+
1123
+ step_fp.footPose = [x, y, z, yaw]
1124
+ additionalFootPoseTrajectory.data.append(step_fp)
1125
+
1126
+ return additionalFootPoseTrajectory
1127
+
1128
+ def _trigonometric_quintic_interpolation_downstairs(self, prev_foot_pose, next_foot_pose, swing_height,
1129
+ num_points, is_first_step):
1130
+ """下楼梯专用:与上楼梯完全镜像对称,使用相同的控制点结构和三角函数范围"""
1131
+ additionalFootPoseTrajectory = footPoses()
1132
+
1133
+ # 计算移动距离
1134
+ x_distance = next_foot_pose[0] - prev_foot_pose[0]
1135
+ y_distance = next_foot_pose[1] - prev_foot_pose[1]
1136
+ z_distance = next_foot_pose[2] - prev_foot_pose[2]
1137
+
1138
+ # 下楼梯参数设置(与上楼梯完全一致)
1139
+ if is_first_step:
1140
+ # 第一步:更保守的参数
1141
+ trig_ratio = 0.6 # 三角函数部分占比
1142
+ max_height_ratio = 1.0 # 最高点相对于总高度的比例
1143
+ else:
1144
+ # 后续步骤:优化参数
1145
+ trig_ratio = 0.6 # 三角函数部分占比
1146
+ max_height_ratio = 0.9 # 最高点相对于总高度的比例
1147
+
1148
+ # 计算基准高度(取两个落点中较高的点)
1149
+ base_height = max(prev_foot_pose[2], next_foot_pose[2])
1150
+ min_height = min(prev_foot_pose[2], next_foot_pose[2])
1151
+
1152
+ # 下楼梯最高点高度:从当前台阶高度+swing_height,然后减去一级step_height
1153
+ max_height = prev_foot_pose[2] + swing_height - 0.08 # 当前台阶高度 + swing_height - step_height
1154
+
1155
+ # 1. 生成三角函数轨迹的4个控制点(与上楼梯完全相同的结构)
1156
+ trig_control_points = []
1157
+
1158
+ # 使用三角函数生成控制点(确保在最高点零加速度)
1159
+ trig_progress = [0.0, 0.33, 0.67, 1.0] # 三角函数内部进度(与上楼梯相同)
1160
+
1161
+ for i, progress in enumerate(trig_progress):
1162
+ # 计算平滑进度(使用三次多项式确保在t=1时导数为0)
1163
+ t = progress
1164
+ smooth_progress = 3 * t**2 - 2 * t**3 # 三次多项式,在t=1时导数为0
1165
+
1166
+ # 三角函数方程(Z方向)- 下楼梯:从起点上升到最高点(与上楼梯相同)
1167
+ # z = start_z + (max_height - start_z) * sin(π/2 * smooth_progress)
1168
+ start_z = prev_foot_pose[2]
1169
+ z = start_z + (max_height - start_z) * np.sin(np.pi/2 * smooth_progress)
1170
+
1171
+ # XY方向使用摆线插值(与上楼梯相同)
1172
+ # 摆线参数:t从0到1
1173
+ t_cycloid = progress * trig_ratio # 归一化到三角函数部分的时间
1174
+
1175
+ # 摆线方程:x = t - sin(t), y = 1 - cos(t)
1176
+ # 映射到实际坐标
1177
+ cycloid_x = t_cycloid - np.sin(2 * np.pi * t_cycloid) / (2 * np.pi)
1178
+ cycloid_y = (1 - np.cos(2 * np.pi * t_cycloid)) / 2
1179
+
1180
+ # 映射到实际XY坐标
1181
+ x = prev_foot_pose[0] + x_distance * cycloid_x
1182
+ y = prev_foot_pose[1] + y_distance * cycloid_y
1183
+
1184
+ trig_control_points.append([x, y, z])
1185
+
1186
+ # 2. 生成多项式轨迹的控制点(与上楼梯完全相同的结构)
1187
+ polynomial_control_points = []
1188
+
1189
+ # 控制点1:多项式起点(后移,避免与三角函数末端重合)
1190
+ t_poly_start = trig_ratio + (1 - trig_ratio) * 0.32 # 三角函数占比后32%位置
1191
+
1192
+ # XY方向使用摆线规划
1193
+ cycloid_x_poly_start = t_poly_start - np.sin(2 * np.pi * t_poly_start) / (2 * np.pi)
1194
+ cycloid_y_poly_start = (1 - np.cos(2 * np.pi * t_poly_start)) / 2
1195
+
1196
+ x_poly_start = prev_foot_pose[0] + x_distance * cycloid_x_poly_start
1197
+ y_poly_start = prev_foot_pose[1] + y_distance * cycloid_y_poly_start
1198
+
1199
+ # Z方向平滑下降(从三角函数终点高度开始)
1200
+ z_trig_end = trig_control_points[-1][2] # 三角函数终点高度
1201
+ z_poly_start = z_trig_end + (next_foot_pose[2] - z_trig_end) * 0.15 # 下降15%
1202
+ polynomial_control_points.append([x_poly_start, y_poly_start, z_poly_start])
1203
+
1204
+ # 控制点2:中间点(使用摆线插值)
1205
+ t_mid = trig_ratio + (1 - trig_ratio) * 0.64 # 多项式部分64%位置
1206
+
1207
+ # 摆线插值
1208
+ cycloid_x_mid = t_mid - np.sin(2 * np.pi * t_mid) / (2 * np.pi)
1209
+ cycloid_y_mid = (1 - np.cos(2 * np.pi * t_mid)) / 2
1210
+
1211
+ x_mid = prev_foot_pose[0] + x_distance * cycloid_x_mid
1212
+ y_mid = prev_foot_pose[1] + y_distance * cycloid_y_mid
1213
+ z_mid = next_foot_pose[2] + (z_poly_start - next_foot_pose[2]) * 0.5 # 平滑下降
1214
+ polynomial_control_points.append([x_mid, y_mid, z_mid])
1215
+
1216
+ # 控制点3:目标位置
1217
+ x_end = next_foot_pose[0]
1218
+ y_end = next_foot_pose[1]
1219
+ z_end = next_foot_pose[2]
1220
+ polynomial_control_points.append([x_end, y_end, z_end])
1221
+
1222
+ # 3. 生成完整轨迹(7个控制点:4个三角函数点 + 3个多项式点,与上楼梯相同)
1223
+ full_trajectory = trig_control_points + polynomial_control_points
1224
+
1225
+ # 删除第一个点(三角函数起始点)和最后一个点(多项式终点)
1226
+ full_trajectory = full_trajectory[1:-1]
1227
+
1228
+ # 4. 生成时间序列(与上楼梯完全相同的时间分布)
1229
+ # 时间分配:三角函数部分占trig_ratio,多项式部分占(1-trig_ratio)
1230
+ # 延长三角函数部分时间,让抬腿更慢
1231
+ extended_trig_ratio = trig_ratio * 1.3 # 延长30%
1232
+ trig_times = [extended_trig_ratio * 0.17, extended_trig_ratio * 0.5, extended_trig_ratio] # 去掉起始点0.0
1233
+
1234
+ # 调整多项式部分时间分布,让后半段更均匀
1235
+ polynomial_times = [extended_trig_ratio + (1-extended_trig_ratio) * 0.32,
1236
+ extended_trig_ratio + (1-extended_trig_ratio) * 0.64] # 删除最后一个时间点1.0
1237
+ full_times = trig_times + polynomial_times
1238
+
1239
+ # 5. 生成轨迹消息(与上楼梯完全相同的执行逻辑)
1240
+ for i, point in enumerate(full_trajectory):
1241
+ step_fp = footPose()
1242
+ x, y, z = point[0], point[1], point[2]
1243
+
1244
+ # Yaw角度使用平滑插值
1245
+ progress = full_times[i]
1246
+ yaw = prev_foot_pose[3] + (next_foot_pose[3] - prev_foot_pose[3]) * progress
1247
+
1248
+ step_fp.footPose = [x, y, z, yaw]
1249
+ additionalFootPoseTrajectory.data.append(step_fp)
1250
+
1251
+ return additionalFootPoseTrajectory
1252
+
1253
+ # SDK-style interface methods
1254
+ def climb_up_stairs(self, num_steps: int = 5, stair_offset: float = 0.0) -> bool:
1255
+ """
1256
+ Plan up stairs trajectory and add to accumulated trajectory.
1257
+
1258
+ Args:
1259
+ num_steps: Number of steps to climb stairs, must be > 0 and <= 20
1260
+ stair_offset: Offset distance from stairs (m), default 0.0
1261
+
1262
+ Returns:
1263
+ bool: Whether planning was successful
1264
+ """
1265
+ # Input validation
1266
+ if not isinstance(num_steps, int) or num_steps <= 0:
1267
+ rospy.logerr("[ClimbStair] num_steps must be a positive integer")
1268
+ return False
1269
+
1270
+ if num_steps > 20: # Reasonable safety limit
1271
+ rospy.logwarn(
1272
+ "[ClimbStair] Planning %d steps seems excessive, consider breaking into smaller segments",
1273
+ num_steps,
1274
+ )
1275
+
1276
+ try:
1277
+ if self.verbose_logging:
1278
+ rospy.loginfo(
1279
+ f"[ClimbStair] Planning up stairs trajectory with {num_steps} steps"
1280
+ )
1281
+
1282
+ # Plan trajectory using existing accumulated trajectory as starting point
1283
+ time_traj, foot_idx_traj, foot_traj, torso_traj, swing_trajectories = (
1284
+ self.plan_up_stairs(
1285
+ num_steps,
1286
+ self.time_traj.copy(),
1287
+ self.foot_idx_traj.copy(),
1288
+ self.foot_traj.copy(),
1289
+ self.torso_traj.copy(),
1290
+ self.swing_trajectories.copy(),
1291
+ stair_offset,
1292
+ )
1293
+ )
1294
+
1295
+ # Replace accumulated trajectory with new complete trajectory
1296
+ self.time_traj = time_traj
1297
+ self.foot_idx_traj = foot_idx_traj
1298
+ self.foot_traj = foot_traj
1299
+ self.torso_traj = torso_traj
1300
+ self.swing_trajectories = swing_trajectories
1301
+
1302
+ if self.verbose_logging:
1303
+ rospy.loginfo(
1304
+ f"[ClimbStair] Up stairs planning completed: {len(time_traj)} total trajectory points"
1305
+ )
1306
+ return True
1307
+ except Exception as e:
1308
+ rospy.logerr(f"[ClimbStair] Failed to plan up stairs: {e}")
1309
+ return False
1310
+
1311
+ def climb_down_stairs(self, num_steps: int = 5) -> bool:
1312
+ """
1313
+ Plan down stairs trajectory and add to accumulated trajectory.
1314
+
1315
+ Args:
1316
+ num_steps: Number of steps to climb down stairs, must be > 0 and <= 20
1317
+
1318
+ Returns:
1319
+ bool: Whether planning was successful
1320
+ """
1321
+ # TEMPORARILY DISABLED: Down stairs functionality is under development
1322
+ rospy.logwarn(
1323
+ "[ClimbStair] Down stairs functionality is currently disabled (under development)"
1324
+ )
1325
+ rospy.loginfo(
1326
+ "[ClimbStair] Please use climb_up_stairs() and move_to_position() instead"
1327
+ )
1328
+ return False
1329
+
1330
+ # Input validation
1331
+ if not isinstance(num_steps, int) or num_steps <= 0:
1332
+ rospy.logerr("[ClimbStair] num_steps must be a positive integer")
1333
+ return False
1334
+
1335
+ if num_steps > 20: # Reasonable safety limit
1336
+ rospy.logwarn(
1337
+ "[ClimbStair] Planning %d steps seems excessive, consider breaking into smaller segments",
1338
+ num_steps,
1339
+ )
1340
+
1341
+ try:
1342
+ if self.verbose_logging:
1343
+ rospy.loginfo(
1344
+ f"[ClimbStair] Planning down stairs trajectory with {num_steps} steps"
1345
+ )
1346
+
1347
+ # Plan trajectory using existing accumulated trajectory as starting point
1348
+ time_traj, foot_idx_traj, foot_traj, torso_traj, swing_trajectories = (
1349
+ self.plan_down_stairs(
1350
+ num_steps,
1351
+ self.time_traj.copy(),
1352
+ self.foot_idx_traj.copy(),
1353
+ self.foot_traj.copy(),
1354
+ self.torso_traj.copy(),
1355
+ self.swing_trajectories.copy(),
1356
+ )
1357
+ )
1358
+
1359
+ # Replace accumulated trajectory with new complete trajectory
1360
+ self.time_traj = time_traj
1361
+ self.foot_idx_traj = foot_idx_traj
1362
+ self.foot_traj = foot_traj
1363
+ self.torso_traj = torso_traj
1364
+ self.swing_trajectories = swing_trajectories
1365
+
1366
+ if self.verbose_logging:
1367
+ rospy.loginfo(
1368
+ f"[ClimbStair] Down stairs planning completed: {len(time_traj)} total trajectory points"
1369
+ )
1370
+ return True
1371
+ except Exception as e:
1372
+ rospy.logerr(f"[ClimbStair] Failed to plan down stairs: {e}")
1373
+ return False
1374
+
1375
+ def move_to_position(
1376
+ self,
1377
+ dx: float = 0.2,
1378
+ dy: float = 0.0,
1379
+ dyaw: float = 0.0,
1380
+ max_step_x: float = None,
1381
+ max_step_y: float = None,
1382
+ max_step_yaw: float = None,
1383
+ ) -> bool:
1384
+ """
1385
+ Plan move to position trajectory and add to accumulated trajectory.
1386
+
1387
+ Args:
1388
+ dx: X direction displacement (m)
1389
+ dy: Y direction displacement (m)
1390
+ dyaw: Yaw angle displacement (degrees)
1391
+ max_step_x: Maximum step size in X direction (m)
1392
+ max_step_y: Maximum step size in Y direction (m)
1393
+ max_step_yaw: Maximum yaw step size (degrees)
1394
+
1395
+ Returns:
1396
+ bool: Whether planning was successful
1397
+ """
1398
+ # Use defaults if not provided
1399
+ max_step_x = (
1400
+ max_step_x
1401
+ if max_step_x is not None
1402
+ else StairClimbingConstants.DEFAULT_MAX_STEP_X
1403
+ )
1404
+ max_step_y = (
1405
+ max_step_y
1406
+ if max_step_y is not None
1407
+ else StairClimbingConstants.DEFAULT_MAX_STEP_Y
1408
+ )
1409
+ max_step_yaw = (
1410
+ max_step_yaw
1411
+ if max_step_yaw is not None
1412
+ else StairClimbingConstants.DEFAULT_MAX_STEP_YAW
1413
+ )
1414
+
1415
+ # Input validation
1416
+ if abs(dx) > 5.0 or abs(dy) > 5.0: # Reasonable safety limits
1417
+ rospy.logerr(
1418
+ "[ClimbStair] Movement distance too large: dx=%.3f, dy=%.3f", dx, dy
1419
+ )
1420
+ return False
1421
+
1422
+ if abs(dyaw) > 180.0: # Reasonable safety limit
1423
+ rospy.logerr(
1424
+ "[ClimbStair] Rotation angle too large: dyaw=%.3f degrees", dyaw
1425
+ )
1426
+ return False
1427
+
1428
+ if max_step_x <= 0 or max_step_y <= 0 or max_step_yaw <= 0:
1429
+ rospy.logerr("[ClimbStair] All max_step parameters must be positive")
1430
+ return False
1431
+
1432
+ try:
1433
+ if self.verbose_logging:
1434
+ rospy.loginfo(
1435
+ f"[ClimbStair] Planning move trajectory: dx={dx:.3f}, dy={dy:.3f}, dyaw={dyaw:.3f}"
1436
+ )
1437
+
1438
+ # Plan trajectory using existing accumulated trajectory as starting point
1439
+ time_traj, foot_idx_traj, foot_traj, torso_traj, swing_trajectories = (
1440
+ self.plan_move_to(
1441
+ dx,
1442
+ dy,
1443
+ dyaw,
1444
+ self.time_traj.copy(),
1445
+ self.foot_idx_traj.copy(),
1446
+ self.foot_traj.copy(),
1447
+ self.torso_traj.copy(),
1448
+ self.swing_trajectories.copy(),
1449
+ max_step_x,
1450
+ max_step_y,
1451
+ max_step_yaw,
1452
+ )
1453
+ )
1454
+
1455
+ # Replace accumulated trajectory with new complete trajectory
1456
+ self.time_traj = time_traj
1457
+ self.foot_idx_traj = foot_idx_traj
1458
+ self.foot_traj = foot_traj
1459
+ self.torso_traj = torso_traj
1460
+ self.swing_trajectories = swing_trajectories
1461
+
1462
+ if self.verbose_logging:
1463
+ rospy.loginfo(
1464
+ f"[ClimbStair] Move planning completed: {len(time_traj)} total trajectory points"
1465
+ )
1466
+ return True
1467
+ except Exception as e:
1468
+ rospy.logerr(f"[ClimbStair] Failed to plan move to position: {e}")
1469
+ return False
1470
+
1471
+ def get_step_count(self) -> int:
1472
+ """Get the current total step count."""
1473
+ return self.total_step
1474
+
1475
+ def reset_step_counter(self) -> None:
1476
+ """Reset the total step counter."""
1477
+ self.total_step = 0
1478
+
1479
+ def get_trajectory_statistics(self) -> dict:
1480
+ """
1481
+ Get statistics about the current accumulated trajectory.
1482
+
1483
+ Returns:
1484
+ dict: Dictionary containing trajectory statistics
1485
+ """
1486
+ if not self.time_traj:
1487
+ return {
1488
+ "total_points": 0,
1489
+ "duration": 0.0,
1490
+ "total_steps": self.total_step,
1491
+ "has_swing_trajectories": False,
1492
+ }
1493
+
1494
+ swing_count = sum(1 for swing in self.swing_trajectories if swing is not None)
1495
+
1496
+ return {
1497
+ "total_points": len(self.time_traj),
1498
+ "duration": self.time_traj[-1] - self.time_traj[0]
1499
+ if len(self.time_traj) > 1
1500
+ else 0.0,
1501
+ "total_steps": self.total_step,
1502
+ "swing_trajectories_count": swing_count,
1503
+ "has_swing_trajectories": swing_count > 0,
1504
+ "time_range": (self.time_traj[0], self.time_traj[-1])
1505
+ if self.time_traj
1506
+ else (0, 0),
1507
+ }
1508
+
1509
+
1510
+ def parse_args():
1511
+ """Parse command line arguments (aligned with continuousStairClimber-roban.py)"""
1512
+ import argparse
1513
+ parser = argparse.ArgumentParser(description='Kuavo Robot Stair Climbing SDK')
1514
+ parser.add_argument('--plot', action='store_true', help='Enable trajectory plotting (not implemented in SDK)')
1515
+ parser.add_argument('--initH', type=float, default=0.0, help='Stand height offset (default: 0.0)')
1516
+ parser.add_argument('--steps', type=int, default=5, help='Number of stairs to climb (default: 5)')
1517
+ parser.add_argument('--move_x', type=float, default=0.15, help='Forward movement after stairs (default: 0.15m)')
1518
+ parser.add_argument('--stair_offset', type=float, default=0.03, help='Offset distance from stairs (default: 0.03m)')
1519
+ parser.add_argument('--verbose', action='store_true', help='Enable verbose logging')
1520
+ return parser.parse_args()
1521
+
1522
+
1523
+ if __name__ == '__main__':
1524
+ try:
1525
+ rospy.init_node("climb_stair_node")
1526
+ args = parse_args()
1527
+
1528
+ # Set parameters based on command line arguments
1529
+ stand_height = args.initH
1530
+ verbose_logging = args.verbose
1531
+ num_stairs = args.steps
1532
+ move_distance = args.move_x
1533
+ stair_offset = args.stair_offset
1534
+
1535
+ if args.plot:
1536
+ rospy.logwarn("[ClimbStair] Plot functionality is not implemented in SDK version")
1537
+
1538
+ # Disable pitch limit (aligned with roban script)
1539
+ rospy.loginfo("[ClimbStair] Disabling pitch limit...")
1540
+ set_pitch_limit(False)
1541
+
1542
+ # Initialize the SDK robot
1543
+ robot = KuavoRobotClimbStair(
1544
+ stand_height=stand_height,
1545
+ verbose_logging=verbose_logging
1546
+ )
1547
+
1548
+ rospy.loginfo(f"[ClimbStair] Initialized robot with stand_height={stand_height:.3f}")
1549
+
1550
+ # Execute stair climbing sequence (aligned with continuousStairClimber-roban.py)
1551
+ rospy.loginfo(f"[ClimbStair] Planning up stairs with {num_stairs} steps, stair_offset={stair_offset:.3f}m...")
1552
+ success = robot.climb_up_stairs(num_stairs, stair_offset=stair_offset)
1553
+ if success:
1554
+ rospy.loginfo("[ClimbStair] Up stairs planning completed successfully")
1555
+ else:
1556
+ rospy.logerr("[ClimbStair] Up stairs planning failed")
1557
+ exit(1)
1558
+
1559
+ # Print trajectory details
1560
+ stats = robot.get_trajectory_statistics()
1561
+ rospy.loginfo(f"[ClimbStair] Trajectory statistics: {stats}")
1562
+
1563
+ # Add forward movement after stairs (aligned with roban script)
1564
+ rospy.loginfo(f"[ClimbStair] Planning forward movement: {move_distance:.3f}m...")
1565
+ success = robot.move_to_position(dx=move_distance, dy=0.0, dyaw=0.0)
1566
+ if success:
1567
+ rospy.loginfo("[ClimbStair] Move planning completed successfully")
1568
+ else:
1569
+ rospy.logerr("[ClimbStair] Move planning failed")
1570
+ exit(1)
1571
+
1572
+ # Print final trajectory details
1573
+ final_stats = robot.get_trajectory_statistics()
1574
+ rospy.loginfo(f"[ClimbStair] Final trajectory statistics: {final_stats}")
1575
+
1576
+ # Print detailed trajectory (similar to roban script)
1577
+ if verbose_logging and robot.time_traj:
1578
+ rospy.loginfo("[ClimbStair] Detailed trajectory:")
1579
+ for i, t in enumerate(robot.time_traj):
1580
+ rospy.loginfo(
1581
+ f" {i:2}: t={t:5.2f} foot_idx={robot.foot_idx_traj[i]} "
1582
+ f"foot=[{robot.foot_traj[i][0]:6.3f}, {robot.foot_traj[i][1]:6.3f}, "
1583
+ f"{robot.foot_traj[i][2]:6.3f}, {robot.foot_traj[i][3]:6.3f}] "
1584
+ f"torso=[{robot.torso_traj[i][0]:6.3f}, {robot.torso_traj[i][1]:6.3f}, "
1585
+ f"{robot.torso_traj[i][2]:6.3f}, {robot.torso_traj[i][3]:6.3f}]"
1586
+ )
1587
+
1588
+ # Execute the complete trajectory
1589
+ rospy.loginfo("[ClimbStair] Executing complete trajectory...")
1590
+ success = robot.execute_trajectory()
1591
+ if success:
1592
+ rospy.loginfo("[ClimbStair] Trajectory execution completed successfully")
1593
+ else:
1594
+ rospy.logerr("[ClimbStair] Trajectory execution failed")
1595
+ exit(1)
1596
+
1597
+ rospy.loginfo("[ClimbStair] All operations completed successfully!")
1598
+
1599
+ except rospy.ROSInterruptException:
1600
+ rospy.loginfo("[ClimbStair] Interrupted by user")
1601
+ # Ensure pitch limit is re-enabled on interruption (aligned with roban script)
1602
+ set_pitch_limit(True)
1603
+ except Exception as e:
1604
+ rospy.logerr(f"[ClimbStair] Unexpected error: {e}")
1605
+ # Ensure pitch limit is re-enabled on error
1606
+ set_pitch_limit(True)
1607
+ exit(1)