kuavo-humanoid-sdk 1.2.2__20250922181216-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 +276 -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 +11 -0
- kuavo_humanoid_sdk/kuavo/core/audio.py +32 -0
- kuavo_humanoid_sdk/kuavo/core/core.py +612 -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/ros/audio.py +92 -0
- kuavo_humanoid_sdk/kuavo/core/ros/control.py +1309 -0
- kuavo_humanoid_sdk/kuavo/core/ros/observation.py +94 -0
- kuavo_humanoid_sdk/kuavo/core/ros/param.py +183 -0
- kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
- kuavo_humanoid_sdk/kuavo/core/ros/state.py +605 -0
- kuavo_humanoid_sdk/kuavo/core/ros/tools.py +219 -0
- kuavo_humanoid_sdk/kuavo/core/ros/vision.py +234 -0
- kuavo_humanoid_sdk/kuavo/core/ros_env.py +237 -0
- kuavo_humanoid_sdk/kuavo/dexterous_hand.py +201 -0
- kuavo_humanoid_sdk/kuavo/leju_claw.py +235 -0
- kuavo_humanoid_sdk/kuavo/robot.py +465 -0
- kuavo_humanoid_sdk/kuavo/robot_arm.py +210 -0
- kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
- kuavo_humanoid_sdk/kuavo/robot_head.py +50 -0
- kuavo_humanoid_sdk/kuavo/robot_info.py +113 -0
- kuavo_humanoid_sdk/kuavo/robot_observation.py +64 -0
- kuavo_humanoid_sdk/kuavo/robot_state.py +299 -0
- kuavo_humanoid_sdk/kuavo/robot_tool.py +82 -0
- kuavo_humanoid_sdk/kuavo/robot_vision.py +83 -0
- kuavo_humanoid_sdk/kuavo_strategy/__init__.py +2 -0
- kuavo_humanoid_sdk/kuavo_strategy/grasp_box/grasp_box_strategy.py +1126 -0
- kuavo_humanoid_sdk/kuavo_strategy/kuavo_strategy.py +104 -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/_JoySticks.py +191 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_Metadata.py +199 -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/__init__.py +48 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPose.py +160 -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 +151 -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/_footPoseTargetTrajectories.py +301 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses.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/_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/_planArmState.py +120 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_questJoySticks.py +191 -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/_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 +495 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_switchGaitByName.py +200 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_touchSensorStatus.py +162 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPose.py +272 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmd.py +315 -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/_ExecuteArmAction.py +281 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_RepublishTFs.py +373 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetJoyTopic.py +282 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SpeechSynthesis.py +270 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/__init__.py +29 -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 +394 -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/_handForceLevel.py +330 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_jointMoveTo.py +302 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryBezierCurve.py +421 -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 +662 -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.2.dist-info/METADATA +291 -0
- kuavo_humanoid_sdk-1.2.2.dist-info/RECORD +137 -0
- kuavo_humanoid_sdk-1.2.2.dist-info/WHEEL +6 -0
- kuavo_humanoid_sdk-1.2.2.dist-info/top_level.txt +1 -0
|
@@ -0,0 +1,94 @@
|
|
|
1
|
+
#!/usr/bin/env python3
|
|
2
|
+
# coding: utf-8
|
|
3
|
+
from kuavo_humanoid_sdk.interfaces.data_types import (
|
|
4
|
+
KuavoJointCommand, KuavoTwist)
|
|
5
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
6
|
+
import rospy
|
|
7
|
+
from geometry_msgs.msg import Twist
|
|
8
|
+
from kuavo_humanoid_sdk.msg.kuavo_msgs.msg import jointCmd
|
|
9
|
+
|
|
10
|
+
class KuavoRobotObservationCore:
|
|
11
|
+
_instance = None
|
|
12
|
+
|
|
13
|
+
def __new__(cls, *args, **kwargs):
|
|
14
|
+
if not cls._instance:
|
|
15
|
+
cls._instance = super().__new__(cls)
|
|
16
|
+
return cls._instance
|
|
17
|
+
|
|
18
|
+
def __init__(self):
|
|
19
|
+
if not hasattr(self, '_initialized'):
|
|
20
|
+
rospy.Subscriber("/joint_cmd", jointCmd, self._joint_cmd_callback)
|
|
21
|
+
rospy.Subscriber("/cmd_vel", Twist, self._cmd_vel_callback)
|
|
22
|
+
rospy.Subscriber("/cmd_pose", Twist, self._cmd_pose_callback)
|
|
23
|
+
|
|
24
|
+
""" data """
|
|
25
|
+
self._joint_cmd = KuavoJointCommand(
|
|
26
|
+
joint_q = [0.0] * 28,
|
|
27
|
+
joint_v = [0.0] * 28,
|
|
28
|
+
tau = [0.0] * 28,
|
|
29
|
+
tau_max = [0.0] * 28,
|
|
30
|
+
tau_ratio = [0.0] * 28,
|
|
31
|
+
joint_kp = [0.0] * 28,
|
|
32
|
+
joint_kd = [0.0] * 28,
|
|
33
|
+
control_modes = [0] * 28
|
|
34
|
+
)
|
|
35
|
+
|
|
36
|
+
self._cmd_vel = KuavoTwist(
|
|
37
|
+
linear = (0.0, 0.0, 0.0),
|
|
38
|
+
angular = (0.0, 0.0, 0.0)
|
|
39
|
+
)
|
|
40
|
+
|
|
41
|
+
self._cmd_pose = KuavoTwist(
|
|
42
|
+
linear = (0.0, 0.0, 0.0),
|
|
43
|
+
angular = (0.0, 0.0, 0.0)
|
|
44
|
+
)
|
|
45
|
+
|
|
46
|
+
self._initialized = True
|
|
47
|
+
|
|
48
|
+
def _joint_cmd_callback(self, msg):
|
|
49
|
+
self._joint_cmd.joint_q = list(msg.joint_q)
|
|
50
|
+
self._joint_cmd.joint_v = list(msg.joint_v)
|
|
51
|
+
self._joint_cmd.tau = list(msg.tau)
|
|
52
|
+
self._joint_cmd.tau_max = list(msg.tau_max)
|
|
53
|
+
self._joint_cmd.tau_ratio = list(msg.tau_ratio)
|
|
54
|
+
self._joint_cmd.joint_kp = list(msg.joint_kp)
|
|
55
|
+
self._joint_cmd.joint_kd = list(msg.joint_kd)
|
|
56
|
+
self._joint_cmd.control_modes = list(msg.control_modes)
|
|
57
|
+
|
|
58
|
+
def _cmd_vel_callback(self, msg):
|
|
59
|
+
self._cmd_vel.linear = (msg.linear.x, msg.linear.y, msg.linear.z)
|
|
60
|
+
self._cmd_vel.angular = (msg.angular.x, msg.angular.y, msg.angular.z)
|
|
61
|
+
|
|
62
|
+
def _cmd_pose_callback(self, msg):
|
|
63
|
+
self._cmd_pose.linear = (msg.linear.x, msg.linear.y, msg.linear.z)
|
|
64
|
+
self._cmd_pose.angular = (msg.angular.x, msg.angular.y, msg.angular.z)
|
|
65
|
+
|
|
66
|
+
@property
|
|
67
|
+
def joint_command(self) -> KuavoJointCommand:
|
|
68
|
+
return self._joint_cmd
|
|
69
|
+
|
|
70
|
+
@property
|
|
71
|
+
def cmd_vel(self) -> KuavoTwist:
|
|
72
|
+
return self._cmd_vel
|
|
73
|
+
|
|
74
|
+
@property
|
|
75
|
+
def cmd_pose(self) -> KuavoTwist:
|
|
76
|
+
return self._cmd_pose
|
|
77
|
+
|
|
78
|
+
@property
|
|
79
|
+
def arm_position_command(self) -> list:
|
|
80
|
+
"""Return the position commands for the arm joints (indices 12-25).
|
|
81
|
+
|
|
82
|
+
Returns:
|
|
83
|
+
list: Position commands for arm joints
|
|
84
|
+
"""
|
|
85
|
+
return self._joint_cmd.joint_q[12:26]
|
|
86
|
+
|
|
87
|
+
@property
|
|
88
|
+
def head_position_command(self) -> list:
|
|
89
|
+
"""Return the position commands for the head joints (indices 26-27).
|
|
90
|
+
|
|
91
|
+
Returns:
|
|
92
|
+
list: Position commands for head joints
|
|
93
|
+
"""
|
|
94
|
+
return self._joint_cmd.joint_q[-2:]
|
|
@@ -0,0 +1,183 @@
|
|
|
1
|
+
import rospy
|
|
2
|
+
import json
|
|
3
|
+
import xml.etree.ElementTree as ET
|
|
4
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
5
|
+
# End effector types
|
|
6
|
+
class EndEffectorType:
|
|
7
|
+
QIANGNAO = "qiangnao"
|
|
8
|
+
QIANGNAO_TOUCH = "qiangnao_touch"
|
|
9
|
+
LEJUCLAW = "lejuclaw"
|
|
10
|
+
class RosParameter:
|
|
11
|
+
def __init__(self):
|
|
12
|
+
pass
|
|
13
|
+
def robot_version(self)->str:
|
|
14
|
+
if not rospy.has_param('/robot_version'):
|
|
15
|
+
rospy.logerr("robot_version parameter not found")
|
|
16
|
+
return None
|
|
17
|
+
return rospy.get_param('/robot_version')
|
|
18
|
+
|
|
19
|
+
def arm_dof(self)->int:
|
|
20
|
+
if not rospy.has_param('/armRealDof'):
|
|
21
|
+
rospy.logerr("armRealDof parameter not found")
|
|
22
|
+
return None
|
|
23
|
+
return rospy.get_param('/armRealDof')
|
|
24
|
+
|
|
25
|
+
def head_dof(self)->int:
|
|
26
|
+
if not rospy.has_param('/headRealDof'):
|
|
27
|
+
rospy.logerr("headRealDof parameter not found")
|
|
28
|
+
return None
|
|
29
|
+
return rospy.get_param('/headRealDof')
|
|
30
|
+
|
|
31
|
+
def leg_dof(self)->int:
|
|
32
|
+
if not rospy.has_param('/legRealDof'):
|
|
33
|
+
rospy.logerr("legRealDof parameter not found")
|
|
34
|
+
return None
|
|
35
|
+
return rospy.get_param('/legRealDof')
|
|
36
|
+
|
|
37
|
+
def end_effector_type(self)->str:
|
|
38
|
+
if not rospy.has_param('/end_effector_type'):
|
|
39
|
+
return None
|
|
40
|
+
return rospy.get_param('/end_effector_type')
|
|
41
|
+
|
|
42
|
+
def humanoid_description(self)->str:
|
|
43
|
+
if not rospy.has_param('/humanoid_description'):
|
|
44
|
+
rospy.logerr("humanoid_description parameter not found")
|
|
45
|
+
return None
|
|
46
|
+
return rospy.get_param('/humanoid_description')
|
|
47
|
+
|
|
48
|
+
def model_path(self)->str:
|
|
49
|
+
if not rospy.has_param('/modelPath'):
|
|
50
|
+
rospy.logerr("modelPath parameter not found")
|
|
51
|
+
return None
|
|
52
|
+
return rospy.get_param('/modelPath')
|
|
53
|
+
|
|
54
|
+
def kuavo_config(self)->str:
|
|
55
|
+
if not rospy.has_param('/kuavo_configuration'):
|
|
56
|
+
rospy.logerr("kuavo_configuration parameter not found")
|
|
57
|
+
return None
|
|
58
|
+
return rospy.get_param('/kuavo_configuration')
|
|
59
|
+
|
|
60
|
+
def initial_state(self)->str:
|
|
61
|
+
if not rospy.has_param('/initial_state'):
|
|
62
|
+
rospy.logerr("initial_state parameter not found")
|
|
63
|
+
return None
|
|
64
|
+
return rospy.get_param('/initial_state')
|
|
65
|
+
|
|
66
|
+
|
|
67
|
+
def joint_names()->dict:
|
|
68
|
+
leg_link_names = [
|
|
69
|
+
'leg_l1_link', 'leg_l2_link', 'leg_l3_link', 'leg_l4_link', 'leg_l5_link', 'leg_l6_link',
|
|
70
|
+
'leg_r1_link', 'leg_r2_link', 'leg_r3_link', 'leg_r4_link', 'leg_r5_link', 'leg_r6_link'
|
|
71
|
+
]
|
|
72
|
+
arm_link_names = [
|
|
73
|
+
'zarm_l1_link', 'zarm_l2_link', 'zarm_l3_link', 'zarm_l4_link', 'zarm_l5_link', 'zarm_l6_link', 'zarm_l7_link',
|
|
74
|
+
'zarm_r1_link', 'zarm_r2_link', 'zarm_r3_link', 'zarm_r4_link', 'zarm_r5_link', 'zarm_r6_link', 'zarm_r7_link',
|
|
75
|
+
]
|
|
76
|
+
head_link_names = [
|
|
77
|
+
'zhead_1_link', 'zhead_2_link'
|
|
78
|
+
]
|
|
79
|
+
|
|
80
|
+
kuavo_ros_param = RosParameter()
|
|
81
|
+
|
|
82
|
+
robot_desc = kuavo_ros_param.humanoid_description()
|
|
83
|
+
if robot_desc is None:
|
|
84
|
+
return None
|
|
85
|
+
|
|
86
|
+
"""
|
|
87
|
+
<link name="leg_l1_link">
|
|
88
|
+
<inertial>
|
|
89
|
+
....
|
|
90
|
+
</inertial>
|
|
91
|
+
<visual>
|
|
92
|
+
...
|
|
93
|
+
<geometry>
|
|
94
|
+
<mesh filename="package://kuavo_assets/models/biped_s43/meshes/l_leg_roll.STL" />
|
|
95
|
+
</geometry>
|
|
96
|
+
...
|
|
97
|
+
</visual>
|
|
98
|
+
</link>
|
|
99
|
+
"""
|
|
100
|
+
root = ET.fromstring(robot_desc)
|
|
101
|
+
process_link_name = lambda link_name: (
|
|
102
|
+
(root.find(f".//link[@name='{link_name}']") is not None and
|
|
103
|
+
root.find(f".//link[@name='{link_name}']/visual") is not None and
|
|
104
|
+
root.find(f".//link[@name='{link_name}']/visual/geometry") is not None and
|
|
105
|
+
root.find(f".//link[@name='{link_name}']/visual/geometry/mesh") is not None and
|
|
106
|
+
root.find(f".//link[@name='{link_name}']/visual/geometry/mesh").get("filename") is not None)
|
|
107
|
+
and (
|
|
108
|
+
# Extract the basename (without path and extension)
|
|
109
|
+
root.find(f".//link[@name='{link_name}']/visual/geometry/mesh")
|
|
110
|
+
.get("filename")
|
|
111
|
+
.split("/")[-1]
|
|
112
|
+
.split(".")[0]
|
|
113
|
+
)
|
|
114
|
+
or (
|
|
115
|
+
SDKLogger.warn(f"Warning: {link_name} is not found or incomplete in robot_desc"),
|
|
116
|
+
None
|
|
117
|
+
)[1] # Return None after printing the warning
|
|
118
|
+
)
|
|
119
|
+
leg_joint_names = [process_link_name(link_name) for link_name in leg_link_names if process_link_name(link_name) is not None]
|
|
120
|
+
arm_joint_names = [process_link_name(link_name) for link_name in arm_link_names if process_link_name(link_name) is not None]
|
|
121
|
+
head_joint_names = [process_link_name(link_name) for link_name in head_link_names if process_link_name(link_name) is not None]
|
|
122
|
+
|
|
123
|
+
if len(leg_link_names) != len(leg_joint_names):
|
|
124
|
+
SDKLogger.warn(f"leg_joint_names is not equal to leg_link_names, {len(leg_link_names)} != {len(leg_joint_names)}")
|
|
125
|
+
return None
|
|
126
|
+
if len(arm_link_names)!= len(arm_joint_names):
|
|
127
|
+
SDKLogger.warn(f"arm_joint_names is not equal to arm_link_names, {len(arm_link_names)}!= {len(arm_joint_names)}")
|
|
128
|
+
return None
|
|
129
|
+
if len(head_link_names)!= len(head_joint_names):
|
|
130
|
+
SDKLogger.warn(f"head_joint_names is not equal to head_link_names, {len(head_link_names)}!= {len(head_joint_names)}")
|
|
131
|
+
return None
|
|
132
|
+
|
|
133
|
+
return leg_joint_names + arm_joint_names + head_joint_names
|
|
134
|
+
|
|
135
|
+
kuavo_ros_info = None
|
|
136
|
+
|
|
137
|
+
def end_frames_names()->dict:
|
|
138
|
+
default = ["torso", "zarm_l7_link", "zarm_r7_link", "zarm_l4_link", "zarm_r4_link"]
|
|
139
|
+
|
|
140
|
+
kuavo_ros_param = RosParameter()
|
|
141
|
+
|
|
142
|
+
kuavo_json = kuavo_ros_param.kuavo_config()
|
|
143
|
+
if kuavo_json is None:
|
|
144
|
+
return default
|
|
145
|
+
|
|
146
|
+
try:
|
|
147
|
+
kuavo_config = json.loads(kuavo_json)
|
|
148
|
+
if kuavo_config.get('end_frames_names') is not None:
|
|
149
|
+
return kuavo_config.get('end_frames_names')
|
|
150
|
+
else:
|
|
151
|
+
return default
|
|
152
|
+
except Exception as e:
|
|
153
|
+
print(f"Failed to get end_frames_names from kuavo_json: {e}")
|
|
154
|
+
return default
|
|
155
|
+
|
|
156
|
+
def make_robot_param()->dict:
|
|
157
|
+
global kuavo_ros_info
|
|
158
|
+
if kuavo_ros_info is not None:
|
|
159
|
+
return kuavo_ros_info
|
|
160
|
+
|
|
161
|
+
kuavo_ros_param = RosParameter()
|
|
162
|
+
|
|
163
|
+
kuavo_ros_info = {
|
|
164
|
+
'robot_version': kuavo_ros_param.robot_version(),
|
|
165
|
+
'arm_dof': kuavo_ros_param.arm_dof(),
|
|
166
|
+
'head_dof': kuavo_ros_param.head_dof(),
|
|
167
|
+
'leg_dof': kuavo_ros_param.leg_dof(),
|
|
168
|
+
'end_effector_type': kuavo_ros_param.end_effector_type(),
|
|
169
|
+
'joint_names': joint_names(),
|
|
170
|
+
'end_frames_names': end_frames_names(),
|
|
171
|
+
}
|
|
172
|
+
|
|
173
|
+
for key, value in kuavo_ros_info.items():
|
|
174
|
+
if value is None and key != 'end_effector_type':
|
|
175
|
+
SDKLogger.debug(f"[Error]: Failed to get '{key}' from ROS.")
|
|
176
|
+
kuavo_ros_info = None
|
|
177
|
+
raise Exception(f"[Error]: Failed to get '{key}' from ROS.")
|
|
178
|
+
|
|
179
|
+
return kuavo_ros_info
|
|
180
|
+
|
|
181
|
+
if __name__ == "__main__":
|
|
182
|
+
rospy.init_node("kuavo_ros_param_test")
|
|
183
|
+
print(make_robot_param())
|
|
@@ -0,0 +1,103 @@
|
|
|
1
|
+
import numpy as np
|
|
2
|
+
|
|
3
|
+
class RotatingRectangle:
|
|
4
|
+
def __init__(self, center, width, height, angle):
|
|
5
|
+
self.center = center
|
|
6
|
+
self.width = width
|
|
7
|
+
self.height = height
|
|
8
|
+
self.angle = angle
|
|
9
|
+
|
|
10
|
+
def set_rotation(self, angle):
|
|
11
|
+
self.angle = angle
|
|
12
|
+
|
|
13
|
+
def rotate_point(self, point):
|
|
14
|
+
"""旋转点"""
|
|
15
|
+
px, py = point
|
|
16
|
+
cos_theta = np.cos(self.angle)
|
|
17
|
+
sin_theta = np.sin(self.angle)
|
|
18
|
+
return (cos_theta * px - sin_theta * py, sin_theta * px + cos_theta * py)
|
|
19
|
+
|
|
20
|
+
def get_vertices(self):
|
|
21
|
+
"""获取旋转长方形的顶点"""
|
|
22
|
+
cx, cy = self.center
|
|
23
|
+
half_w, half_h = self.width / 2, self.height / 2
|
|
24
|
+
vertices = [
|
|
25
|
+
(half_w, half_h),
|
|
26
|
+
(-half_w, half_h),
|
|
27
|
+
(-half_w, -half_h),
|
|
28
|
+
(half_w, -half_h)
|
|
29
|
+
]
|
|
30
|
+
return [(cx + x, cy + y) for x, y in (self.rotate_point(v) for v in vertices)]
|
|
31
|
+
|
|
32
|
+
@staticmethod
|
|
33
|
+
def project(vertices, axis):
|
|
34
|
+
"""将顶点投影到轴上"""
|
|
35
|
+
projections = [np.dot(v, axis) for v in vertices]
|
|
36
|
+
return min(projections), max(projections)
|
|
37
|
+
|
|
38
|
+
@staticmethod
|
|
39
|
+
def is_separating_axis(vertices1, vertices2, axis):
|
|
40
|
+
"""检查是否为分离轴"""
|
|
41
|
+
min1, max1 = RotatingRectangle.project(vertices1, axis)
|
|
42
|
+
min2, max2 = RotatingRectangle.project(vertices2, axis)
|
|
43
|
+
return max1 < min2 or max2 < min1
|
|
44
|
+
|
|
45
|
+
def is_collision(self, other):
|
|
46
|
+
"""检测两个旋转长方形是否发生碰撞"""
|
|
47
|
+
vertices1 = self.get_vertices()
|
|
48
|
+
vertices2 = other.get_vertices()
|
|
49
|
+
|
|
50
|
+
# 获取所有可能的分离轴
|
|
51
|
+
axes = []
|
|
52
|
+
for i in range(4):
|
|
53
|
+
edge = (vertices1[i][0] - vertices1[i-1][0], vertices1[i][1] - vertices1[i-1][1])
|
|
54
|
+
axis = (-edge[1], edge[0])
|
|
55
|
+
axes.append(axis)
|
|
56
|
+
for i in range(4):
|
|
57
|
+
edge = (vertices2[i][0] - vertices2[i-1][0], vertices2[i][1] - vertices2[i-1][1])
|
|
58
|
+
axis = (-edge[1], edge[0])
|
|
59
|
+
axes.append(axis)
|
|
60
|
+
|
|
61
|
+
# 检查所有轴上的投影是否重叠
|
|
62
|
+
for axis in axes:
|
|
63
|
+
if self.is_separating_axis(vertices1, vertices2, axis):
|
|
64
|
+
return False
|
|
65
|
+
return True
|
|
66
|
+
|
|
67
|
+
def show(self, color):
|
|
68
|
+
"""绘制旋转长方形"""
|
|
69
|
+
vertices = self.get_vertices()
|
|
70
|
+
vertices.append(vertices[0]) # 闭合多边形
|
|
71
|
+
xs, ys = zip(*vertices)
|
|
72
|
+
plt.fill(xs, ys, color=color, alpha=0.5)
|
|
73
|
+
|
|
74
|
+
|
|
75
|
+
# 示例
|
|
76
|
+
if __name__ == "__main__":
|
|
77
|
+
rect1 = RotatingRectangle(center=(0, 0.1), width=0.2, height=0.1, angle=0)
|
|
78
|
+
rect2 = RotatingRectangle(center=(0, -0.1), width=0.2, height=0.1, angle=0)
|
|
79
|
+
|
|
80
|
+
collision = rect1.is_collision(rect2)
|
|
81
|
+
print("发生碰撞:", collision)
|
|
82
|
+
|
|
83
|
+
rect1.set_rotation(-np.pi / 4)
|
|
84
|
+
rect2.set_rotation(np.pi / 4)
|
|
85
|
+
collision = rect1.is_collision(rect2)
|
|
86
|
+
print("发生碰撞:", collision)
|
|
87
|
+
|
|
88
|
+
# visualize
|
|
89
|
+
import matplotlib.pyplot as plt
|
|
90
|
+
# 绘制长方形
|
|
91
|
+
plt.figure()
|
|
92
|
+
rect1.show(color='blue')
|
|
93
|
+
rect2.show(color='red')
|
|
94
|
+
|
|
95
|
+
# 设置显示区域
|
|
96
|
+
plt.xlim(-0.3, 0.3)
|
|
97
|
+
plt.ylim(-0.3, 0.3)
|
|
98
|
+
plt.xlabel('x')
|
|
99
|
+
plt.ylabel('y')
|
|
100
|
+
plt.gca().set_aspect('equal', adjustable='box')
|
|
101
|
+
plt.grid()
|
|
102
|
+
plt.title(f'Rotated Rectangle Collision Detection: {collision}')
|
|
103
|
+
plt.show()
|