kuavo-humanoid-sdk 1.2.1b3321__20250917182547-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.
- kuavo_humanoid_sdk/__init__.py +6 -0
- kuavo_humanoid_sdk/common/logger.py +45 -0
- kuavo_humanoid_sdk/interfaces/__init__.py +4 -0
- kuavo_humanoid_sdk/interfaces/data_types.py +288 -0
- kuavo_humanoid_sdk/interfaces/end_effector.py +62 -0
- kuavo_humanoid_sdk/interfaces/robot.py +22 -0
- kuavo_humanoid_sdk/interfaces/robot_info.py +56 -0
- kuavo_humanoid_sdk/kuavo/__init__.py +16 -0
- kuavo_humanoid_sdk/kuavo/core/audio.py +32 -0
- kuavo_humanoid_sdk/kuavo/core/core.py +666 -0
- kuavo_humanoid_sdk/kuavo/core/dex_hand_control.py +114 -0
- kuavo_humanoid_sdk/kuavo/core/leju_claw_control.py +67 -0
- kuavo_humanoid_sdk/kuavo/core/llm_doubao.py +608 -0
- kuavo_humanoid_sdk/kuavo/core/microphone.py +192 -0
- kuavo_humanoid_sdk/kuavo/core/navigation.py +70 -0
- kuavo_humanoid_sdk/kuavo/core/ros/audio.py +110 -0
- kuavo_humanoid_sdk/kuavo/core/ros/camera.py +105 -0
- kuavo_humanoid_sdk/kuavo/core/ros/control.py +1524 -0
- kuavo_humanoid_sdk/kuavo/core/ros/microphone.py +38 -0
- kuavo_humanoid_sdk/kuavo/core/ros/navigation.py +217 -0
- kuavo_humanoid_sdk/kuavo/core/ros/observation.py +94 -0
- kuavo_humanoid_sdk/kuavo/core/ros/param.py +201 -0
- kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
- kuavo_humanoid_sdk/kuavo/core/ros/state.py +652 -0
- kuavo_humanoid_sdk/kuavo/core/ros/tools.py +220 -0
- kuavo_humanoid_sdk/kuavo/core/ros/vision.py +234 -0
- kuavo_humanoid_sdk/kuavo/core/ros_env.py +238 -0
- kuavo_humanoid_sdk/kuavo/core/sdk_deprecated.py +41 -0
- kuavo_humanoid_sdk/kuavo/demo_climbstair.py +249 -0
- kuavo_humanoid_sdk/kuavo/dexterous_hand.py +238 -0
- kuavo_humanoid_sdk/kuavo/leju_claw.py +235 -0
- kuavo_humanoid_sdk/kuavo/logger_client.py +80 -0
- kuavo_humanoid_sdk/kuavo/robot.py +646 -0
- kuavo_humanoid_sdk/kuavo/robot_arm.py +411 -0
- kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
- kuavo_humanoid_sdk/kuavo/robot_blockly.py +1154 -0
- kuavo_humanoid_sdk/kuavo/robot_climbstair.py +1607 -0
- kuavo_humanoid_sdk/kuavo/robot_head.py +95 -0
- kuavo_humanoid_sdk/kuavo/robot_info.py +134 -0
- kuavo_humanoid_sdk/kuavo/robot_microphone.py +19 -0
- kuavo_humanoid_sdk/kuavo/robot_navigation.py +135 -0
- kuavo_humanoid_sdk/kuavo/robot_observation.py +64 -0
- kuavo_humanoid_sdk/kuavo/robot_speech.py +24 -0
- kuavo_humanoid_sdk/kuavo/robot_state.py +310 -0
- kuavo_humanoid_sdk/kuavo/robot_tool.py +109 -0
- kuavo_humanoid_sdk/kuavo/robot_vision.py +81 -0
- kuavo_humanoid_sdk/kuavo_strategy/__init__.py +2 -0
- kuavo_humanoid_sdk/kuavo_strategy/grasp_box/grasp_box_strategy.py +1325 -0
- kuavo_humanoid_sdk/kuavo_strategy/kuavo_strategy.py +106 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/common/data_type.py +340 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/common/events/base_event.py +215 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/common/robot_sdk.py +25 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/pick_place_box/case.py +331 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/pick_place_box/strategy.py +504 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/utils/logger_setup.py +40 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/utils/utils.py +88 -0
- kuavo_humanoid_sdk/msg/__init__.py +4 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/__init__.py +7 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetection.py +306 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetectionArray.py +437 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AudioReceiverData.py +122 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_FTsensorData.py +260 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_JoySticks.py +191 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_Metadata.py +199 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_MmDetectionMsg.py +264 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_RobotActionState.py +112 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_TFArray.py +323 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_TaskPoint.py +175 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/__init__.py +62 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armCollisionCheckInfo.py +160 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPose.py +161 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPoseFree.py +171 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armPoseWithTimeStamp.py +168 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armTargetPoses.py +171 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_bezierCurveCubicPoint.py +178 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_dexhandCommand.py +229 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_dexhandTouchState.py +256 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_endEffectorData.py +227 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose.py +123 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose6D.py +123 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose6DTargetTrajectories.py +320 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseTargetTrajectories.py +301 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseWithVision.py +136 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseWithVisionArray.py +231 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses.py +149 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses6D.py +149 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_fullBodyTargetTrajectories.py +258 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gaitTimeName.py +147 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gestureInfo.py +218 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gestureTask.py +149 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_handPose.py +136 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_headBodyPose.py +145 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_ikSolveError.py +171 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_ikSolveParam.py +140 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_imuData.py +165 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointBezierTrajectory.py +201 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointCmd.py +390 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointData.py +205 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_kuavoModeSchedule.py +224 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_lejuClawCommand.py +320 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_lejuClawState.py +341 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_motorParam.py +122 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_picoPoseInfo.py +143 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_picoPoseInfoList.py +220 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_planArmState.py +120 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_qv.py +121 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotArmQVVD.py +177 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotBodyMatrices.py +332 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotHandPosition.py +225 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotHeadMotionData.py +128 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotState.py +222 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_sensorsData.py +655 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_switchGaitByName.py +200 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_tagDataArray.py +216 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_touchSensorStatus.py +162 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPose.py +273 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmd.py +316 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmdFree.py +338 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseFree.py +299 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_yoloDetection.py +251 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_yoloOutputData.py +168 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_CreatePath.py +581 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_ExecuteArmAction.py +281 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetAllMaps.py +241 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetCurrentMap.py +225 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetTargetPartPoseInCamera.py +298 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_InitialPoseWithTaskPoint.py +281 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_LoadMap.py +281 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_NavigateToTaskPoint.py +281 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_RepublishTFs.py +373 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetInitialPose.py +394 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetJoyTopic.py +282 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetLEDMode.py +468 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetLEDMode_free.py +289 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SpeechSynthesis.py +270 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_TaskPointOperation.py +536 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/__init__.py +43 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_adjustZeroPoint.py +277 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeArmCtrlMode.py +275 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeArmCtrlModeKuavo.py +236 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeMotorParam.py +299 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeTorsoCtrlMode.py +274 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_controlLejuClaw.py +408 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_enableHandTouchSensor.py +304 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_fkSrv.py +395 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_footPose6DTargetTrajectoriesSrv.py +426 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_footPoseTargetTrajectoriesSrv.py +409 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureExecute.py +339 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureExecuteState.py +257 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureList.py +418 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getCurrentGaitName.py +253 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getMotorParam.py +299 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getMotorZeroPoints.py +286 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_handForceLevel.py +330 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_jointMoveTo.py +302 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryBezierCurve.py +422 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryCubicSpline.py +490 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_playmusic.py +268 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setHwIntialState.py +304 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setMmCtrlFrame.py +273 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setMotorEncoderRoundService.py +283 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setTagId.py +275 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_singleStepControl.py +444 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_twoArmHandPoseCmdFreeSrv.py +716 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_twoArmHandPoseCmdSrv.py +664 -0
- kuavo_humanoid_sdk/msg/motion_capture_ik/__init__.py +7 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/__init__.py +7 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/__init__.py +12 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_constraint.py +142 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_controller_data.py +121 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_lagrangian_metrics.py +148 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mode_schedule.py +150 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_flattened_controller.py +666 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_input.py +122 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_observation.py +209 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_performance_indices.py +140 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_solver_data.py +886 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_state.py +122 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_target_trajectories.py +239 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_multiplier.py +148 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/srv/__init__.py +1 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/srv/_reset.py +376 -0
- kuavo_humanoid_sdk-1.2.1b3321.dist-info/METADATA +297 -0
- kuavo_humanoid_sdk-1.2.1b3321.dist-info/RECORD +186 -0
- kuavo_humanoid_sdk-1.2.1b3321.dist-info/WHEEL +6 -0
- kuavo_humanoid_sdk-1.2.1b3321.dist-info/top_level.txt +1 -0
|
@@ -0,0 +1,41 @@
|
|
|
1
|
+
import warnings
|
|
2
|
+
from deprecated import deprecated
|
|
3
|
+
|
|
4
|
+
def custom_formatwarning(message, category, filename, lineno, file=None, line=None):
|
|
5
|
+
return f"\033[33mWarning: {filename}:{lineno} - {message}\033[0m\n"
|
|
6
|
+
|
|
7
|
+
warnings.formatwarning = custom_formatwarning
|
|
8
|
+
|
|
9
|
+
def sdk_deprecated(reason=None, version=None, replacement=None, removed_in=None, remove_date=None):
|
|
10
|
+
"""
|
|
11
|
+
SDK专用的弃用装饰器,支持函数和类
|
|
12
|
+
|
|
13
|
+
Args:
|
|
14
|
+
reason (str): 弃用原因
|
|
15
|
+
version (str): 弃用版本
|
|
16
|
+
replacement (str): 替代函数/类名,如果为None则自动生成
|
|
17
|
+
removed_in (str): 将在哪个版本移除
|
|
18
|
+
remove_date (str): 将在哪个日期移除 (格式: YYYY-MM-DD)
|
|
19
|
+
"""
|
|
20
|
+
# 构建reason字符串,包含replacement、removed_in和remove_date信息
|
|
21
|
+
if reason is None:
|
|
22
|
+
reason = ""
|
|
23
|
+
if replacement:
|
|
24
|
+
if reason:
|
|
25
|
+
reason += f",建议使用 {replacement} 替代"
|
|
26
|
+
else:
|
|
27
|
+
reason = f"建议使用 {replacement} 替代"
|
|
28
|
+
if removed_in:
|
|
29
|
+
if reason:
|
|
30
|
+
reason += f",将在版本 {removed_in} 移除"
|
|
31
|
+
else:
|
|
32
|
+
reason = f"将在版本 {removed_in} 移除"
|
|
33
|
+
if remove_date:
|
|
34
|
+
if reason:
|
|
35
|
+
reason += f",预计移除日期: {remove_date}"
|
|
36
|
+
else:
|
|
37
|
+
reason = f"预计移除日期: {remove_date}"
|
|
38
|
+
|
|
39
|
+
# 使用标准的deprecated装饰器
|
|
40
|
+
return deprecated(version=version, reason=reason)
|
|
41
|
+
|
|
@@ -0,0 +1,249 @@
|
|
|
1
|
+
#!/usr/bin/env python3
|
|
2
|
+
# coding: utf-8
|
|
3
|
+
|
|
4
|
+
import argparse
|
|
5
|
+
import sys
|
|
6
|
+
import rospy
|
|
7
|
+
from robot_climbstair import KuavoRobotClimbStair
|
|
8
|
+
|
|
9
|
+
|
|
10
|
+
def parse_args():
|
|
11
|
+
"""Parse command line arguments."""
|
|
12
|
+
parser = argparse.ArgumentParser(
|
|
13
|
+
description="Stair climbing demo using KuavoRobotClimbStair"
|
|
14
|
+
)
|
|
15
|
+
parser.add_argument(
|
|
16
|
+
"--plot", action="store_true", help="Enable trajectory plotting"
|
|
17
|
+
)
|
|
18
|
+
parser.add_argument(
|
|
19
|
+
"--initH", type=float, default=0.0, help="Stand height offset (default: 0.0)"
|
|
20
|
+
)
|
|
21
|
+
return parser.parse_args()
|
|
22
|
+
|
|
23
|
+
|
|
24
|
+
def wait_for_user_confirmation(message: str) -> bool:
|
|
25
|
+
"""Wait for user confirmation before proceeding."""
|
|
26
|
+
try:
|
|
27
|
+
response = input(f"{message} (y/n): ").lower().strip()
|
|
28
|
+
return response in ["y", "yes"]
|
|
29
|
+
except KeyboardInterrupt:
|
|
30
|
+
print("\nDemo interrupted by user")
|
|
31
|
+
return False
|
|
32
|
+
|
|
33
|
+
|
|
34
|
+
def main():
|
|
35
|
+
"""Main demo function replicating original stairClimbPlanner.py sequence."""
|
|
36
|
+
try:
|
|
37
|
+
# Parse command line arguments
|
|
38
|
+
args = parse_args()
|
|
39
|
+
plot_enabled = args.plot
|
|
40
|
+
stand_height = args.initH
|
|
41
|
+
|
|
42
|
+
rospy.loginfo(
|
|
43
|
+
f"[Demo] Starting stair climbing demo with plot={plot_enabled}, stand_height={stand_height}"
|
|
44
|
+
)
|
|
45
|
+
|
|
46
|
+
# Initialize robot stair climbing system
|
|
47
|
+
climb_stair = KuavoRobotClimbStair()
|
|
48
|
+
|
|
49
|
+
# Set stair parameters matching the original script
|
|
50
|
+
success = climb_stair.set_stair_parameters(
|
|
51
|
+
step_height=0.13, # 台阶高度
|
|
52
|
+
step_length=0.28, # 台阶长度
|
|
53
|
+
foot_width=0.10, # 宽
|
|
54
|
+
stand_height=stand_height,
|
|
55
|
+
dt=0.6, # 步态周期
|
|
56
|
+
ss_time=0.5, # 支撑相时间
|
|
57
|
+
)
|
|
58
|
+
|
|
59
|
+
if not success:
|
|
60
|
+
rospy.logerr("[Demo] Failed to set stair parameters")
|
|
61
|
+
return False
|
|
62
|
+
|
|
63
|
+
# Display current parameters
|
|
64
|
+
params = climb_stair.get_parameters()
|
|
65
|
+
rospy.loginfo(
|
|
66
|
+
f"[Demo] Current parameters: step_height={params['step_height']:.3f}m, "
|
|
67
|
+
f"step_length={params['step_length']:.3f}m, dt={params['dt']:.3f}s"
|
|
68
|
+
)
|
|
69
|
+
|
|
70
|
+
# Ask user confirmation before starting
|
|
71
|
+
if not wait_for_user_confirmation("Start stair climbing demo sequence?"):
|
|
72
|
+
rospy.loginfo("[Demo] Demo cancelled by user")
|
|
73
|
+
return False
|
|
74
|
+
|
|
75
|
+
# Use the new API: plan all trajectories, then publish them
|
|
76
|
+
rospy.loginfo("[Demo] Planning complete demo sequence...")
|
|
77
|
+
|
|
78
|
+
# Disable pitch limit for stair climbing
|
|
79
|
+
from robot_climbstair import set_pitch_limit
|
|
80
|
+
|
|
81
|
+
set_pitch_limit(False)
|
|
82
|
+
|
|
83
|
+
# Clear any existing trajectory
|
|
84
|
+
climb_stair.clear_trajectory()
|
|
85
|
+
|
|
86
|
+
# Phase 1: Plan up stairs
|
|
87
|
+
success = climb_stair.climb_up_stairs(5)
|
|
88
|
+
if not success:
|
|
89
|
+
rospy.logerr("[Demo] Failed to plan up stairs")
|
|
90
|
+
set_pitch_limit(True)
|
|
91
|
+
return False
|
|
92
|
+
rospy.loginfo("[Demo] Up stairs plan done.")
|
|
93
|
+
|
|
94
|
+
# Phase 2: Plan move forward
|
|
95
|
+
success = climb_stair.move_to_position(0.35, 0, 0)
|
|
96
|
+
if not success:
|
|
97
|
+
rospy.logerr("[Demo] Failed to plan move forward")
|
|
98
|
+
set_pitch_limit(True)
|
|
99
|
+
return False
|
|
100
|
+
rospy.loginfo("[Demo] Move forward plan done.")
|
|
101
|
+
|
|
102
|
+
# Phase 3: Plan down stairs (TEMPORARILY DISABLED)
|
|
103
|
+
rospy.loginfo(
|
|
104
|
+
"[Demo] Skipping down stairs phase (functionality under development)"
|
|
105
|
+
)
|
|
106
|
+
# success = climb_stair.climb_down_stairs(5)
|
|
107
|
+
# if not success:
|
|
108
|
+
# rospy.logerr("[Demo] Failed to plan down stairs")
|
|
109
|
+
# set_pitch_limit(True)
|
|
110
|
+
# return False
|
|
111
|
+
rospy.loginfo("[Demo] Down stairs phase skipped.")
|
|
112
|
+
|
|
113
|
+
# Execute the complete accumulated trajectory
|
|
114
|
+
rospy.loginfo("[Demo] Executing complete trajectory sequence...")
|
|
115
|
+
success = climb_stair.execute_trajectory()
|
|
116
|
+
|
|
117
|
+
# Re-enable pitch limit
|
|
118
|
+
set_pitch_limit(True)
|
|
119
|
+
|
|
120
|
+
if not success:
|
|
121
|
+
rospy.logerr("[Demo] Failed to execute demo sequence")
|
|
122
|
+
return False
|
|
123
|
+
|
|
124
|
+
rospy.loginfo("[Demo] ✓ Complete demo sequence executed successfully!")
|
|
125
|
+
|
|
126
|
+
# Print final statistics
|
|
127
|
+
total_steps = climb_stair.get_step_count()
|
|
128
|
+
rospy.loginfo(
|
|
129
|
+
f"[Demo] Demo completed successfully! Total steps taken: {total_steps}"
|
|
130
|
+
)
|
|
131
|
+
print(f"\n=== DEMO COMPLETED ===")
|
|
132
|
+
print(f"Total steps taken: {total_steps}")
|
|
133
|
+
print("All phases completed successfully!")
|
|
134
|
+
|
|
135
|
+
return True
|
|
136
|
+
|
|
137
|
+
except KeyboardInterrupt:
|
|
138
|
+
rospy.logwarn("[Demo] Demo interrupted by user (Ctrl+C)")
|
|
139
|
+
return False
|
|
140
|
+
except Exception as e:
|
|
141
|
+
rospy.logerr(f"[Demo] Demo failed with exception: {e}")
|
|
142
|
+
return False
|
|
143
|
+
|
|
144
|
+
|
|
145
|
+
def run_detailed_demo():
|
|
146
|
+
"""Run demo with detailed trajectory logging (similar to original script)."""
|
|
147
|
+
try:
|
|
148
|
+
args = parse_args()
|
|
149
|
+
stand_height = args.initH
|
|
150
|
+
|
|
151
|
+
rospy.loginfo("[Demo] Starting detailed stair climbing demo")
|
|
152
|
+
|
|
153
|
+
# Initialize robot
|
|
154
|
+
climb_stair = KuavoRobotClimbStair()
|
|
155
|
+
|
|
156
|
+
# Set parameters
|
|
157
|
+
climb_stair.set_stair_parameters(
|
|
158
|
+
step_height=0.13,
|
|
159
|
+
step_length=0.28,
|
|
160
|
+
foot_width=0.10,
|
|
161
|
+
stand_height=stand_height,
|
|
162
|
+
)
|
|
163
|
+
|
|
164
|
+
print("\n=== DETAILED STAIR CLIMBING DEMO ===")
|
|
165
|
+
print("This demo replicates the exact sequence from stairClimbPlanner.py:")
|
|
166
|
+
print("1. Up stairs (5 steps)")
|
|
167
|
+
print("2. Move forward (0.35m)")
|
|
168
|
+
print("3. Down stairs (5 steps)")
|
|
169
|
+
print()
|
|
170
|
+
|
|
171
|
+
# Disable pitch limit (matching original behavior)
|
|
172
|
+
climb_stair.set_pitch_limit(False)
|
|
173
|
+
|
|
174
|
+
print("=== EXECUTING COMPLETE TRAJECTORY SEQUENCE ===")
|
|
175
|
+
|
|
176
|
+
# Use the new API: plan all trajectories, then publish them
|
|
177
|
+
climb_stair.clear_trajectory()
|
|
178
|
+
|
|
179
|
+
# Phase 1: Plan up stairs
|
|
180
|
+
success = climb_stair.climb_up_stairs(5)
|
|
181
|
+
if not success:
|
|
182
|
+
print("✗ Failed to plan up stairs")
|
|
183
|
+
return False
|
|
184
|
+
print("✓ Up stairs plan done.")
|
|
185
|
+
|
|
186
|
+
# Phase 2: Plan move forward
|
|
187
|
+
success = climb_stair.move_to_position(0.35, 0, 0)
|
|
188
|
+
if not success:
|
|
189
|
+
print("✗ Failed to plan move forward")
|
|
190
|
+
return False
|
|
191
|
+
print("✓ Move forward plan done.")
|
|
192
|
+
|
|
193
|
+
# Phase 3: Plan down stairs (TEMPORARILY DISABLED)
|
|
194
|
+
print("⚠ Skipping down stairs phase (functionality under development)")
|
|
195
|
+
# success = climb_stair.climb_down_stairs(5)
|
|
196
|
+
# if not success:
|
|
197
|
+
# print("✗ Failed to plan down stairs")
|
|
198
|
+
# return False
|
|
199
|
+
print("✓ Down stairs phase skipped.")
|
|
200
|
+
|
|
201
|
+
# Execute the complete accumulated trajectory
|
|
202
|
+
print("Executing complete trajectory sequence...")
|
|
203
|
+
success = climb_stair.execute_trajectory()
|
|
204
|
+
if success:
|
|
205
|
+
print("✓ Complete trajectory sequence executed successfully")
|
|
206
|
+
print(f"Total step count: {climb_stair.get_step_count()}")
|
|
207
|
+
else:
|
|
208
|
+
print("✗ Complete trajectory sequence failed")
|
|
209
|
+
return False
|
|
210
|
+
|
|
211
|
+
# Re-enable pitch limit (safety)
|
|
212
|
+
climb_stair.set_pitch_limit(True)
|
|
213
|
+
|
|
214
|
+
total_steps = climb_stair.get_step_count()
|
|
215
|
+
print(f"\n=== DEMO COMPLETED ===")
|
|
216
|
+
print(f"Total steps taken: {total_steps}")
|
|
217
|
+
print("All phases completed successfully!")
|
|
218
|
+
print("\nTrajectory published to: /humanoid_mpc_foot_pose_target_trajectories")
|
|
219
|
+
|
|
220
|
+
return True
|
|
221
|
+
|
|
222
|
+
except Exception as e:
|
|
223
|
+
# Ensure pitch limit is restored on error
|
|
224
|
+
try:
|
|
225
|
+
climb_stair.set_pitch_limit(True)
|
|
226
|
+
except:
|
|
227
|
+
pass
|
|
228
|
+
rospy.logerr(f"[Demo] Detailed demo failed: {e}")
|
|
229
|
+
return False
|
|
230
|
+
|
|
231
|
+
|
|
232
|
+
if __name__ == "__main__":
|
|
233
|
+
try:
|
|
234
|
+
rospy.init_node("stair_climbing_demo", anonymous=True)
|
|
235
|
+
success = main()
|
|
236
|
+
|
|
237
|
+
if success:
|
|
238
|
+
rospy.loginfo("[Demo] Demo completed successfully!")
|
|
239
|
+
sys.exit(0)
|
|
240
|
+
else:
|
|
241
|
+
rospy.logerr("[Demo] Demo failed!")
|
|
242
|
+
sys.exit(1)
|
|
243
|
+
|
|
244
|
+
except KeyboardInterrupt:
|
|
245
|
+
rospy.logwarn("[Demo] Demo interrupted by user")
|
|
246
|
+
sys.exit(130)
|
|
247
|
+
except Exception as e:
|
|
248
|
+
rospy.logerr(f"[Demo] Unexpected error: {e}")
|
|
249
|
+
sys.exit(1)
|
|
@@ -0,0 +1,238 @@
|
|
|
1
|
+
#!/usr/bin/env python3
|
|
2
|
+
# coding: utf-8
|
|
3
|
+
from typing import Tuple
|
|
4
|
+
from kuavo_humanoid_sdk.interfaces.end_effector import EndEffector
|
|
5
|
+
from kuavo_humanoid_sdk.interfaces.data_types import EndEffectorSide, EndEffectorState, KuavoDexHandTouchState
|
|
6
|
+
from kuavo_humanoid_sdk.kuavo.core.dex_hand_control import DexHandControl
|
|
7
|
+
from kuavo_humanoid_sdk.kuavo.core.ros.state import KuavoRobotStateCore
|
|
8
|
+
import time
|
|
9
|
+
|
|
10
|
+
class DexterousHand(EndEffector):
|
|
11
|
+
"""普通灵巧手控制类"""
|
|
12
|
+
def __init__(self):
|
|
13
|
+
joint_names = ['l_thumb', 'l_thumb_aux', 'l_index', 'l_middle', 'l_ring', 'l_pinky',
|
|
14
|
+
'r_thumb', 'r_thumb_aux', 'r_index', 'r_middle', 'r_ring', 'r_pinky',]
|
|
15
|
+
super().__init__(joint_names=joint_names)
|
|
16
|
+
self.dex_hand_control = DexHandControl()
|
|
17
|
+
self._rb_state = KuavoRobotStateCore()
|
|
18
|
+
|
|
19
|
+
def control(self, target_positions:list, target_velocities:list=None, target_torques:list=None)->bool:
|
|
20
|
+
"""控制灵巧手的位置。
|
|
21
|
+
|
|
22
|
+
Args:
|
|
23
|
+
target_positions (list): 所有手指关节的目标位置列表,长度必须为12(每只手6个手指关节),范围 => [0.0 ~ 100.0]
|
|
24
|
+
target_velocities (list, optional): 不支持。默认为None。
|
|
25
|
+
target_torques (list, optional): 不支持。默认为None。
|
|
26
|
+
|
|
27
|
+
Returns:
|
|
28
|
+
bool: 如果控制成功返回 True,否则返回 False。
|
|
29
|
+
|
|
30
|
+
Note:
|
|
31
|
+
target_velocities 和 target_torques 参数暂不支持。
|
|
32
|
+
"""
|
|
33
|
+
if len(target_positions) != self.joint_count():
|
|
34
|
+
raise ValueError(f"Target positions must have the same length as joint names {len(target_positions)} != {self.joint_count()}")
|
|
35
|
+
|
|
36
|
+
q = [max(0, min(100, pos if isinstance(pos, int) else int(pos))) for pos in target_positions]
|
|
37
|
+
|
|
38
|
+
# control the hand
|
|
39
|
+
return self.dex_hand_control.control(target_positions=q, side=EndEffectorSide.BOTH)
|
|
40
|
+
|
|
41
|
+
def control_right(self, target_positions:list, target_velocities:list=None, target_torques:list=None)->bool:
|
|
42
|
+
"""控制右手灵巧手。
|
|
43
|
+
|
|
44
|
+
Args:
|
|
45
|
+
target_positions (list): 右手关节的目标位置 [0 ~ 100],长度必须为6
|
|
46
|
+
target_velocities (list, optional): 不支持。默认为None。
|
|
47
|
+
target_torques (list, optional): 不支持。默认为None。
|
|
48
|
+
|
|
49
|
+
Returns:
|
|
50
|
+
bool: 如果控制成功返回True,否则返回False。
|
|
51
|
+
|
|
52
|
+
Raises:
|
|
53
|
+
ValueError: 如果目标位置长度与关节数不匹配或值超出[0,100]范围
|
|
54
|
+
|
|
55
|
+
Note:
|
|
56
|
+
target_velocities 和 target_torques 参数暂不支持。
|
|
57
|
+
"""
|
|
58
|
+
if len(target_positions) != (self.joint_count()/2):
|
|
59
|
+
raise ValueError(f"Target positions must have the same length as joint names {len(target_positions)} != {self.joint_count()/2}.")
|
|
60
|
+
|
|
61
|
+
q = [max(0, min(100, pos if isinstance(pos, int) else int(pos))) for pos in target_positions]
|
|
62
|
+
|
|
63
|
+
return self.dex_hand_control.control(target_positions=q, side=EndEffectorSide.RIGHT)
|
|
64
|
+
|
|
65
|
+
def control_left(self, target_positions:list, target_velocities:list=None, target_torques:list=None)->bool:
|
|
66
|
+
"""控制左手灵巧手。
|
|
67
|
+
|
|
68
|
+
Args:
|
|
69
|
+
target_positions (list): 左手关节的目标位置 [0 ~ 100],长度必须为6
|
|
70
|
+
target_velocities (list, optional): 不支持。默认为None。
|
|
71
|
+
target_torques (list, optional): 不支持。默认为None。
|
|
72
|
+
|
|
73
|
+
Returns:
|
|
74
|
+
bool: 如果控制成功返回True,否则返回False。
|
|
75
|
+
|
|
76
|
+
Raises:
|
|
77
|
+
ValueError: 如果目标位置长度与关节数不匹配或值超出[0,100]范围
|
|
78
|
+
|
|
79
|
+
Note:
|
|
80
|
+
target_velocities 和 target_torques 参数不支持。
|
|
81
|
+
"""
|
|
82
|
+
if len(target_positions) != (self.joint_count()/2):
|
|
83
|
+
raise ValueError(f"Target positions must have the same length as joint names {len(target_positions)} != {self.joint_count()/2}.")
|
|
84
|
+
|
|
85
|
+
q = [max(0, min(100, pos if isinstance(pos, int) else int(pos))) for pos in target_positions]
|
|
86
|
+
|
|
87
|
+
return self.dex_hand_control.control(target_positions=q, side=EndEffectorSide.LEFT)
|
|
88
|
+
|
|
89
|
+
def open(self, side: EndEffectorSide=EndEffectorSide.BOTH)->bool:
|
|
90
|
+
"""通过将所有关节位置设置为 0 来张开灵巧手。
|
|
91
|
+
|
|
92
|
+
Args:
|
|
93
|
+
side (EndEffectorSide, optional): 要打开的手。默认为 :attr:`EndEffectorSide.BOTH`。 \n
|
|
94
|
+
可以是 :attr:`EndEffectorSide.LEFT`、:attr:`EndEffectorSide.RIGHT` 或 :attr:`EndEffectorSide.BOTH`。
|
|
95
|
+
|
|
96
|
+
Returns:
|
|
97
|
+
bool: 如果打开命令发送成功返回True,否则返回False。
|
|
98
|
+
"""
|
|
99
|
+
zero_pos = [0]*self.joint_count()
|
|
100
|
+
if side == EndEffectorSide.LEFT:
|
|
101
|
+
return self.dex_hand_control.control(target_positions=zero_pos[:len(zero_pos)//2], side=EndEffectorSide.LEFT)
|
|
102
|
+
elif side == EndEffectorSide.RIGHT:
|
|
103
|
+
return self.dex_hand_control.control(target_positions=zero_pos[len(zero_pos)//2:], side=EndEffectorSide.RIGHT)
|
|
104
|
+
else:
|
|
105
|
+
return self.dex_hand_control.control(target_positions=zero_pos, side=EndEffectorSide.BOTH)
|
|
106
|
+
|
|
107
|
+
def make_gesture(self, l_gesture_name: str, r_gesture_name: str)->bool:
|
|
108
|
+
"""为双手做预定义的手势。
|
|
109
|
+
|
|
110
|
+
Args:
|
|
111
|
+
l_gesture_name (str): 左手手势的名称。None表示跳过左手。
|
|
112
|
+
r_gesture_name (str): 右手手势的名称。None表示跳过右手。
|
|
113
|
+
|
|
114
|
+
Returns:
|
|
115
|
+
bool: 如果手势命令发送成功返回True,否则返回False。
|
|
116
|
+
|
|
117
|
+
Note:
|
|
118
|
+
手势示例:'fist'、'ok'、'thumbs_up'、'666'等...
|
|
119
|
+
"""
|
|
120
|
+
gesture = []
|
|
121
|
+
if l_gesture_name is not None:
|
|
122
|
+
gesture.append({'gesture_name':l_gesture_name, 'hand_side':EndEffectorSide.LEFT})
|
|
123
|
+
self.dex_hand_control.make_gestures(gesture)
|
|
124
|
+
if r_gesture_name is not None:
|
|
125
|
+
gesture.append({'gesture_name':r_gesture_name, 'hand_side':EndEffectorSide.RIGHT})
|
|
126
|
+
self.dex_hand_control.make_gestures(gesture)
|
|
127
|
+
return True
|
|
128
|
+
def get_gesture_names(self)->list:
|
|
129
|
+
"""获取所有手势的名称。
|
|
130
|
+
|
|
131
|
+
Returns:
|
|
132
|
+
list: 手势名称列表。
|
|
133
|
+
例如:['fist', 'ok', 'thumbs_up', '666', 'number_1', 'number_2', 'number_3', ... ], 如果没有手势则返回 None。
|
|
134
|
+
"""
|
|
135
|
+
return self.dex_hand_control.get_gesture_names()
|
|
136
|
+
|
|
137
|
+
def get_state(self)->Tuple[EndEffectorState, EndEffectorState]:
|
|
138
|
+
"""获取灵巧手的状态。
|
|
139
|
+
|
|
140
|
+
Returns:
|
|
141
|
+
Tuple[EndEffectorState, EndEffectorState]: 灵巧手的状态。
|
|
142
|
+
"""
|
|
143
|
+
return self._rb_state.eef_state
|
|
144
|
+
|
|
145
|
+
def get_position(self)->Tuple[list, list]:
|
|
146
|
+
"""获取灵巧手的位置。
|
|
147
|
+
|
|
148
|
+
Returns:
|
|
149
|
+
Tuple[list, list]: 灵巧手的位置。
|
|
150
|
+
"""
|
|
151
|
+
state = self._rb_state.eef_state
|
|
152
|
+
return (state[0].position, state[1].position)
|
|
153
|
+
|
|
154
|
+
def get_velocity(self)->Tuple[list, list]:
|
|
155
|
+
"""获取灵巧手的速度。
|
|
156
|
+
|
|
157
|
+
Returns:
|
|
158
|
+
Tuple[list, list]: 灵巧手的速度。
|
|
159
|
+
"""
|
|
160
|
+
state = self._rb_state.eef_state
|
|
161
|
+
return (state[0].velocity, state[1].velocity)
|
|
162
|
+
|
|
163
|
+
def get_effort(self)->Tuple[list, list]:
|
|
164
|
+
"""获取灵巧手的力。
|
|
165
|
+
|
|
166
|
+
Returns:
|
|
167
|
+
Tuple[list, list]: 灵巧手的力。
|
|
168
|
+
|
|
169
|
+
Note:
|
|
170
|
+
每个手指的范围为0 ~ 100。表示最大电机电流的分数,绝对数值。
|
|
171
|
+
最大电机电流为600mA,换句话说,100。
|
|
172
|
+
"""
|
|
173
|
+
state = self._rb_state.eef_state
|
|
174
|
+
return (state[0].effort, state[1].effort)
|
|
175
|
+
|
|
176
|
+
def get_grasping_state(self)->Tuple[EndEffectorState.GraspingState, EndEffectorState.GraspingState]:
|
|
177
|
+
"""获取灵巧手的抓取状态。
|
|
178
|
+
|
|
179
|
+
Note:
|
|
180
|
+
该功能尚未实现。
|
|
181
|
+
|
|
182
|
+
Returns:
|
|
183
|
+
Tuple[EndEffectorState.GraspingState, EndEffectorState.GraspingState]: 灵巧手的抓取状态。
|
|
184
|
+
"""
|
|
185
|
+
raise NotImplementedError("This function is not implemented yet")
|
|
186
|
+
|
|
187
|
+
|
|
188
|
+
class TouchDexterousHand(DexterousHand):
|
|
189
|
+
"""触觉灵巧手控制类,继承自普通灵巧手控制类,可调用普通灵巧手控制类中的所有方法"""
|
|
190
|
+
def __init__(self):
|
|
191
|
+
super().__init__()
|
|
192
|
+
|
|
193
|
+
def get_touch_state(self)-> Tuple[KuavoDexHandTouchState, KuavoDexHandTouchState]:
|
|
194
|
+
"""获取灵巧手的触觉状态。
|
|
195
|
+
|
|
196
|
+
Warning:
|
|
197
|
+
该功能仅在触觉灵巧手上可用。
|
|
198
|
+
|
|
199
|
+
Returns:
|
|
200
|
+
Tuple[KuavoDexHandTouchState, KuavoDexHandTouchState]
|
|
201
|
+
"""
|
|
202
|
+
return self._rb_state.eef_state.state
|
|
203
|
+
|
|
204
|
+
def get_dexhand_gesture_state(self)->bool:
|
|
205
|
+
"""获取机器人灵巧手势的当前状态。
|
|
206
|
+
|
|
207
|
+
Returns:
|
|
208
|
+
bool: 如果机器人灵巧手势正在执行返回True,否则返回False。
|
|
209
|
+
"""
|
|
210
|
+
return self._rb_state._srv_get_dexhand_gesture_state()
|
|
211
|
+
|
|
212
|
+
def make_gesture_sync(self, l_gesture_name: str, r_gesture_name: str, timeout:float=5.0)->bool:
|
|
213
|
+
"""为双手做预定义的手势(同步等待完成)。
|
|
214
|
+
|
|
215
|
+
Args:
|
|
216
|
+
l_gesture_name (str): 左手手势的名称。None表示跳过左手。
|
|
217
|
+
r_gesture_name (str): 右手手势的名称。None表示跳过右手。
|
|
218
|
+
timeout (float, optional): 手势超时时间。默认为5.0秒。
|
|
219
|
+
|
|
220
|
+
Returns:
|
|
221
|
+
bool: 如果手势执行成功返回True,否则返回False。
|
|
222
|
+
"""
|
|
223
|
+
gesture = []
|
|
224
|
+
if l_gesture_name is not None:
|
|
225
|
+
gesture.append({'gesture_name':l_gesture_name, 'hand_side':EndEffectorSide.LEFT})
|
|
226
|
+
if r_gesture_name is not None:
|
|
227
|
+
gesture.append({'gesture_name':r_gesture_name, 'hand_side':EndEffectorSide.RIGHT})
|
|
228
|
+
self.dex_hand_control.make_gestures(gesture)
|
|
229
|
+
start_time = time.time()
|
|
230
|
+
while time.time() - start_time < timeout:
|
|
231
|
+
if self.get_dexhand_gesture_state() == True:
|
|
232
|
+
break;
|
|
233
|
+
time.sleep(0.1)
|
|
234
|
+
while time.time() - start_time < timeout:
|
|
235
|
+
if self.get_dexhand_gesture_state() == False:
|
|
236
|
+
return True
|
|
237
|
+
time.sleep(0.1)
|
|
238
|
+
return False
|