kuavo-humanoid-sdk 1.2.1b3290__20250912184757-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 +561 -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.1b3290.dist-info/METADATA +296 -0
- kuavo_humanoid_sdk-1.2.1b3290.dist-info/RECORD +186 -0
- kuavo_humanoid_sdk-1.2.1b3290.dist-info/WHEEL +6 -0
- kuavo_humanoid_sdk-1.2.1b3290.dist-info/top_level.txt +1 -0
|
@@ -0,0 +1,1325 @@
|
|
|
1
|
+
import time
|
|
2
|
+
import math
|
|
3
|
+
from kuavo_humanoid_sdk.kuavo_strategy.kuavo_strategy import KuavoRobotStrategyBase
|
|
4
|
+
from kuavo_humanoid_sdk.interfaces.data_types import KuavoPose
|
|
5
|
+
from kuavo_humanoid_sdk.interfaces.data_types import KuavoManipulationMpcFrame, KuavoManipulationMpcCtrlMode, KuavoManipulationMpcControlFlow
|
|
6
|
+
from kuavo_humanoid_sdk.interfaces.data_types import EndEffectorSide
|
|
7
|
+
from kuavo_humanoid_sdk.interfaces.data_types import AprilTagData, HomogeneousMatrix, PoseQuaternion
|
|
8
|
+
from kuavo_humanoid_sdk import KuavoRobot, KuavoRobotState, KuavoRobotTools, KuavoRobotVision
|
|
9
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
10
|
+
from dataclasses import dataclass
|
|
11
|
+
from typing import Tuple
|
|
12
|
+
import numpy as np
|
|
13
|
+
from scipy.spatial.transform import Rotation as R
|
|
14
|
+
|
|
15
|
+
class KuavoGraspBoxUtils:
|
|
16
|
+
@staticmethod
|
|
17
|
+
def extract_yaw_from_quaternion(quaternion: Tuple[float, float, float, float])-> float:
|
|
18
|
+
"""从四元数中提取yaw角
|
|
19
|
+
|
|
20
|
+
Args:
|
|
21
|
+
quaternion: 四元数 (x, y, z, w)
|
|
22
|
+
|
|
23
|
+
Returns:
|
|
24
|
+
float: yaw角(弧度)
|
|
25
|
+
"""
|
|
26
|
+
if not quaternion or len(quaternion) != 4:
|
|
27
|
+
SDKLogger.error("无法获取有效的四元数")
|
|
28
|
+
return 0.0
|
|
29
|
+
|
|
30
|
+
# 计算yaw角 (围绕z轴的旋转)
|
|
31
|
+
# 四元数到欧拉角的简化计算,仅提取yaw
|
|
32
|
+
x, y, z, w = quaternion
|
|
33
|
+
yaw = math.atan2(2.0 * (w * z + x * y), 1.0 - 2.0 * (y * y + z * z))
|
|
34
|
+
return yaw
|
|
35
|
+
|
|
36
|
+
@staticmethod
|
|
37
|
+
def util_euler_to_quat(euler):
|
|
38
|
+
# x, y, z, w
|
|
39
|
+
"""将欧拉角转换为四元数"""
|
|
40
|
+
quat = R.from_euler('xyz', euler, degrees=False).as_quat()
|
|
41
|
+
return [quat[0], quat[1], quat[2], quat[3]]
|
|
42
|
+
|
|
43
|
+
@staticmethod
|
|
44
|
+
def extract_tag_pose(tag_info)-> KuavoPose:
|
|
45
|
+
if (tag_info is not None and isinstance(tag_info, dict) and
|
|
46
|
+
'poses' in tag_info and len(tag_info['poses']) > 0):
|
|
47
|
+
tag_pose = KuavoPose(
|
|
48
|
+
position=(tag_info['poses'][0].position.x,
|
|
49
|
+
tag_info['poses'][0].position.y,
|
|
50
|
+
tag_info['poses'][0].position.z),
|
|
51
|
+
orientation=(tag_info['poses'][0].orientation.x,
|
|
52
|
+
tag_info['poses'][0].orientation.y,
|
|
53
|
+
tag_info['poses'][0].orientation.z,
|
|
54
|
+
tag_info['poses'][0].orientation.w)
|
|
55
|
+
)
|
|
56
|
+
return tag_pose
|
|
57
|
+
else:
|
|
58
|
+
raise ValueError(f"未找到 AprilTag ID 为 {tag_info['id']} 的位姿信息, 无法创建 BoxInfo 实例")
|
|
59
|
+
|
|
60
|
+
@staticmethod
|
|
61
|
+
def get_box_world_pose(tag_pose, box_in_tag_xyz):
|
|
62
|
+
"""根据目标信息和目标距离计算目标位姿
|
|
63
|
+
p_wa : tag的世界系下位置
|
|
64
|
+
R_wa : tag的世界系下旋转矩阵
|
|
65
|
+
|
|
66
|
+
注意: box的朝向默认和tag的朝向一致
|
|
67
|
+
xyz轴上可以有平移
|
|
68
|
+
注意看好实际中tag的轴朝向
|
|
69
|
+
"""
|
|
70
|
+
pose = KuavoGraspBoxUtils.extract_tag_pose(tag_pose)
|
|
71
|
+
p_wa = np.array([pose.position[0], pose.position[1], pose.position[2]])
|
|
72
|
+
quat_wa = np.array([pose.orientation[0], pose.orientation[1], pose.orientation[2], pose.orientation[3]]) # x,y,z,w
|
|
73
|
+
R_wa = R.from_quat(quat_wa).as_matrix()
|
|
74
|
+
|
|
75
|
+
p_at = np.array(box_in_tag_xyz, np.float32)
|
|
76
|
+
tag_z_uni = np.array([0, 0, 1], np.float32) # tag的z轴朝向
|
|
77
|
+
p_z_w = R_wa @ tag_z_uni # tag的z轴在世界系下的朝向
|
|
78
|
+
|
|
79
|
+
SDKLogger.debug(f'---------------- p_z_w {p_z_w}')
|
|
80
|
+
yaw = math.atan2(p_z_w[1], p_z_w[0])
|
|
81
|
+
yaw += math.pi
|
|
82
|
+
yaw = KuavoGraspBoxUtils.util_cast_to_pi(yaw)
|
|
83
|
+
|
|
84
|
+
SDKLogger.debug(f'---------------- yaw {yaw}')
|
|
85
|
+
|
|
86
|
+
p_at_w = R_wa @ p_at
|
|
87
|
+
p_wt = p_wa + p_at_w
|
|
88
|
+
|
|
89
|
+
return p_wt, yaw
|
|
90
|
+
|
|
91
|
+
def util_cast_to_pi(yaw):
|
|
92
|
+
while yaw > math.pi:
|
|
93
|
+
yaw -= 2 * math.pi
|
|
94
|
+
while yaw < -math.pi:
|
|
95
|
+
yaw += 2 * math.pi
|
|
96
|
+
return yaw
|
|
97
|
+
|
|
98
|
+
@dataclass
|
|
99
|
+
class BoxInfo:
|
|
100
|
+
"""箱子信息数据类
|
|
101
|
+
|
|
102
|
+
描述箱子的位置、尺寸和质量信息,用于箱子抓取策略
|
|
103
|
+
|
|
104
|
+
Attributes:
|
|
105
|
+
pose (KuavoPose): 箱子的位姿信息
|
|
106
|
+
size (Tuple[float, float, float]): 箱子的尺寸 ( 宽, 长, 高) 单位: 米
|
|
107
|
+
mass (float): 箱子的质量 单位: 千克
|
|
108
|
+
"""
|
|
109
|
+
pose: KuavoPose
|
|
110
|
+
size: Tuple[float, float, float] = (0.3, 0.4, 0.22) # 默认箱子尺寸
|
|
111
|
+
mass: float = 1.5 # 默认箱子质量(kg)
|
|
112
|
+
|
|
113
|
+
def __init__(self, pose: KuavoPose = None, size: Tuple[float, float, float] = (0.3, 0.4, 0.22), mass: float = 2.0):
|
|
114
|
+
"""初始化箱子信息
|
|
115
|
+
|
|
116
|
+
Args:
|
|
117
|
+
pose (KuavoPose, optional): 箱子的位姿信息. 默认为 None
|
|
118
|
+
size (Tuple[float, float, float], optional): 箱子尺寸(长,宽,高). 默认为 (0.3, 0.4, 0.22)
|
|
119
|
+
mass (float, optional): 箱子质量(kg). 默认为 2.0
|
|
120
|
+
"""
|
|
121
|
+
self.pose = pose
|
|
122
|
+
self.size = size
|
|
123
|
+
self.mass = mass
|
|
124
|
+
|
|
125
|
+
@classmethod
|
|
126
|
+
def from_apriltag(cls, tag_info: dict, xyz_offset: Tuple[float, float, float] = (0.0, 0.0, 0.0), size: Tuple[float, float, float] = (0.4, 0.3, 0.22), mass: float = 2.0):
|
|
127
|
+
"""从粘贴在箱子正面的 AprilTag 信息创建 BoxInfo 实例
|
|
128
|
+
|
|
129
|
+
Warning:
|
|
130
|
+
必须正确粘贴 AprilTag,AprilTag 朝向请参考: https://chev.me/arucogen/
|
|
131
|
+
|
|
132
|
+
错误的粘贴方向会导致箱子位姿错乱。
|
|
133
|
+
|
|
134
|
+
Args:
|
|
135
|
+
tag_info (dict): 从 :meth:`KuavoRobotVision.get_data_by_id_from_odom` 获取的 AprilTag 信息
|
|
136
|
+
xyz_offset (Tuple[float, float, float], optional): 相对与 AprilTag中心点的偏移量(右手坐标系) \n
|
|
137
|
+
例如:\n
|
|
138
|
+
1. 箱子粘贴在货架上,需要把箱子放下距离货架的高度 -0.5m 则 xyz_offset=(size[1]/2, 0.0, -0.5) \n
|
|
139
|
+
2. 箱子粘贴在箱子正面,为了得到箱子中心点,因此偏移量为箱子宽度的一半 则 xyz_offset=(size[1]/2, 0.0, 0.0) \n
|
|
140
|
+
size (Tuple[float, float, float], optional): 箱子尺寸(长,宽,高). 默认为 (0.4, 0.3, 0.22) \n
|
|
141
|
+
mass (float, optional): 箱子质量(kg). 默认为 2.0
|
|
142
|
+
|
|
143
|
+
Returns:
|
|
144
|
+
BoxInfo: 新的 BoxInfo 实例
|
|
145
|
+
"""
|
|
146
|
+
# tag 的右手坐标系: z 轴正方向朝向tag面对的方向,xy为平面坐标系
|
|
147
|
+
box_in_tag_xyz = [-xyz_offset[1], xyz_offset[2], -xyz_offset[0]]
|
|
148
|
+
pos_world, yaw_world = KuavoGraspBoxUtils.get_box_world_pose(tag_info, box_in_tag_xyz=box_in_tag_xyz)
|
|
149
|
+
|
|
150
|
+
pose = KuavoPose(
|
|
151
|
+
position=pos_world,
|
|
152
|
+
orientation=KuavoGraspBoxUtils.util_euler_to_quat([0, 0, yaw_world])
|
|
153
|
+
)
|
|
154
|
+
return cls(pose, size, mass)
|
|
155
|
+
|
|
156
|
+
class KuavoGraspBox(KuavoRobotStrategyBase):
|
|
157
|
+
"""箱子抓取策略类,继承自基础策略类"""
|
|
158
|
+
|
|
159
|
+
def __init__(self, robot:KuavoRobot, robot_state:KuavoRobotState, robot_tools:KuavoRobotTools, robot_vision:KuavoRobotVision):
|
|
160
|
+
"""初始化箱子抓取策略类
|
|
161
|
+
|
|
162
|
+
Args:
|
|
163
|
+
robot: KuavoRobot实例
|
|
164
|
+
robot_state: KuavoRobotState实例
|
|
165
|
+
robot_tools: KuavoRobotTools实例
|
|
166
|
+
robot_vision: KuavoRobotVision实例
|
|
167
|
+
"""
|
|
168
|
+
super().__init__(robot, robot_state, robot_tools, robot_vision)
|
|
169
|
+
|
|
170
|
+
# 箱子抓取相关的配置参数
|
|
171
|
+
self.search_timeout = 20.0 # 搜索超时时间(秒)
|
|
172
|
+
self.approach_timeout = 30.0 # 接近超时时间(秒)
|
|
173
|
+
self.grasp_height_offset = 0.15 # 抓取高度偏移量(米)
|
|
174
|
+
self.grasp_horizontal_offset = -0.20 # 手指与箱子表面的偏移量,取反为远离箱子 | 取正为靠近箱子
|
|
175
|
+
# 存放头部寻找AprilTag的目标,初始化为异常ID 9999
|
|
176
|
+
self.head_find_target_current_info_pose = AprilTagData(
|
|
177
|
+
id=[9999], # 异常ID
|
|
178
|
+
size=[0.0], # 默认尺寸为0
|
|
179
|
+
pose=[PoseQuaternion(
|
|
180
|
+
position=(0.0, 0.0, 0.0), # 默认零位置
|
|
181
|
+
orientation=(0.0, 0.0, 0.0, 1.0) # 默认朝向(无旋转)
|
|
182
|
+
)]
|
|
183
|
+
)
|
|
184
|
+
# 新增安全参数
|
|
185
|
+
self.orientation_safety_threshold = math.radians(20) # 20度安全阈值
|
|
186
|
+
# 新增位置安全参数
|
|
187
|
+
self.workspace_radius = 0.92 # 工作空间半径0.92米
|
|
188
|
+
|
|
189
|
+
def head_find_target(self, target_info:AprilTagData, max_search_time=None, search_pattern="rotate_head", **kwargs):
|
|
190
|
+
"""使用头部旋转寻找AprilTag目标
|
|
191
|
+
|
|
192
|
+
Args:
|
|
193
|
+
target_info: AprilTag的信息
|
|
194
|
+
max_search_time: 最大搜索时间(秒),如果为None则使用默认值
|
|
195
|
+
search_pattern: 搜索模式,"rotate_head"或"rotate_body"
|
|
196
|
+
|
|
197
|
+
Returns:
|
|
198
|
+
bool: 是否成功找到目标
|
|
199
|
+
|
|
200
|
+
logic:
|
|
201
|
+
1. 判断目标位置是否在机器人FOV(70度视场角)内
|
|
202
|
+
2. 如果不在FOV内且search_pattern为"rotate_body",先旋转机器人身体朝向目标位置
|
|
203
|
+
3. 无论如何都使用头部搜索模式尝试找到目标
|
|
204
|
+
4. 找到apriltag_data_from_odom之后,马上开始头部追踪
|
|
205
|
+
"""
|
|
206
|
+
# 初始目标赋值
|
|
207
|
+
self.head_find_target_current_info_pose = target_info
|
|
208
|
+
|
|
209
|
+
# 设置搜索超时时间
|
|
210
|
+
if max_search_time is None:
|
|
211
|
+
max_search_time = self.search_timeout
|
|
212
|
+
|
|
213
|
+
# 获取需要追踪的目标ID
|
|
214
|
+
target_id = target_info.id[0]
|
|
215
|
+
|
|
216
|
+
if target_id > 9999:
|
|
217
|
+
SDKLogger.error(f"target_id: {target_id} 大于 9999, 无效的AprilTag家族ID")
|
|
218
|
+
return False
|
|
219
|
+
|
|
220
|
+
# 判断目标位置是否在FOV内
|
|
221
|
+
if len(target_info.pose) > 0:
|
|
222
|
+
target_position = target_info.pose[0].position
|
|
223
|
+
robot_position = self.state.robot_position()
|
|
224
|
+
robot_orientation = self.state.robot_orientation()
|
|
225
|
+
|
|
226
|
+
# 计算目标相对于机器人的位置向量
|
|
227
|
+
dx = target_position[0] - robot_position[0]
|
|
228
|
+
dy = target_position[1] - robot_position[1]
|
|
229
|
+
|
|
230
|
+
# 计算目标相对于机器人的角度
|
|
231
|
+
target_angle = math.atan2(dy, dx)
|
|
232
|
+
|
|
233
|
+
# 获取机器人当前朝向的yaw角
|
|
234
|
+
robot_yaw = KuavoGraspBoxUtils.extract_yaw_from_quaternion(robot_orientation)
|
|
235
|
+
|
|
236
|
+
# 计算目标与机器人朝向的角度差
|
|
237
|
+
angle_diff = target_angle - robot_yaw
|
|
238
|
+
# 标准化角度到[-pi, pi]
|
|
239
|
+
while angle_diff > math.pi:
|
|
240
|
+
angle_diff -= 2 * math.pi
|
|
241
|
+
while angle_diff < -math.pi:
|
|
242
|
+
angle_diff += 2 * math.pi
|
|
243
|
+
|
|
244
|
+
# 检查是否在FOV内(70度 = 约1.22弧度)
|
|
245
|
+
FOV_HALF_ANGLE = math.radians(35) # 70度/2 = 35度
|
|
246
|
+
is_in_fov = abs(angle_diff) <= FOV_HALF_ANGLE
|
|
247
|
+
|
|
248
|
+
SDKLogger.debug(f"目标位置: ({target_position[0]:.2f}, {target_position[1]:.2f})")
|
|
249
|
+
SDKLogger.debug(f"机器人位置: ({robot_position[0]:.2f}, {robot_position[1]:.2f})")
|
|
250
|
+
SDKLogger.debug(f"目标角度: {math.degrees(target_angle):.2f}度")
|
|
251
|
+
SDKLogger.debug(f"机器人朝向: {math.degrees(robot_yaw):.2f}度")
|
|
252
|
+
SDKLogger.debug(f"角度差: {math.degrees(angle_diff):.2f}度")
|
|
253
|
+
SDKLogger.debug(f"是否在FOV内: {is_in_fov}")
|
|
254
|
+
|
|
255
|
+
# 如果目标不在FOV内且模式允许旋转身体,先旋转机器人身体
|
|
256
|
+
if not is_in_fov and search_pattern == "rotate_body":
|
|
257
|
+
SDKLogger.info("目标超出FOV,调整机器人朝向...")
|
|
258
|
+
# 调整机器人朝向
|
|
259
|
+
SDKLogger.info(f"开始调整 - 机器人位置: {robot_position}")
|
|
260
|
+
SDKLogger.info(f"开始调整 - 目标角度: {math.degrees(target_angle):.2f}度")
|
|
261
|
+
SDKLogger.info(f"开始调整 - 目标角度: {target_angle}")
|
|
262
|
+
self.robot.control_command_pose_world(
|
|
263
|
+
robot_position[0], # 保持机器人当前x位置
|
|
264
|
+
robot_position[1], # 保持机器人当前y位置
|
|
265
|
+
0.0, # 保持当前z高度
|
|
266
|
+
target_angle # 朝向目标位置 转换为弧度
|
|
267
|
+
)
|
|
268
|
+
|
|
269
|
+
# 等待机器人旋转到位,使用闭环控制替代固定时间等待
|
|
270
|
+
self._wait_for_orientation(target_angle, max_wait_time=10.0, angle_threshold=0.1)
|
|
271
|
+
|
|
272
|
+
# 开始搜索计时
|
|
273
|
+
start_time = time.time()
|
|
274
|
+
found_target = False
|
|
275
|
+
|
|
276
|
+
# 执行头部搜索模式,无论search_pattern是什么
|
|
277
|
+
# 定义头部搜索参数(角度制)
|
|
278
|
+
pitch_angles_deg = [25, -25] # 两档pitch角度:抬头和低头,角度制
|
|
279
|
+
yaw_angles_deg = [-30, -15, 0, 15, 30] # 左右扫描的yaw角度,角度制
|
|
280
|
+
|
|
281
|
+
# 在超时前循环搜索
|
|
282
|
+
while time.time() - start_time < max_search_time and not found_target:
|
|
283
|
+
# 遍历两档pitch角度
|
|
284
|
+
for pitch_deg in pitch_angles_deg:
|
|
285
|
+
# 遍历yaw角度进行左右扫描
|
|
286
|
+
for yaw_deg in yaw_angles_deg:
|
|
287
|
+
# 将角度转换为弧度
|
|
288
|
+
yaw_rad = yaw_deg * 0.0174533 # 度转弧度,math.pi/180
|
|
289
|
+
pitch_rad = pitch_deg * 0.0174533 # 度转弧度
|
|
290
|
+
|
|
291
|
+
# 控制头部旋转(使用弧度)
|
|
292
|
+
self.robot.control_head(yaw=yaw_rad, pitch=pitch_rad)
|
|
293
|
+
# 等待头部移动到位
|
|
294
|
+
time.sleep(0.5)
|
|
295
|
+
|
|
296
|
+
# 检查是否找到目标
|
|
297
|
+
target_data = self.vision.get_data_by_id_from_odom(target_id)
|
|
298
|
+
SDKLogger.debug(f"target_data: {target_data}")
|
|
299
|
+
|
|
300
|
+
if (target_data is not None and isinstance(target_data, dict) and
|
|
301
|
+
'poses' in target_data and len(target_data['poses']) > 0):
|
|
302
|
+
SDKLogger.info(f"Target AprilTag {target_id} found!")
|
|
303
|
+
found_target = True
|
|
304
|
+
# 开始头部追踪
|
|
305
|
+
SDKLogger.info("---- 开始头部追踪 ---- ")
|
|
306
|
+
self.robot.enable_head_tracking(target_id) # self.robot.disable_head_tracking()
|
|
307
|
+
break
|
|
308
|
+
|
|
309
|
+
if found_target:
|
|
310
|
+
break
|
|
311
|
+
|
|
312
|
+
return found_target
|
|
313
|
+
|
|
314
|
+
def _is_orientation_aligned(self, orientation1, orientation2, threshold=0.3):
|
|
315
|
+
"""检查两个朝向是否大致一致
|
|
316
|
+
|
|
317
|
+
Args:
|
|
318
|
+
orientation1: 第一个朝向的四元数
|
|
319
|
+
orientation2: 第二个朝向的四元数
|
|
320
|
+
threshold: 判断为一致的阈值
|
|
321
|
+
|
|
322
|
+
Returns:
|
|
323
|
+
bool: 朝向是否一致
|
|
324
|
+
"""
|
|
325
|
+
# 这里简化实现,实际应用需要进行四元数计算
|
|
326
|
+
# 提取两个朝向的yaw角并比较差异
|
|
327
|
+
yaw1 = KuavoGraspBoxUtils.extract_yaw_from_quaternion(orientation1)
|
|
328
|
+
yaw2 = KuavoGraspBoxUtils.extract_yaw_from_quaternion(orientation2)
|
|
329
|
+
|
|
330
|
+
# 计算角度差异
|
|
331
|
+
diff = abs(yaw1 - yaw2)
|
|
332
|
+
while diff > math.pi:
|
|
333
|
+
diff -= 2 * math.pi
|
|
334
|
+
|
|
335
|
+
return abs(diff) < threshold
|
|
336
|
+
|
|
337
|
+
def _track_target_with_head(self, target_data):
|
|
338
|
+
"""使用头部追踪目标
|
|
339
|
+
|
|
340
|
+
Args:
|
|
341
|
+
target_data: 目标数据,包含位置信息
|
|
342
|
+
"""
|
|
343
|
+
# 从目标数据中提取相对位置
|
|
344
|
+
position = target_data["position"]
|
|
345
|
+
|
|
346
|
+
# 计算目标相对于机器人的方向
|
|
347
|
+
dx = position[0]
|
|
348
|
+
dy = position[1]
|
|
349
|
+
dz = position[2]
|
|
350
|
+
|
|
351
|
+
# 计算yaw和pitch角度来指向目标
|
|
352
|
+
# 简单的反正切计算(结果为弧度)
|
|
353
|
+
yaw_rad = math.atan2(dy, dx)
|
|
354
|
+
distance = math.sqrt(dx*dx + dy*dy)
|
|
355
|
+
pitch_rad = math.atan2(dz, distance)
|
|
356
|
+
|
|
357
|
+
# 限制角度范围(弧度)
|
|
358
|
+
yaw_rad = min(math.radians(80), max(math.radians(-80), yaw_rad)) # 限制在±80度
|
|
359
|
+
pitch_rad = min(math.radians(25), max(math.radians(-25), pitch_rad)) # 限制在±25度
|
|
360
|
+
|
|
361
|
+
# 控制头部指向目标(输入为弧度)
|
|
362
|
+
self.robot.control_head(yaw=yaw_rad, pitch=pitch_rad)
|
|
363
|
+
|
|
364
|
+
def walk_approach_target(self, target_id:int, target_distance=0.5, approach_speed=0.15, **kwargs):
|
|
365
|
+
"""走路接近 ID 为 `target_id` 的 AprilTag 目标
|
|
366
|
+
|
|
367
|
+
Args:
|
|
368
|
+
target_id: 目标 AprilTag ID
|
|
369
|
+
target_distance: 与目标的期望距离(米)
|
|
370
|
+
approach_speed: 接近速度(米/秒)
|
|
371
|
+
|
|
372
|
+
Returns:
|
|
373
|
+
bool: 是否成功接近目标
|
|
374
|
+
"""
|
|
375
|
+
approach_success = False
|
|
376
|
+
start_time = time.time()
|
|
377
|
+
target_data = self.vision.get_data_by_id_from_odom(target_id)
|
|
378
|
+
if target_data is None:
|
|
379
|
+
SDKLogger.error(f"未找到目标ID: {target_id} 的目标数据!")
|
|
380
|
+
return False
|
|
381
|
+
target_pose = target_data["poses"][0]
|
|
382
|
+
SDKLogger.debug(f"target_pose in _approach_target: {target_pose}")
|
|
383
|
+
while not approach_success:
|
|
384
|
+
approach_success = self._approach_target(target_pose, target_distance, approach_speed, **kwargs)
|
|
385
|
+
time.sleep(1)
|
|
386
|
+
time_cost = time.time() - start_time
|
|
387
|
+
SDKLogger.debug(f"walking approach target..., time_cost: {time_cost:.2f}秒.")
|
|
388
|
+
return approach_success
|
|
389
|
+
|
|
390
|
+
def _approach_target(self, target_pose, target_distance=0.5, approach_speed=0.15, **kwargs):
|
|
391
|
+
"""根据目标信息和目标距离计算目标位姿
|
|
392
|
+
|
|
393
|
+
Args:
|
|
394
|
+
target_pose: 目标位姿信息
|
|
395
|
+
target_distance: 与目标的期望距离(米)
|
|
396
|
+
approach_speed: 接近速度(米/秒)
|
|
397
|
+
|
|
398
|
+
Returns:
|
|
399
|
+
bool: 是否成功接近目标
|
|
400
|
+
"""
|
|
401
|
+
p_wa = np.array([target_pose.position.x, target_pose.position.y, target_pose.position.z])
|
|
402
|
+
quat_wa = np.array([target_pose.orientation.x, target_pose.orientation.y, target_pose.orientation.z, target_pose.orientation.w]) # x,y,z,w
|
|
403
|
+
R_wa = R.from_quat(quat_wa).as_matrix()
|
|
404
|
+
def get_target_pose_by_distance(p_wa, R_wa, target_distance=0.5):
|
|
405
|
+
"""根据目标信息和目标距离计算目标位姿"""
|
|
406
|
+
p_at = np.array([0, 0, target_distance], np.float32)
|
|
407
|
+
p_at_w = R_wa @ p_at
|
|
408
|
+
p_wt = p_wa + p_at_w
|
|
409
|
+
yaw = math.atan2(p_at_w[1], p_at_w[0])
|
|
410
|
+
yaw += math.pi
|
|
411
|
+
while yaw > math.pi:
|
|
412
|
+
yaw -= 2 * math.pi
|
|
413
|
+
while yaw < -math.pi:
|
|
414
|
+
yaw += 2 * math.pi
|
|
415
|
+
return p_wt, yaw
|
|
416
|
+
|
|
417
|
+
p_wt, angle = get_target_pose_by_distance(p_wa, R_wa, target_distance)
|
|
418
|
+
self.robot.control_command_pose_world(p_wt[0], p_wt[1], 0, angle)
|
|
419
|
+
|
|
420
|
+
yaw_reached = self._yaw_check(angle)
|
|
421
|
+
pos_reached = self._pos_check(p_wt)
|
|
422
|
+
stance_check = (self.state == 'stance')
|
|
423
|
+
SDKLogger.debug(f"yaw_reached: {yaw_reached}, pos_reached: {pos_reached}, stance_check: {stance_check}")
|
|
424
|
+
return yaw_reached and pos_reached # and stance_check
|
|
425
|
+
|
|
426
|
+
def _check_target_reachable(self, target_info:BoxInfo) -> bool:
|
|
427
|
+
"""检查目标位置是否在机器人手臂可达区域内
|
|
428
|
+
|
|
429
|
+
Args:
|
|
430
|
+
target_info: 目标信息,包含位置、尺寸等
|
|
431
|
+
|
|
432
|
+
Returns:
|
|
433
|
+
bool: 目标是否可达
|
|
434
|
+
|
|
435
|
+
Note:
|
|
436
|
+
此函数为预留接口,待实现以下功能:
|
|
437
|
+
1. 获取机器人当前位姿
|
|
438
|
+
2. 获取机器人手臂工作空间范围
|
|
439
|
+
3. 检查目标位置是否在工作空间内
|
|
440
|
+
"""
|
|
441
|
+
# TODO: 实现可达性检查逻辑
|
|
442
|
+
# 1. 获取机器人当前位姿
|
|
443
|
+
# robot_pose = self.state.robot_pose()
|
|
444
|
+
|
|
445
|
+
# 2. 获取机器人手臂工作空间范围
|
|
446
|
+
# workspace_range = self.robot.get_arm_workspace()
|
|
447
|
+
|
|
448
|
+
# 3. 检查目标位置是否在工作空间内
|
|
449
|
+
# target_position = target_info.pose.position
|
|
450
|
+
# is_in_workspace = check_position_in_workspace(target_position, workspace_range)
|
|
451
|
+
|
|
452
|
+
# 临时返回True,等待接口实现后修改
|
|
453
|
+
return True
|
|
454
|
+
|
|
455
|
+
# 添加四元数乘法函数
|
|
456
|
+
@staticmethod
|
|
457
|
+
def _quaternion_multiply(q1, q2):
|
|
458
|
+
"""
|
|
459
|
+
四元数乘法,用于组合旋转
|
|
460
|
+
q1, q2: 两个四元数 [x, y, z, w]
|
|
461
|
+
"""
|
|
462
|
+
x1, y1, z1, w1 = q1
|
|
463
|
+
x2, y2, z2, w2 = q2
|
|
464
|
+
|
|
465
|
+
w = w1 * w2 - x1 * x2 - y1 * y2 - z1 * z2
|
|
466
|
+
x = w1 * x2 + x1 * w2 + y1 * z2 - z1 * y2
|
|
467
|
+
y = w1 * y2 + y1 * w2 + z1 * x2 - x1 * z2
|
|
468
|
+
z = w1 * z2 + z1 * w2 + x1 * y2 - y1 * x2
|
|
469
|
+
|
|
470
|
+
return [x, y, z, w]
|
|
471
|
+
|
|
472
|
+
def _quaternion_rotate(self, q, v):
|
|
473
|
+
"""
|
|
474
|
+
使用四元数旋转向量
|
|
475
|
+
q: 四元数 [x, y, z, w]
|
|
476
|
+
v: 三维向量 [x, y, z]
|
|
477
|
+
"""
|
|
478
|
+
q = np.array(q)
|
|
479
|
+
v = np.array(v)
|
|
480
|
+
q_conj = np.array([-q[0], -q[1], -q[2], q[3]])
|
|
481
|
+
v_quat = np.array([v[0], v[1], v[2], 0.0])
|
|
482
|
+
rotated = KuavoGraspBox._quaternion_multiply(KuavoGraspBox._quaternion_multiply(q, v_quat), q_conj)
|
|
483
|
+
return rotated[:3]
|
|
484
|
+
|
|
485
|
+
# 坐标转换函数
|
|
486
|
+
def _transform_to_odom(self, pose, transform):
|
|
487
|
+
"""将姿态从base_link转换到odom坐标系"""
|
|
488
|
+
# 位置转换(显式转换为numpy数组)
|
|
489
|
+
pos_base = np.array(pose.position)
|
|
490
|
+
transform_pos = np.array(transform.position)
|
|
491
|
+
|
|
492
|
+
# 使用显式类型转换确保运算正确
|
|
493
|
+
rotated_pos = self._quaternion_rotate(
|
|
494
|
+
np.array(transform.orientation), # 确保四元数是numpy数组
|
|
495
|
+
pos_base
|
|
496
|
+
)
|
|
497
|
+
pos_odom = transform_pos + rotated_pos
|
|
498
|
+
|
|
499
|
+
# 姿态转换(显式转换为numpy数组)
|
|
500
|
+
transform_quat = np.array(transform.orientation)
|
|
501
|
+
pose_quat = np.array(pose.orientation)
|
|
502
|
+
rot_odom = KuavoGraspBox._quaternion_multiply(transform_quat, pose_quat)
|
|
503
|
+
|
|
504
|
+
# 转换为Python原生类型
|
|
505
|
+
return KuavoPose(
|
|
506
|
+
position=tuple(pos_odom.tolist()),
|
|
507
|
+
orientation=rot_odom # rot_odom 已经是列表,不需要转换
|
|
508
|
+
)
|
|
509
|
+
|
|
510
|
+
def _transform_to_base_link(self, pose):
|
|
511
|
+
"""将姿态从odom坐标系转换到base_link坐标系
|
|
512
|
+
|
|
513
|
+
Args:
|
|
514
|
+
pose: KuavoPose类型,表示odom坐标系下的位姿
|
|
515
|
+
|
|
516
|
+
Returns:
|
|
517
|
+
KuavoPose: base_link坐标系下的位姿
|
|
518
|
+
"""
|
|
519
|
+
try:
|
|
520
|
+
# 获取odom到base_link的变换
|
|
521
|
+
odom_to_base = self.tools.get_tf_transform("base_link", "odom")
|
|
522
|
+
|
|
523
|
+
# 位置转换
|
|
524
|
+
pos_odom = np.array(pose.position)
|
|
525
|
+
odom_pos = np.array(odom_to_base.position)
|
|
526
|
+
|
|
527
|
+
# 使用四元数旋转
|
|
528
|
+
rotated_pos = self._quaternion_rotate(
|
|
529
|
+
np.array(odom_to_base.orientation),
|
|
530
|
+
pos_odom
|
|
531
|
+
)
|
|
532
|
+
pos_base = rotated_pos + odom_pos
|
|
533
|
+
|
|
534
|
+
# 姿态转换
|
|
535
|
+
odom_quat = np.array(odom_to_base.orientation)
|
|
536
|
+
pose_quat = np.array(pose.orientation)
|
|
537
|
+
# 注意:这里需要先旋转odom_quat的共轭,再与pose_quat相乘
|
|
538
|
+
odom_quat_conj = np.array([-odom_quat[0], -odom_quat[1], -odom_quat[2], odom_quat[3]])
|
|
539
|
+
rot_base = KuavoGraspBox._quaternion_multiply(odom_quat_conj, pose_quat)
|
|
540
|
+
|
|
541
|
+
# 返回转换后的位姿
|
|
542
|
+
return KuavoPose(
|
|
543
|
+
position=tuple(pos_base.tolist()),
|
|
544
|
+
orientation=rot_base
|
|
545
|
+
)
|
|
546
|
+
except Exception as e:
|
|
547
|
+
SDKLogger.error(f"坐标转换出错: {str(e)}")
|
|
548
|
+
return None
|
|
549
|
+
|
|
550
|
+
@staticmethod
|
|
551
|
+
def _interpolate_poses(start_pose, end_pose, num_points=20):
|
|
552
|
+
"""
|
|
553
|
+
在两个笛卡尔空间姿态之间进行三次样条插值
|
|
554
|
+
|
|
555
|
+
Args:
|
|
556
|
+
start_pose: 起始KuavoPose
|
|
557
|
+
end_pose: 终点KuavoPose
|
|
558
|
+
num_points: 插值点数量
|
|
559
|
+
|
|
560
|
+
Returns:
|
|
561
|
+
插值后的KuavoPose列表
|
|
562
|
+
"""
|
|
563
|
+
# 提取位置
|
|
564
|
+
start_pos = np.array(start_pose.position)
|
|
565
|
+
end_pos = np.array(end_pose.position)
|
|
566
|
+
|
|
567
|
+
# 提取四元数
|
|
568
|
+
start_quat = np.array(start_pose.orientation)
|
|
569
|
+
end_quat = np.array(end_pose.orientation)
|
|
570
|
+
|
|
571
|
+
# 确保四元数方向一致(避免绕远路)
|
|
572
|
+
if np.dot(start_quat, end_quat) < 0:
|
|
573
|
+
end_quat = -end_quat
|
|
574
|
+
|
|
575
|
+
# 生成参数t
|
|
576
|
+
t = np.linspace(0, 1, num_points)
|
|
577
|
+
|
|
578
|
+
# 位置插值 - 使用三次样条
|
|
579
|
+
# 为了进行三次样条插值,我们需要在t, x, y, z上分别拟合样条
|
|
580
|
+
|
|
581
|
+
# 四元数插值 - 球面线性插值 (SLERP)
|
|
582
|
+
interp_poses = []
|
|
583
|
+
for i in range(num_points):
|
|
584
|
+
# 位置插值
|
|
585
|
+
pos = start_pos * (1 - t[i]) + end_pos * t[i]
|
|
586
|
+
pos = (pos[0], pos[1], pos[2])
|
|
587
|
+
|
|
588
|
+
# 四元数球面插值
|
|
589
|
+
# 计算四元数之间的夹角
|
|
590
|
+
cos_half_theta = np.dot(start_quat, end_quat)
|
|
591
|
+
cos_half_theta = np.clip(cos_half_theta, -1.0, 1.0) # 确保在有效范围内
|
|
592
|
+
|
|
593
|
+
if abs(cos_half_theta) >= 1.0:
|
|
594
|
+
# 如果四元数几乎相同,直接使用起始四元数
|
|
595
|
+
quat = start_quat
|
|
596
|
+
else:
|
|
597
|
+
half_theta = np.arccos(cos_half_theta)
|
|
598
|
+
sin_half_theta = np.sqrt(1.0 - cos_half_theta * cos_half_theta)
|
|
599
|
+
|
|
600
|
+
# 如果夹角足够大,使用SLERP插值
|
|
601
|
+
if abs(sin_half_theta) < 0.001:
|
|
602
|
+
# 夹角太小,使用线性插值
|
|
603
|
+
quat = start_quat * (1 - t[i]) + end_quat * t[i]
|
|
604
|
+
quat = quat / np.linalg.norm(quat) # 归一化
|
|
605
|
+
else:
|
|
606
|
+
# SLERP公式
|
|
607
|
+
ratio_a = np.sin((1 - t[i]) * half_theta) / sin_half_theta
|
|
608
|
+
ratio_b = np.sin(t[i] * half_theta) / sin_half_theta
|
|
609
|
+
quat = start_quat * ratio_a + end_quat * ratio_b
|
|
610
|
+
quat = quat / np.linalg.norm(quat) # 归一化
|
|
611
|
+
|
|
612
|
+
# 创建新的KuavoPose
|
|
613
|
+
interp_poses.append(KuavoPose(
|
|
614
|
+
position=pos,
|
|
615
|
+
orientation=quat.tolist()
|
|
616
|
+
))
|
|
617
|
+
|
|
618
|
+
return interp_poses
|
|
619
|
+
|
|
620
|
+
def _execute_trajectory(self, left_poses, right_poses, total_time=2.0):
|
|
621
|
+
"""
|
|
622
|
+
执行左右手轨迹
|
|
623
|
+
|
|
624
|
+
Args:
|
|
625
|
+
grasp_strategy: 抓取策略对象
|
|
626
|
+
left_poses: 左手KuavoPose列表
|
|
627
|
+
right_poses: 右手KuavoPose列表
|
|
628
|
+
total_time: 总执行时间(秒)
|
|
629
|
+
"""
|
|
630
|
+
|
|
631
|
+
num_points = min(len(left_poses), len(right_poses))
|
|
632
|
+
time_per_point = total_time / (num_points - 1) if num_points > 1 else total_time
|
|
633
|
+
|
|
634
|
+
for i in range(num_points):
|
|
635
|
+
self.robot.control_robot_end_effector_pose(
|
|
636
|
+
left_pose=left_poses[i],
|
|
637
|
+
right_pose=right_poses[i],
|
|
638
|
+
frame=KuavoManipulationMpcFrame.WorldFrame,
|
|
639
|
+
)
|
|
640
|
+
if i < num_points - 1: # 最后一个点不需要延时
|
|
641
|
+
time.sleep(time_per_point)
|
|
642
|
+
|
|
643
|
+
def _get_target_pose(self, target_info:BoxInfo, traj_type="grasp", **kwargs):
|
|
644
|
+
"""获取起始位置和目标位置
|
|
645
|
+
|
|
646
|
+
Args:
|
|
647
|
+
target_info: 目标信息,包含位置、尺寸等
|
|
648
|
+
traj_type: 轨迹类型:
|
|
649
|
+
- "grasp": 抓取轨迹
|
|
650
|
+
- "lift": 抬起轨迹
|
|
651
|
+
- "place": 放置轨迹
|
|
652
|
+
|
|
653
|
+
Returns:
|
|
654
|
+
tuple: (left_pose_init, right_pose_init, left_pose_target, right_pose_target)
|
|
655
|
+
"""
|
|
656
|
+
# 计算抓取姿态
|
|
657
|
+
box_position = list(target_info.pose.position)
|
|
658
|
+
box_orientation = list(target_info.pose.orientation)
|
|
659
|
+
SDKLogger.debug(f"原始世界坐标系下的位置: {box_position}")
|
|
660
|
+
SDKLogger.debug(f"原始世界坐标系下的姿态: {box_orientation}")
|
|
661
|
+
|
|
662
|
+
box_size = target_info.size # (length, width, height)
|
|
663
|
+
|
|
664
|
+
if box_position is None:
|
|
665
|
+
return None, None, None, None
|
|
666
|
+
else:
|
|
667
|
+
# 将四元数转换为yaw角
|
|
668
|
+
qx, qy, qz, qw = box_orientation
|
|
669
|
+
box_yaw = np.arctan2(2*(qw*qz + qx*qy), qw**2 + qx**2 - qy**2 - qz**2)
|
|
670
|
+
|
|
671
|
+
# 计算箱子侧面的位置(基于box_yaw旋转)
|
|
672
|
+
half_width = box_size[1] / 2.0
|
|
673
|
+
grasp_height = box_position[2] # 通常在箱子高度的中间位置抓取
|
|
674
|
+
|
|
675
|
+
right_hand_position = ( # left_hand_position
|
|
676
|
+
box_position[0] + half_width * np.sin(box_yaw),
|
|
677
|
+
box_position[1] - half_width * np.cos(box_yaw),
|
|
678
|
+
grasp_height
|
|
679
|
+
)
|
|
680
|
+
left_hand_position = ( # right_hand_position
|
|
681
|
+
box_position[0] - half_width * np.sin(box_yaw),
|
|
682
|
+
box_position[1] + half_width * np.cos(box_yaw),
|
|
683
|
+
grasp_height
|
|
684
|
+
)
|
|
685
|
+
# 基础抓取姿态(只考虑roll和pitch)
|
|
686
|
+
base_left_orientation = [0.06163, -0.70442, -0.06163, 0.70442] # roll 10度 Pitch -90度
|
|
687
|
+
base_right_orientation = [-0.06163, -0.70442, 0.06163, 0.70442] # roll -10度 Pitch -90度
|
|
688
|
+
|
|
689
|
+
# 创建yaw旋转的四元数
|
|
690
|
+
yaw_quat = [0, 0, np.sin(box_yaw/2), np.cos(box_yaw/2)]
|
|
691
|
+
|
|
692
|
+
# 合并四元数:结合基础姿态和yaw旋转
|
|
693
|
+
left_grasp_orientation = KuavoGraspBox._quaternion_multiply(yaw_quat, base_left_orientation)
|
|
694
|
+
right_grasp_orientation = KuavoGraspBox._quaternion_multiply(yaw_quat, base_right_orientation)
|
|
695
|
+
|
|
696
|
+
# 计算基础姿态
|
|
697
|
+
# 1. 贴合箱子侧面左右手的末端位姿
|
|
698
|
+
left_hand_pose = KuavoPose(
|
|
699
|
+
position=left_hand_position,
|
|
700
|
+
orientation=left_grasp_orientation
|
|
701
|
+
)
|
|
702
|
+
right_hand_pose = KuavoPose(
|
|
703
|
+
position=right_hand_position,
|
|
704
|
+
orientation=right_grasp_orientation
|
|
705
|
+
)
|
|
706
|
+
|
|
707
|
+
# 2. 预抓取姿态
|
|
708
|
+
left_pre_grasp = KuavoPose(
|
|
709
|
+
position=(
|
|
710
|
+
left_hand_pose.position[0] + self.grasp_horizontal_offset * np.sin(box_yaw),
|
|
711
|
+
left_hand_pose.position[1] - self.grasp_horizontal_offset * np.cos(box_yaw),
|
|
712
|
+
left_hand_pose.position[2]
|
|
713
|
+
),
|
|
714
|
+
orientation=left_hand_pose.orientation
|
|
715
|
+
)
|
|
716
|
+
|
|
717
|
+
right_pre_grasp = KuavoPose(
|
|
718
|
+
position=(
|
|
719
|
+
right_hand_pose.position[0] - self.grasp_horizontal_offset * np.sin(box_yaw),
|
|
720
|
+
right_hand_pose.position[1] + self.grasp_horizontal_offset * np.cos(box_yaw),
|
|
721
|
+
right_hand_pose.position[2]
|
|
722
|
+
),
|
|
723
|
+
orientation=right_hand_pose.orientation
|
|
724
|
+
)
|
|
725
|
+
|
|
726
|
+
# 3. 抓取姿态(不只是贴合箱子,抓紧)
|
|
727
|
+
left_grasp = KuavoPose(
|
|
728
|
+
position=(
|
|
729
|
+
left_hand_pose.position[0], # + 0.05 * np.sin(box_yaw),
|
|
730
|
+
left_hand_pose.position[1], # - 0.05 * np.cos(box_yaw),
|
|
731
|
+
left_hand_pose.position[2]
|
|
732
|
+
),
|
|
733
|
+
orientation=left_hand_pose.orientation
|
|
734
|
+
)
|
|
735
|
+
|
|
736
|
+
right_grasp = KuavoPose(
|
|
737
|
+
position=(
|
|
738
|
+
right_hand_pose.position[0], # - 0.05 * np.sin(box_yaw),
|
|
739
|
+
right_hand_pose.position[1], # + 0.05 * np.cos(box_yaw),
|
|
740
|
+
right_hand_pose.position[2]
|
|
741
|
+
),
|
|
742
|
+
orientation=right_hand_pose.orientation
|
|
743
|
+
)
|
|
744
|
+
|
|
745
|
+
# 4. 抬起姿态(抓取后向上)
|
|
746
|
+
left_lift = KuavoPose(
|
|
747
|
+
position=(
|
|
748
|
+
left_grasp.position[0],
|
|
749
|
+
left_grasp.position[1],
|
|
750
|
+
left_grasp.position[2] + self.grasp_height_offset
|
|
751
|
+
),
|
|
752
|
+
orientation=left_grasp.orientation
|
|
753
|
+
)
|
|
754
|
+
|
|
755
|
+
right_lift = KuavoPose(
|
|
756
|
+
position=(
|
|
757
|
+
right_grasp.position[0],
|
|
758
|
+
right_grasp.position[1],
|
|
759
|
+
right_grasp.position[2] + self.grasp_height_offset
|
|
760
|
+
),
|
|
761
|
+
orientation=right_grasp.orientation
|
|
762
|
+
)
|
|
763
|
+
|
|
764
|
+
# 5. 收臂姿态
|
|
765
|
+
# 定义base_link坐标系下的目标姿态
|
|
766
|
+
# l_arm_base_target_pose = KuavoPose(
|
|
767
|
+
# position=(0.499, 0.121, 0.370),
|
|
768
|
+
# orientation=[-0.107, -0.758, 0.063, 0.641]
|
|
769
|
+
# )
|
|
770
|
+
# r_arm_base_target_pose = KuavoPose(
|
|
771
|
+
# position=(0.499, -0.121, 0.370),
|
|
772
|
+
# orientation=[-0.026, -0.765, 0.049, 0.642]
|
|
773
|
+
# )
|
|
774
|
+
l_arm_base_target_pose = KuavoPose(
|
|
775
|
+
position=(0.4, half_width, 0.370),
|
|
776
|
+
orientation=[-0.107, -0.758, 0.063, 0.641]
|
|
777
|
+
)
|
|
778
|
+
r_arm_base_target_pose = KuavoPose(
|
|
779
|
+
position=(0.4, -half_width, 0.370),
|
|
780
|
+
orientation=[-0.026, -0.765, 0.049, 0.642]
|
|
781
|
+
)
|
|
782
|
+
|
|
783
|
+
# 获取base_link到odom的坐标变换
|
|
784
|
+
base_to_odom = self.tools.get_tf_transform("odom", "base_link")
|
|
785
|
+
|
|
786
|
+
# 添加调试信息
|
|
787
|
+
SDKLogger.debug(f"base_to_odom position type: {type(base_to_odom.position)}")
|
|
788
|
+
SDKLogger.debug(f"base_to_odom orientation type: {type(base_to_odom.orientation)}")
|
|
789
|
+
|
|
790
|
+
# 确保返回的是可迭代对象
|
|
791
|
+
if not isinstance(base_to_odom.position, (list, tuple, np.ndarray)):
|
|
792
|
+
raise ValueError("TF变换位置信息格式错误")
|
|
793
|
+
if not isinstance(base_to_odom.orientation, (list, tuple, np.ndarray)):
|
|
794
|
+
raise ValueError("TF变换姿态信息格式错误")
|
|
795
|
+
|
|
796
|
+
# 转换目标姿态到odom坐标系
|
|
797
|
+
left_pull = self._transform_to_odom(l_arm_base_target_pose, base_to_odom)
|
|
798
|
+
right_pull = self._transform_to_odom(r_arm_base_target_pose, base_to_odom)
|
|
799
|
+
|
|
800
|
+
# 6. 放置姿态(放下箱子)
|
|
801
|
+
l_arm_put_away_base_pose = KuavoPose(
|
|
802
|
+
position=(0.419, half_width, 0.160),
|
|
803
|
+
orientation=[-0.107, -0.758, 0.063, 0.641]
|
|
804
|
+
)
|
|
805
|
+
r_arm_put_away_base_pose = KuavoPose(
|
|
806
|
+
position=(0.419, -half_width, 0.160),
|
|
807
|
+
orientation=[-0.026, -0.765, 0.049, 0.642]
|
|
808
|
+
)
|
|
809
|
+
base_to_odom = self.tools.get_tf_transform("odom", "base_link")
|
|
810
|
+
# 添加调试信息
|
|
811
|
+
SDKLogger.debug(f"base_to_odom position type: {type(base_to_odom.position)}")
|
|
812
|
+
SDKLogger.debug(f"base_to_odom orientation type: {type(base_to_odom.orientation)}")
|
|
813
|
+
# 转换目标姿态到odom坐标系
|
|
814
|
+
left_place = self._transform_to_odom(l_arm_put_away_base_pose, base_to_odom)
|
|
815
|
+
right_place = self._transform_to_odom(r_arm_put_away_base_pose, base_to_odom)
|
|
816
|
+
|
|
817
|
+
# 7. 松开手臂
|
|
818
|
+
"""
|
|
819
|
+
left_hand_pose.position[0] + self.grasp_horizontal_offset * np.sin(box_yaw),
|
|
820
|
+
left_hand_pose.position[1] - self.grasp_horizontal_offset * np.cos(box_yaw),
|
|
821
|
+
left_hand_pose.position[2]
|
|
822
|
+
|
|
823
|
+
right_hand_pose.position[0] - self.grasp_horizontal_offset * np.sin(box_yaw),
|
|
824
|
+
right_hand_pose.position[1] + self.grasp_horizontal_offset * np.cos(box_yaw),
|
|
825
|
+
right_hand_pose.position[2]
|
|
826
|
+
"""
|
|
827
|
+
left_release = KuavoPose(
|
|
828
|
+
position=(
|
|
829
|
+
left_place.position[0] + self.grasp_horizontal_offset * np.sin(box_yaw),
|
|
830
|
+
left_place.position[1] - self.grasp_horizontal_offset * np.cos(box_yaw),
|
|
831
|
+
left_place.position[2]
|
|
832
|
+
),
|
|
833
|
+
orientation=left_place.orientation
|
|
834
|
+
)
|
|
835
|
+
|
|
836
|
+
right_release = KuavoPose(
|
|
837
|
+
position=(
|
|
838
|
+
right_place.position[0] - self.grasp_horizontal_offset * np.sin(box_yaw),
|
|
839
|
+
right_place.position[1] + self.grasp_horizontal_offset * np.cos(box_yaw),
|
|
840
|
+
right_place.position[2]
|
|
841
|
+
),
|
|
842
|
+
orientation=right_place.orientation
|
|
843
|
+
)
|
|
844
|
+
|
|
845
|
+
# 8.获取一下当前最近更新的位置,用于后续的轨迹计算
|
|
846
|
+
left_current_position, left_current_orientation = self.tools.get_link_position(link_name="zarm_l7_end_effector", reference_frame="odom")
|
|
847
|
+
right_current_position, right_current_orientation = self.tools.get_link_position(link_name="zarm_r7_end_effector", reference_frame="odom")
|
|
848
|
+
|
|
849
|
+
left_current = KuavoPose(
|
|
850
|
+
position=left_current_position,
|
|
851
|
+
orientation=left_current_orientation
|
|
852
|
+
)
|
|
853
|
+
right_current = KuavoPose(
|
|
854
|
+
position=right_current_position,
|
|
855
|
+
orientation=right_current_orientation
|
|
856
|
+
)
|
|
857
|
+
|
|
858
|
+
# 根据轨迹类型返回对应的姿态
|
|
859
|
+
if traj_type == "grasp":
|
|
860
|
+
return left_pre_grasp, right_pre_grasp, left_grasp, right_grasp
|
|
861
|
+
elif traj_type == "lift":
|
|
862
|
+
return left_grasp, right_grasp, left_lift, right_lift
|
|
863
|
+
elif traj_type == "pull":
|
|
864
|
+
return left_current, right_current, left_pull, right_pull
|
|
865
|
+
elif traj_type == "place":
|
|
866
|
+
return left_current, right_current, left_place, right_place
|
|
867
|
+
elif traj_type == "release":
|
|
868
|
+
return left_place, right_place, left_release, right_release
|
|
869
|
+
else:
|
|
870
|
+
SDKLogger.error(f"未知的轨迹类型: {traj_type}")
|
|
871
|
+
return None, None, None, None
|
|
872
|
+
|
|
873
|
+
def _check_orientation_safety(self, target_orientation, threshold=None):
|
|
874
|
+
"""检查目标朝向与机器人当前朝向的安全性"""
|
|
875
|
+
if threshold is None:
|
|
876
|
+
threshold = self.orientation_safety_threshold
|
|
877
|
+
|
|
878
|
+
# 获取当前机器人朝向
|
|
879
|
+
current_orientation = self.state.robot_orientation()
|
|
880
|
+
current_yaw = KuavoGraspBoxUtils.extract_yaw_from_quaternion(current_orientation)
|
|
881
|
+
|
|
882
|
+
# 提取目标朝向的yaw角
|
|
883
|
+
target_yaw = KuavoGraspBoxUtils.extract_yaw_from_quaternion(target_orientation)
|
|
884
|
+
|
|
885
|
+
# 计算角度差
|
|
886
|
+
angle_diff = abs(target_yaw - current_yaw)
|
|
887
|
+
angle_diff = min(2*math.pi - angle_diff, angle_diff) # 取最小角度差
|
|
888
|
+
|
|
889
|
+
SDKLogger.debug(f"[安全检查] 当前朝向: {math.degrees(current_yaw):.1f}°, 目标朝向: {math.degrees(target_yaw):.1f}°, 差异: {math.degrees(angle_diff):.1f}°")
|
|
890
|
+
|
|
891
|
+
if angle_diff > threshold:
|
|
892
|
+
SDKLogger.error(f"❌ 方向偏差超过安全阈值({math.degrees(threshold):.1f}°),终止操作!")
|
|
893
|
+
return False
|
|
894
|
+
return True
|
|
895
|
+
|
|
896
|
+
def _check_position_safety(self, target_info: BoxInfo) -> bool:
|
|
897
|
+
"""检查目标位置是否在工作空间内"""
|
|
898
|
+
try:
|
|
899
|
+
# 将目标位置转换到base_link坐标系
|
|
900
|
+
target_pose_base = self._transform_to_base_link(target_info.pose)
|
|
901
|
+
|
|
902
|
+
# 获取左右臂关节位置(需要解包位置和姿态)
|
|
903
|
+
l_pos, _ = self.tools.get_link_position("zarm_l1_link") # 解包位置和姿态
|
|
904
|
+
r_pos, _ = self.tools.get_link_position("zarm_r1_link") # 只取位置部分
|
|
905
|
+
|
|
906
|
+
# 转换为numpy数组
|
|
907
|
+
target_pos = np.array(target_pose_base.position)
|
|
908
|
+
l_joint_pos = np.array(l_pos)
|
|
909
|
+
r_joint_pos = np.array(r_pos)
|
|
910
|
+
|
|
911
|
+
# 计算水平距离(只取x,y坐标)
|
|
912
|
+
l_distance = np.linalg.norm(target_pos[:2] - l_joint_pos[:2])
|
|
913
|
+
r_distance = np.linalg.norm(target_pos[:2] - r_joint_pos[:2])
|
|
914
|
+
|
|
915
|
+
SDKLogger.debug(f"[位置安全检查] 左臂距离: {l_distance:.2f}m, 右臂距离: {r_distance:.2f}m, 安全阈值: {self.workspace_radius:.2f}m")
|
|
916
|
+
|
|
917
|
+
# 检查是否在安全范围内
|
|
918
|
+
if l_distance > self.workspace_radius or r_distance > self.workspace_radius:
|
|
919
|
+
SDKLogger.error(f"❌ 目标位置超出工作空间范围({self.workspace_radius}m)")
|
|
920
|
+
return False
|
|
921
|
+
return True
|
|
922
|
+
except Exception as e:
|
|
923
|
+
SDKLogger.error(f"位置安全检查出错: {str(e)}")
|
|
924
|
+
return False
|
|
925
|
+
|
|
926
|
+
def _check_height_safety(self, target_info: BoxInfo) -> bool:
|
|
927
|
+
"""检查目标位置的高度是否在机器人工作范围内
|
|
928
|
+
|
|
929
|
+
Args:
|
|
930
|
+
target_info: 目标信息,包含位置、尺寸等
|
|
931
|
+
|
|
932
|
+
Returns:
|
|
933
|
+
bool: 高度是否在安全范围内
|
|
934
|
+
"""
|
|
935
|
+
target_height = target_info.pose.position[2]
|
|
936
|
+
min_height = 0.5 # 最小工作高度
|
|
937
|
+
max_height = 1.8 # 最大工作高度
|
|
938
|
+
|
|
939
|
+
SDKLogger.debug(f"[高度安全检查] 目标高度: {target_height:.2f}m, 工作范围: {min_height:.2f}m - {max_height:.2f}m")
|
|
940
|
+
|
|
941
|
+
if target_height < min_height or target_height > max_height:
|
|
942
|
+
SDKLogger.error(f"❌ 目标高度 {target_height:.2f}m 超出工作范围({min_height:.2f}m - {max_height:.2f}m),终止操作!")
|
|
943
|
+
return False
|
|
944
|
+
return True
|
|
945
|
+
|
|
946
|
+
def arm_move_to_target(self, target_info:BoxInfo, arm_mode="manipulation_mpc", **kwargs):
|
|
947
|
+
"""添加安全保护检查"""
|
|
948
|
+
# 统一的安全检查
|
|
949
|
+
if not self._check_orientation_safety(target_info.pose.orientation):
|
|
950
|
+
return False
|
|
951
|
+
if not self._check_position_safety(target_info):
|
|
952
|
+
return False
|
|
953
|
+
if not self._check_height_safety(target_info):
|
|
954
|
+
return False
|
|
955
|
+
|
|
956
|
+
# 原有代码保持不变
|
|
957
|
+
if arm_mode == "manipulation_mpc":
|
|
958
|
+
self.robot.set_manipulation_mpc_mode(KuavoManipulationMpcCtrlMode.BaseArm)
|
|
959
|
+
else:
|
|
960
|
+
self.robot.set_fixed_arm_mode()
|
|
961
|
+
|
|
962
|
+
# 获取预抓取轨迹
|
|
963
|
+
left_pose_init, right_pose_init, left_pose_target, right_pose_target = self._get_target_pose(target_info, traj_type="grasp")
|
|
964
|
+
if left_pose_init is None:
|
|
965
|
+
return False
|
|
966
|
+
|
|
967
|
+
# 控制手臂移动到预抓取位置
|
|
968
|
+
if not self.robot.control_robot_end_effector_pose(
|
|
969
|
+
left_pose_init,
|
|
970
|
+
right_pose_init,
|
|
971
|
+
KuavoManipulationMpcFrame.WorldFrame
|
|
972
|
+
):
|
|
973
|
+
return False
|
|
974
|
+
|
|
975
|
+
SDKLogger.debug("执行预抓取姿态到抓取姿态的轨迹...")
|
|
976
|
+
left_traj_grasp = KuavoGraspBox._interpolate_poses(left_pose_init, left_pose_target)
|
|
977
|
+
right_traj_grasp = KuavoGraspBox._interpolate_poses(right_pose_init, right_pose_target)
|
|
978
|
+
self._execute_trajectory(left_traj_grasp, right_traj_grasp)
|
|
979
|
+
return True
|
|
980
|
+
|
|
981
|
+
def _check_box_lifting_status(self, target_info:BoxInfo) -> bool:
|
|
982
|
+
"""检查箱子是否成功抬起
|
|
983
|
+
|
|
984
|
+
Args:
|
|
985
|
+
target_info: 目标信息,包含位置、尺寸等
|
|
986
|
+
|
|
987
|
+
Returns:
|
|
988
|
+
bool: 是否成功抬起箱子
|
|
989
|
+
|
|
990
|
+
Note:
|
|
991
|
+
此函数为预留接口,待实现以下功能:
|
|
992
|
+
1. 获取手部力反馈数据
|
|
993
|
+
2. 根据箱子重量和力反馈判断是否成功抬起
|
|
994
|
+
3. 检查力反馈是否稳定
|
|
995
|
+
"""
|
|
996
|
+
# TODO: 实现力反馈检测逻辑
|
|
997
|
+
# 1. 获取手部力反馈数据
|
|
998
|
+
# left_force = self.state.get_end_effector_force(EndEffectorSide.Left)
|
|
999
|
+
# right_force = self.state.get_end_effector_force(EndEffectorSide.Right)
|
|
1000
|
+
|
|
1001
|
+
# 2. 根据箱子重量和力反馈判断
|
|
1002
|
+
# expected_force = target_info.mass * 9.8
|
|
1003
|
+
# actual_force = calculate_total_force(left_force, right_force)
|
|
1004
|
+
|
|
1005
|
+
# 3. 检查力反馈稳定性
|
|
1006
|
+
# force_stable = check_force_stability()
|
|
1007
|
+
|
|
1008
|
+
# 临时返回True,等待接口实现后修改
|
|
1009
|
+
return True
|
|
1010
|
+
|
|
1011
|
+
def arm_transport_target_up(self, target_info:BoxInfo, arm_mode="manipulation_mpc", sim_mode=False):
|
|
1012
|
+
"""添加安全检查"""
|
|
1013
|
+
# 统一的安全检查
|
|
1014
|
+
if not self._check_orientation_safety(target_info.pose.orientation):
|
|
1015
|
+
return False
|
|
1016
|
+
if not self._check_position_safety(target_info):
|
|
1017
|
+
return False
|
|
1018
|
+
if not self._check_height_safety(target_info):
|
|
1019
|
+
return False
|
|
1020
|
+
|
|
1021
|
+
# 原有代码保持不变
|
|
1022
|
+
if arm_mode == "manipulation_mpc":
|
|
1023
|
+
self.robot.set_manipulation_mpc_mode(KuavoManipulationMpcCtrlMode.BaseArm)
|
|
1024
|
+
else:
|
|
1025
|
+
self.robot.set_fixed_arm_mode()
|
|
1026
|
+
|
|
1027
|
+
# 智能计算夹持力参数
|
|
1028
|
+
g = 9.8 # 重力加速度
|
|
1029
|
+
force_ratio = 0.34 # 经验系数(根据1.5kg对应5N得出:5/(1.5*9.8)≈0.34)
|
|
1030
|
+
|
|
1031
|
+
# 计算基础Z向力(考虑安全系数和经验比例)
|
|
1032
|
+
force_z_base = target_info.mass * g * force_ratio
|
|
1033
|
+
force_z = -abs(force_z_base) # z方向负值表示向上施加力
|
|
1034
|
+
|
|
1035
|
+
# 侧向夹持力计算(基于Z向力的比例)
|
|
1036
|
+
lateral_ratio = 3.0 # 侧向力与垂直力的比例(根据15N/5N=3得出)
|
|
1037
|
+
lateral_force = abs(force_z) * lateral_ratio
|
|
1038
|
+
|
|
1039
|
+
# 判断是否为仿真模式
|
|
1040
|
+
if sim_mode:
|
|
1041
|
+
force_z = 0
|
|
1042
|
+
left_force = 0
|
|
1043
|
+
right_force = 0
|
|
1044
|
+
else:
|
|
1045
|
+
left_force = 15 # 左手侧向力(正值为夹紧方向)
|
|
1046
|
+
right_force = -15 # 右手侧向力(负值为夹紧方向)
|
|
1047
|
+
|
|
1048
|
+
# 提起箱子调用末端力(使用计算得到的力)
|
|
1049
|
+
self.robot.control_hand_wrench(
|
|
1050
|
+
[0, left_force, force_z, 0, 0, 0], # 左手力
|
|
1051
|
+
[0, right_force, force_z, 0, 0, 0] # 右手力
|
|
1052
|
+
)
|
|
1053
|
+
time.sleep(2)
|
|
1054
|
+
|
|
1055
|
+
# 获取抬起轨迹
|
|
1056
|
+
left_pose_init, right_pose_init, left_pose_target, right_pose_target = self._get_target_pose(target_info, traj_type="lift")
|
|
1057
|
+
if left_pose_init is None:
|
|
1058
|
+
return False
|
|
1059
|
+
|
|
1060
|
+
# 执行抬起轨迹
|
|
1061
|
+
SDKLogger.debug("执行抬起轨迹")
|
|
1062
|
+
left_traj_lift = KuavoGraspBox._interpolate_poses(left_pose_init, left_pose_target)
|
|
1063
|
+
right_traj_lift = KuavoGraspBox._interpolate_poses(right_pose_init, right_pose_target)
|
|
1064
|
+
self._execute_trajectory(left_traj_lift, right_traj_lift)
|
|
1065
|
+
time.sleep(2)
|
|
1066
|
+
|
|
1067
|
+
# 暂时关闭
|
|
1068
|
+
self.robot.manipulation_mpc_reset()
|
|
1069
|
+
time.sleep(2)
|
|
1070
|
+
|
|
1071
|
+
# 机器人往后退
|
|
1072
|
+
self.robot.stance()
|
|
1073
|
+
time.sleep(2)
|
|
1074
|
+
self.robot.control_command_pose(-0.5, 0, 0, 0)
|
|
1075
|
+
time.sleep(5) # 等待机器人执行到位
|
|
1076
|
+
|
|
1077
|
+
# 执行收臂轨迹
|
|
1078
|
+
SDKLogger.debug("执行收臂轨迹")
|
|
1079
|
+
left_pose_init, right_pose_init, left_pose_target, right_pose_target = self._get_target_pose(target_info, traj_type="pull")
|
|
1080
|
+
if left_pose_init is None:
|
|
1081
|
+
return False
|
|
1082
|
+
self.robot.set_manipulation_mpc_control_flow(KuavoManipulationMpcControlFlow.DirectToWbc)
|
|
1083
|
+
self.robot.set_manipulation_mpc_mode(KuavoManipulationMpcCtrlMode.ArmOnly)
|
|
1084
|
+
left_traj_pull = KuavoGraspBox._interpolate_poses(left_pose_init, left_pose_target) # left_pose_init left_pose_target
|
|
1085
|
+
right_traj_pull = KuavoGraspBox._interpolate_poses(right_pose_init, right_pose_target) # right_pose_init right_pose_target
|
|
1086
|
+
self._execute_trajectory(left_traj_pull, right_traj_pull)
|
|
1087
|
+
|
|
1088
|
+
if not self._check_box_lifting_status(target_info):
|
|
1089
|
+
return False
|
|
1090
|
+
|
|
1091
|
+
# 暂时关闭
|
|
1092
|
+
self.robot.manipulation_mpc_reset()
|
|
1093
|
+
time.sleep(5)
|
|
1094
|
+
|
|
1095
|
+
return True
|
|
1096
|
+
|
|
1097
|
+
|
|
1098
|
+
def _arrive_pose(self, target_position: list, target_yaw: float, timeout: float = 20.0) -> bool:
|
|
1099
|
+
"""控制机器人移动到指定位姿并等待到达
|
|
1100
|
+
|
|
1101
|
+
Args:
|
|
1102
|
+
target_position: 目标位置 [x, y, z]
|
|
1103
|
+
target_yaw: 目标朝向角度(弧度)
|
|
1104
|
+
timeout: 等待超时时间(秒)
|
|
1105
|
+
|
|
1106
|
+
Returns:
|
|
1107
|
+
bool: 是否成功到达目标位姿
|
|
1108
|
+
"""
|
|
1109
|
+
# 控制机器人移动到目标位姿
|
|
1110
|
+
self.robot.control_command_pose_world(
|
|
1111
|
+
target_position[0], # x
|
|
1112
|
+
target_position[1], # y
|
|
1113
|
+
0, # z (保持当前高度)
|
|
1114
|
+
target_yaw # 目标朝向
|
|
1115
|
+
)
|
|
1116
|
+
|
|
1117
|
+
# 等待机器人到达目标位姿
|
|
1118
|
+
start_time = time.time()
|
|
1119
|
+
rate_hz = 10 # 检查频率
|
|
1120
|
+
wait_interval = 1.0 / rate_hz
|
|
1121
|
+
|
|
1122
|
+
while time.time() - start_time < timeout:
|
|
1123
|
+
# 检查位置和朝向是否到位
|
|
1124
|
+
pos_reached = self._pos_check(target_position)
|
|
1125
|
+
yaw_reached = self._yaw_check(target_yaw)
|
|
1126
|
+
|
|
1127
|
+
if pos_reached and yaw_reached:
|
|
1128
|
+
SDKLogger.debug("机器人已到达目标位姿!")
|
|
1129
|
+
return True
|
|
1130
|
+
|
|
1131
|
+
# 短暂等待再次检查
|
|
1132
|
+
time.sleep(wait_interval)
|
|
1133
|
+
|
|
1134
|
+
# 超时
|
|
1135
|
+
SDKLogger.warn(f"等待机器人到达目标位姿超时!")
|
|
1136
|
+
return False
|
|
1137
|
+
|
|
1138
|
+
def walk_to_pose(self, target_pose:KuavoPose, target_distance=0.5, approach_speed=0.15, timeout=10.0, **kwargs):
|
|
1139
|
+
"""让机器人走到指定的位姿
|
|
1140
|
+
|
|
1141
|
+
Args:
|
|
1142
|
+
target_pose: 目标位姿
|
|
1143
|
+
target_distance: 与目标的期望距离(米)
|
|
1144
|
+
approach_speed: 接近速度(米/秒)
|
|
1145
|
+
timeout: 超时时间(秒)
|
|
1146
|
+
Returns:
|
|
1147
|
+
bool: 是否成功到达目标位姿
|
|
1148
|
+
"""
|
|
1149
|
+
# 获取目标位置和朝向
|
|
1150
|
+
target_position = target_pose.position
|
|
1151
|
+
target_orientation = target_pose.orientation
|
|
1152
|
+
SDKLogger.debug(f"target_position: {target_position}, target_orientation: {target_orientation}")
|
|
1153
|
+
|
|
1154
|
+
# 从四元数中提取yaw角
|
|
1155
|
+
target_yaw = KuavoGraspBoxUtils.extract_yaw_from_quaternion(target_orientation)
|
|
1156
|
+
SDKLogger.debug(f"target_yaw: {target_yaw}")
|
|
1157
|
+
|
|
1158
|
+
# 计算偏移后的位置
|
|
1159
|
+
# 根据目标朝向计算偏移方向
|
|
1160
|
+
offset_x = -target_distance * math.cos(target_yaw) # 负号是因为要远离目标
|
|
1161
|
+
offset_y = -target_distance * math.sin(target_yaw)
|
|
1162
|
+
|
|
1163
|
+
# 计算新的目标位置
|
|
1164
|
+
new_target_position = [
|
|
1165
|
+
target_position[0] + offset_x,
|
|
1166
|
+
target_position[1] + offset_y,
|
|
1167
|
+
target_position[2]
|
|
1168
|
+
]
|
|
1169
|
+
|
|
1170
|
+
SDKLogger.info(f"开始移动到目标位姿:")
|
|
1171
|
+
SDKLogger.info(f"原始目标位置: ({target_position[0]:.2f}, {target_position[1]:.2f}, {target_position[2]:.2f})")
|
|
1172
|
+
SDKLogger.info(f"偏移后位置: ({new_target_position[0]:.2f}, {new_target_position[1]:.2f}, {new_target_position[2]:.2f})")
|
|
1173
|
+
SDKLogger.info(f"目标朝向: {math.degrees(target_yaw):.2f}度")
|
|
1174
|
+
|
|
1175
|
+
if not self._arrive_pose(
|
|
1176
|
+
new_target_position,
|
|
1177
|
+
target_yaw,
|
|
1178
|
+
timeout
|
|
1179
|
+
):
|
|
1180
|
+
return False
|
|
1181
|
+
|
|
1182
|
+
return True
|
|
1183
|
+
|
|
1184
|
+
def arm_transport_target_down(self, target_info:BoxInfo, arm_mode="manipulation_mpc"):
|
|
1185
|
+
"""添加安全检查"""
|
|
1186
|
+
# 统一的安全检查
|
|
1187
|
+
if not self._check_orientation_safety(target_info.pose.orientation):
|
|
1188
|
+
return False
|
|
1189
|
+
if not self._check_position_safety(target_info): # 添加位置检查
|
|
1190
|
+
return False
|
|
1191
|
+
if not self._check_height_safety(target_info):
|
|
1192
|
+
return False
|
|
1193
|
+
|
|
1194
|
+
# 原有代码保持不变
|
|
1195
|
+
if arm_mode == "manipulation_mpc":
|
|
1196
|
+
self.robot.set_manipulation_mpc_mode(KuavoManipulationMpcCtrlMode.BaseArm)
|
|
1197
|
+
else:
|
|
1198
|
+
self.robot.set_fixed_arm_mode()
|
|
1199
|
+
|
|
1200
|
+
# 获取放置轨迹
|
|
1201
|
+
left_pose_init, right_pose_init, left_pose_target, right_pose_target = self._get_target_pose(target_info, traj_type="place")
|
|
1202
|
+
if left_pose_init is None:
|
|
1203
|
+
return False
|
|
1204
|
+
|
|
1205
|
+
# 执行放置轨迹
|
|
1206
|
+
left_traj_place = KuavoGraspBox._interpolate_poses(left_pose_init, left_pose_target)
|
|
1207
|
+
right_traj_place = KuavoGraspBox._interpolate_poses(right_pose_init, right_pose_target)
|
|
1208
|
+
self._execute_trajectory(left_traj_place, right_traj_place)
|
|
1209
|
+
|
|
1210
|
+
time.sleep(2)
|
|
1211
|
+
|
|
1212
|
+
# 箱子已经放到平面
|
|
1213
|
+
self.robot.control_hand_wrench([0,0,0,0,0,0],
|
|
1214
|
+
[0,0,0,0,0,0])
|
|
1215
|
+
time.sleep(2)
|
|
1216
|
+
|
|
1217
|
+
# 放开箱子
|
|
1218
|
+
left_pose_init, right_pose_init, left_pose_target, right_pose_target = self._get_target_pose(target_info, traj_type="release")
|
|
1219
|
+
if left_pose_init is None:
|
|
1220
|
+
return False
|
|
1221
|
+
|
|
1222
|
+
# 执行放开轨迹
|
|
1223
|
+
left_traj_place = KuavoGraspBox._interpolate_poses(left_pose_init, left_pose_target)
|
|
1224
|
+
right_traj_place = KuavoGraspBox._interpolate_poses(right_pose_init, right_pose_target)
|
|
1225
|
+
self._execute_trajectory(left_traj_place, right_traj_place)
|
|
1226
|
+
time.sleep(2)
|
|
1227
|
+
|
|
1228
|
+
self.robot.manipulation_mpc_reset()
|
|
1229
|
+
time.sleep(2)
|
|
1230
|
+
|
|
1231
|
+
# 机器人往后退 0.5m
|
|
1232
|
+
self.robot.stance()
|
|
1233
|
+
time.sleep(2)
|
|
1234
|
+
self.robot.control_command_pose(-0.5, 0, 0, 0)
|
|
1235
|
+
time.sleep(5)
|
|
1236
|
+
|
|
1237
|
+
# 手臂归中
|
|
1238
|
+
self.robot.disable_head_tracking()
|
|
1239
|
+
self.robot.stance()
|
|
1240
|
+
time.sleep(0.5)
|
|
1241
|
+
self.robot.arm_reset()
|
|
1242
|
+
time.sleep(2)
|
|
1243
|
+
|
|
1244
|
+
return True
|
|
1245
|
+
|
|
1246
|
+
def _wait_for_orientation(self, target_angle, max_wait_time=10.0, angle_threshold=0.1):
|
|
1247
|
+
"""等待机器人旋转到指定朝向
|
|
1248
|
+
|
|
1249
|
+
Args:
|
|
1250
|
+
target_angle: 目标朝向角度(弧度)
|
|
1251
|
+
max_wait_time: 最大等待时间(秒)
|
|
1252
|
+
angle_threshold: 角度阈值(弧度),小于此阈值认为已到位
|
|
1253
|
+
|
|
1254
|
+
Returns:
|
|
1255
|
+
bool: 是否成功到达目标朝向
|
|
1256
|
+
"""
|
|
1257
|
+
start_time = time.time()
|
|
1258
|
+
rate_hz = 10 # 检查频率
|
|
1259
|
+
wait_interval = 1.0 / rate_hz
|
|
1260
|
+
|
|
1261
|
+
SDKLogger.info(f"等待机器人旋转到位,目标角度: {math.degrees(target_angle):.2f}度")
|
|
1262
|
+
|
|
1263
|
+
while time.time() - start_time < max_wait_time:
|
|
1264
|
+
if self._yaw_check(target_angle, angle_threshold):
|
|
1265
|
+
return True
|
|
1266
|
+
|
|
1267
|
+
# 短暂等待再次检查
|
|
1268
|
+
time.sleep(wait_interval)
|
|
1269
|
+
|
|
1270
|
+
# 超时
|
|
1271
|
+
SDKLogger.warn(f"等待机器人旋转到位超时! 已经等待了 {max_wait_time:.2f}秒")
|
|
1272
|
+
return False
|
|
1273
|
+
|
|
1274
|
+
def _yaw_check(self, yaw_angle_target, angle_threshold=0.1):
|
|
1275
|
+
"""检查机器人当前朝向与目标朝向的差异
|
|
1276
|
+
|
|
1277
|
+
Args:
|
|
1278
|
+
yaw_angle_target: 目标朝向角度(弧度)
|
|
1279
|
+
angle_threshold: 角度阈值(弧度),小于此阈值认为已到位
|
|
1280
|
+
|
|
1281
|
+
Returns:
|
|
1282
|
+
bool: 是否成功到达目标朝向
|
|
1283
|
+
"""
|
|
1284
|
+
# 获取当前机器人朝向
|
|
1285
|
+
current_orientation = self.state.robot_orientation()
|
|
1286
|
+
current_yaw = KuavoGraspBoxUtils.extract_yaw_from_quaternion(current_orientation)
|
|
1287
|
+
|
|
1288
|
+
# 计算角度差
|
|
1289
|
+
angle_diff = yaw_angle_target - current_yaw
|
|
1290
|
+
# 标准化到[-pi, pi]
|
|
1291
|
+
while angle_diff > math.pi:
|
|
1292
|
+
angle_diff -= 2 * math.pi
|
|
1293
|
+
while angle_diff < -math.pi:
|
|
1294
|
+
angle_diff += 2 * math.pi
|
|
1295
|
+
|
|
1296
|
+
# 输出当前状态
|
|
1297
|
+
SDKLogger.debug(f"当前朝向: {math.degrees(current_yaw):.2f}度, 目标朝向: {math.degrees(yaw_angle_target):.2f}度, 差值: {math.degrees(abs(angle_diff)):.2f}度")
|
|
1298
|
+
|
|
1299
|
+
# 检查是否已到位
|
|
1300
|
+
if abs(angle_diff) < angle_threshold:
|
|
1301
|
+
SDKLogger.debug(f"机器人已旋转到位!")
|
|
1302
|
+
return True
|
|
1303
|
+
else:
|
|
1304
|
+
return False
|
|
1305
|
+
|
|
1306
|
+
def _pos_check(self, pos_target, pos_threshold=0.2):
|
|
1307
|
+
"""检查机器人当前位置(x, y)与目标位置的差异
|
|
1308
|
+
|
|
1309
|
+
Args:
|
|
1310
|
+
pos_target: 目标位置
|
|
1311
|
+
pos_threshold: 位置阈值(米),小于此阈值认为已到位
|
|
1312
|
+
"""
|
|
1313
|
+
current_pos = self.state.robot_position()
|
|
1314
|
+
if not current_pos or len(current_pos) < 2:
|
|
1315
|
+
SDKLogger.error("无法获取有效的机器人当前位置")
|
|
1316
|
+
return False
|
|
1317
|
+
|
|
1318
|
+
# SDKLogger.debug(f"current_pos: {current_pos}, pos_target: {pos_target}")
|
|
1319
|
+
pos_diff = np.linalg.norm(np.array(pos_target[:2]) - np.array(current_pos[:2]))
|
|
1320
|
+
SDKLogger.debug(f"当前位置(x,y): ({current_pos[0]:.2f}, {current_pos[1]:.2f}), 目标位置(x,y): ({pos_target[0]:.2f}, {pos_target[1]:.2f}), 距离: {pos_diff:.2f}米")
|
|
1321
|
+
if pos_diff < pos_threshold:
|
|
1322
|
+
SDKLogger.debug(f"机器人已到达目标位置!")
|
|
1323
|
+
return True
|
|
1324
|
+
else:
|
|
1325
|
+
return False
|