kuavo-humanoid-sdk-ws 1.3.2b397__20260202203030-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.
- kuavo_humanoid_sdk/__init__.py +6 -0
- kuavo_humanoid_sdk/common/launch_robot_tool.py +170 -0
- kuavo_humanoid_sdk/common/logger.py +45 -0
- kuavo_humanoid_sdk/common/websocket_kuavo_sdk.py +26 -0
- kuavo_humanoid_sdk/interfaces/__init__.py +4 -0
- kuavo_humanoid_sdk/interfaces/data_types.py +293 -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 +12 -0
- kuavo_humanoid_sdk/kuavo/core/audio.py +32 -0
- kuavo_humanoid_sdk/kuavo/core/core.py +755 -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 +86 -0
- kuavo_humanoid_sdk/kuavo/core/ros/control.py +1325 -0
- kuavo_humanoid_sdk/kuavo/core/ros/observation.py +125 -0
- kuavo_humanoid_sdk/kuavo/core/ros/param.py +335 -0
- kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
- kuavo_humanoid_sdk/kuavo/core/ros/state.py +426 -0
- kuavo_humanoid_sdk/kuavo/core/ros/tools.py +197 -0
- kuavo_humanoid_sdk/kuavo/core/ros/vision.py +280 -0
- kuavo_humanoid_sdk/kuavo/core/ros_env.py +236 -0
- kuavo_humanoid_sdk/kuavo/dexterous_hand.py +198 -0
- kuavo_humanoid_sdk/kuavo/leju_claw.py +232 -0
- kuavo_humanoid_sdk/kuavo/robot.py +550 -0
- kuavo_humanoid_sdk/kuavo/robot_arm.py +235 -0
- kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
- kuavo_humanoid_sdk/kuavo/robot_head.py +39 -0
- kuavo_humanoid_sdk/kuavo/robot_info.py +235 -0
- kuavo_humanoid_sdk/kuavo/robot_observation.py +69 -0
- kuavo_humanoid_sdk/kuavo/robot_state.py +346 -0
- kuavo_humanoid_sdk/kuavo/robot_tool.py +58 -0
- kuavo_humanoid_sdk/kuavo/robot_vision.py +82 -0
- kuavo_humanoid_sdk/kuavo/robot_waist.py +53 -0
- kuavo_humanoid_sdk/kuavo_strategy/__init__.py +2 -0
- kuavo_humanoid_sdk/kuavo_strategy/grasp_box/grasp_box_strategy.py +418 -0
- kuavo_humanoid_sdk/kuavo_strategy/kuavo_strategy.py +63 -0
- kuavo_humanoid_sdk/msg/__init__.py +4 -0
- kuavo_humanoid_sdk_ws-1.3.2b397.dist-info/METADATA +279 -0
- kuavo_humanoid_sdk_ws-1.3.2b397.dist-info/RECORD +43 -0
- kuavo_humanoid_sdk_ws-1.3.2b397.dist-info/WHEEL +6 -0
- kuavo_humanoid_sdk_ws-1.3.2b397.dist-info/top_level.txt +1 -0
|
@@ -0,0 +1,125 @@
|
|
|
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 roslibpy
|
|
7
|
+
from kuavo_humanoid_sdk.common.websocket_kuavo_sdk import WebSocketKuavoSDK
|
|
8
|
+
|
|
9
|
+
class KuavoRobotObservationCoreWebsocket:
|
|
10
|
+
_instance = None
|
|
11
|
+
|
|
12
|
+
def __new__(cls, *args, **kwargs):
|
|
13
|
+
if not cls._instance:
|
|
14
|
+
cls._instance = super().__new__(cls)
|
|
15
|
+
return cls._instance
|
|
16
|
+
|
|
17
|
+
def __init__(self):
|
|
18
|
+
if not hasattr(self, '_initialized'):
|
|
19
|
+
# 初始化 WebSocket 连接
|
|
20
|
+
self.websocket = WebSocketKuavoSDK()
|
|
21
|
+
|
|
22
|
+
# 初始化订阅者
|
|
23
|
+
self._joint_cmd_subscriber = roslibpy.Topic(
|
|
24
|
+
self.websocket.client, '/joint_cmd', 'kuavo_msgs/jointCmd')
|
|
25
|
+
self._cmd_vel_subscriber = roslibpy.Topic(
|
|
26
|
+
self.websocket.client, '/cmd_vel', 'geometry_msgs/Twist')
|
|
27
|
+
self._cmd_pose_subscriber = roslibpy.Topic(
|
|
28
|
+
self.websocket.client, '/cmd_pose', 'geometry_msgs/Twist')
|
|
29
|
+
|
|
30
|
+
# 订阅话题
|
|
31
|
+
self._joint_cmd_subscriber.subscribe(self._joint_cmd_callback)
|
|
32
|
+
self._cmd_vel_subscriber.subscribe(self._cmd_vel_callback)
|
|
33
|
+
self._cmd_pose_subscriber.subscribe(self._cmd_pose_callback)
|
|
34
|
+
|
|
35
|
+
""" 数据初始化 """
|
|
36
|
+
self._joint_cmd = KuavoJointCommand(
|
|
37
|
+
joint_q = [0.0] * 28,
|
|
38
|
+
joint_v = [0.0] * 28,
|
|
39
|
+
tau = [0.0] * 28,
|
|
40
|
+
tau_max = [0.0] * 28,
|
|
41
|
+
tau_ratio = [0.0] * 28,
|
|
42
|
+
joint_kp = [0.0] * 28,
|
|
43
|
+
joint_kd = [0.0] * 28,
|
|
44
|
+
control_modes = [0] * 28
|
|
45
|
+
)
|
|
46
|
+
|
|
47
|
+
self._cmd_vel = KuavoTwist(
|
|
48
|
+
linear = (0.0, 0.0, 0.0),
|
|
49
|
+
angular = (0.0, 0.0, 0.0)
|
|
50
|
+
)
|
|
51
|
+
|
|
52
|
+
self._cmd_pose = KuavoTwist(
|
|
53
|
+
linear = (0.0, 0.0, 0.0),
|
|
54
|
+
angular = (0.0, 0.0, 0.0)
|
|
55
|
+
)
|
|
56
|
+
|
|
57
|
+
self._initialized = True
|
|
58
|
+
|
|
59
|
+
def _joint_cmd_callback(self, msg):
|
|
60
|
+
"""关节命令回调函数
|
|
61
|
+
|
|
62
|
+
Args:
|
|
63
|
+
msg: roslibpy 消息,包含关节命令数据
|
|
64
|
+
"""
|
|
65
|
+
# 将 roslibpy 消息转换为我们的格式
|
|
66
|
+
self._joint_cmd.joint_q = list(msg['joint_q'])
|
|
67
|
+
self._joint_cmd.joint_v = list(msg['joint_v'])
|
|
68
|
+
self._joint_cmd.tau = list(msg['tau'])
|
|
69
|
+
self._joint_cmd.tau_max = list(msg['tau_max'])
|
|
70
|
+
self._joint_cmd.tau_ratio = list(msg['tau_ratio'])
|
|
71
|
+
self._joint_cmd.joint_kp = list(msg['joint_kp'])
|
|
72
|
+
self._joint_cmd.joint_kd = list(msg['joint_kd'])
|
|
73
|
+
self._joint_cmd.control_modes = list(msg['control_modes'])
|
|
74
|
+
|
|
75
|
+
def _cmd_vel_callback(self, msg):
|
|
76
|
+
"""速度命令回调函数
|
|
77
|
+
|
|
78
|
+
Args:
|
|
79
|
+
msg: WebSocket 消息,包含速度命令数据
|
|
80
|
+
"""
|
|
81
|
+
self._cmd_vel.linear = (msg['linear']['x'], msg['linear']['y'], msg['linear']['z'])
|
|
82
|
+
self._cmd_vel.angular = (msg['angular']['x'], msg['angular']['y'], msg['angular']['z'])
|
|
83
|
+
|
|
84
|
+
def _cmd_pose_callback(self, msg):
|
|
85
|
+
"""位姿命令回调函数
|
|
86
|
+
|
|
87
|
+
Args:
|
|
88
|
+
msg: WebSocket 消息,包含位姿命令数据
|
|
89
|
+
"""
|
|
90
|
+
self._cmd_pose.linear = (msg['linear']['x'], msg['linear']['y'], msg['linear']['z'])
|
|
91
|
+
self._cmd_pose.angular = (msg['angular']['x'], msg['angular']['y'], msg['angular']['z'])
|
|
92
|
+
|
|
93
|
+
|
|
94
|
+
@property
|
|
95
|
+
def joint_command(self) -> KuavoJointCommand:
|
|
96
|
+
return self._joint_cmd
|
|
97
|
+
|
|
98
|
+
@property
|
|
99
|
+
def cmd_vel(self) -> KuavoTwist:
|
|
100
|
+
return self._cmd_vel
|
|
101
|
+
|
|
102
|
+
@property
|
|
103
|
+
def cmd_pose(self) -> KuavoTwist:
|
|
104
|
+
return self._cmd_pose
|
|
105
|
+
|
|
106
|
+
@property
|
|
107
|
+
def arm_position_command(self) -> list:
|
|
108
|
+
"""Return the position commands for the arm joints (indices 12-25).
|
|
109
|
+
|
|
110
|
+
Returns:
|
|
111
|
+
list: Position commands for arm joints
|
|
112
|
+
"""
|
|
113
|
+
return self._joint_cmd.joint_q[12:26]
|
|
114
|
+
|
|
115
|
+
@property
|
|
116
|
+
def head_position_command(self) -> list:
|
|
117
|
+
"""Return the position commands for the head joints (indices 26-27).
|
|
118
|
+
|
|
119
|
+
Returns:
|
|
120
|
+
list: Position commands for head joints
|
|
121
|
+
"""
|
|
122
|
+
return self._joint_cmd.joint_q[-2:]
|
|
123
|
+
|
|
124
|
+
|
|
125
|
+
# TODO: 实现 Websocket 接口在这里
|
|
@@ -0,0 +1,335 @@
|
|
|
1
|
+
import json
|
|
2
|
+
import xml.etree.ElementTree as ET
|
|
3
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
4
|
+
from kuavo_humanoid_sdk.common.websocket_kuavo_sdk import WebSocketKuavoSDK
|
|
5
|
+
import roslibpy
|
|
6
|
+
|
|
7
|
+
# End effector types
|
|
8
|
+
class EndEffectorType:
|
|
9
|
+
QIANGNAO = "qiangnao"
|
|
10
|
+
QIANGNAO_TOUCH = "qiangnao_touch"
|
|
11
|
+
LEJUCLAW = "lejuclaw"
|
|
12
|
+
|
|
13
|
+
|
|
14
|
+
class RosParamWebsocket:
|
|
15
|
+
def __init__(self):
|
|
16
|
+
self.websocket = WebSocketKuavoSDK()
|
|
17
|
+
if not self.websocket.client.is_connected:
|
|
18
|
+
SDKLogger.error("Failed to connect to WebSocket server")
|
|
19
|
+
raise ConnectionError("Failed to connect to WebSocket server")
|
|
20
|
+
|
|
21
|
+
def robot_version(self)->str:
|
|
22
|
+
try:
|
|
23
|
+
param_service = roslibpy.Param(self.websocket.client, 'robot_version')
|
|
24
|
+
param = param_service.get()
|
|
25
|
+
if param is None:
|
|
26
|
+
SDKLogger.error("robot_version parameter not found")
|
|
27
|
+
return None
|
|
28
|
+
return param
|
|
29
|
+
except Exception as e:
|
|
30
|
+
SDKLogger.error(f"Failed to get robot_version: {e}")
|
|
31
|
+
return None
|
|
32
|
+
def init_stand_height(self)->float:
|
|
33
|
+
try:
|
|
34
|
+
param_service = roslibpy.Param(self.websocket.client, 'com_height')
|
|
35
|
+
param = param_service.get()
|
|
36
|
+
if param is None:
|
|
37
|
+
SDKLogger.error("com_height parameter not found")
|
|
38
|
+
# KUAVO-4PRO
|
|
39
|
+
return 0.8328437523948975
|
|
40
|
+
return param
|
|
41
|
+
except Exception as e:
|
|
42
|
+
SDKLogger.error(f"Failed to get com_height: {e}")
|
|
43
|
+
return 0.8328437523948975
|
|
44
|
+
|
|
45
|
+
def arm_dof(self)->int:
|
|
46
|
+
try:
|
|
47
|
+
param_service = roslibpy.Param(self.websocket.client, 'armRealDof')
|
|
48
|
+
param = param_service.get()
|
|
49
|
+
if param is None:
|
|
50
|
+
SDKLogger.error("armRealDof parameter not found")
|
|
51
|
+
return None
|
|
52
|
+
return param
|
|
53
|
+
except Exception as e:
|
|
54
|
+
SDKLogger.error(f"Failed to get armRealDof: {e}")
|
|
55
|
+
return None
|
|
56
|
+
|
|
57
|
+
def head_dof(self)->int:
|
|
58
|
+
try:
|
|
59
|
+
param_service = roslibpy.Param(self.websocket.client, 'headRealDof')
|
|
60
|
+
param = param_service.get()
|
|
61
|
+
if param is None:
|
|
62
|
+
SDKLogger.error("headRealDof parameter not found")
|
|
63
|
+
return None
|
|
64
|
+
return param
|
|
65
|
+
except Exception as e:
|
|
66
|
+
SDKLogger.error(f"Failed to get headRealDof: {e}")
|
|
67
|
+
return None
|
|
68
|
+
|
|
69
|
+
def leg_dof(self)->int:
|
|
70
|
+
try:
|
|
71
|
+
param_service = roslibpy.Param(self.websocket.client, 'legRealDof')
|
|
72
|
+
param = param_service.get()
|
|
73
|
+
if param is None:
|
|
74
|
+
SDKLogger.error("legRealDof parameter not found")
|
|
75
|
+
return None
|
|
76
|
+
return param
|
|
77
|
+
except Exception as e:
|
|
78
|
+
SDKLogger.error(f"Failed to get legRealDof: {e}")
|
|
79
|
+
return None
|
|
80
|
+
|
|
81
|
+
def waist_dof(self)->int:
|
|
82
|
+
try:
|
|
83
|
+
param_service = roslibpy.Param(self.websocket.client, 'waistRealDof')
|
|
84
|
+
param = param_service.get()
|
|
85
|
+
if param is None:
|
|
86
|
+
# If parameter not found, default to 0 (no waist joint)
|
|
87
|
+
SDKLogger.debug("waistRealDof parameter not found, defaulting to 0")
|
|
88
|
+
return 0
|
|
89
|
+
return param
|
|
90
|
+
except Exception as e:
|
|
91
|
+
# If parameter doesn't exist or error occurs, default to 0
|
|
92
|
+
SDKLogger.debug(f"Failed to get waistRealDof: {e}, defaulting to 0")
|
|
93
|
+
return 0
|
|
94
|
+
|
|
95
|
+
def end_effector_type(self)->str:
|
|
96
|
+
try:
|
|
97
|
+
param_service = roslibpy.Param(self.websocket.client, 'end_effector_type')
|
|
98
|
+
param = param_service.get()
|
|
99
|
+
if param is None:
|
|
100
|
+
SDKLogger.error("end_effector_type parameter not found")
|
|
101
|
+
return None
|
|
102
|
+
return param
|
|
103
|
+
except Exception as e:
|
|
104
|
+
SDKLogger.error(f"Failed to get end_effector_type: {e}")
|
|
105
|
+
return None
|
|
106
|
+
|
|
107
|
+
def humanoid_description(self)->str:
|
|
108
|
+
try:
|
|
109
|
+
param_service = roslibpy.Param(self.websocket.client, 'humanoid_description')
|
|
110
|
+
param = param_service.get()
|
|
111
|
+
if param is None:
|
|
112
|
+
SDKLogger.error("humanoid_description parameter not found")
|
|
113
|
+
return None
|
|
114
|
+
return param
|
|
115
|
+
except Exception as e:
|
|
116
|
+
SDKLogger.error(f"Failed to get humanoid_description: {e}")
|
|
117
|
+
return None
|
|
118
|
+
|
|
119
|
+
def model_path(self)->str:
|
|
120
|
+
try:
|
|
121
|
+
param_service = roslibpy.Param(self.websocket.client, 'modelPath')
|
|
122
|
+
param = param_service.get()
|
|
123
|
+
if param is None:
|
|
124
|
+
SDKLogger.error("modelPath parameter not found")
|
|
125
|
+
return None
|
|
126
|
+
return param
|
|
127
|
+
except Exception as e:
|
|
128
|
+
SDKLogger.error(f"Failed to get modelPath: {e}")
|
|
129
|
+
return None
|
|
130
|
+
|
|
131
|
+
def kuavo_config(self)->str:
|
|
132
|
+
try:
|
|
133
|
+
param_service = roslibpy.Param(self.websocket.client, 'kuavo_configuration')
|
|
134
|
+
param = param_service.get()
|
|
135
|
+
if param is None:
|
|
136
|
+
SDKLogger.error("kuavo_configuration parameter not found")
|
|
137
|
+
return None
|
|
138
|
+
return param
|
|
139
|
+
except Exception as e:
|
|
140
|
+
SDKLogger.error(f"Failed to get kuavo_configuration: {e}")
|
|
141
|
+
return None
|
|
142
|
+
|
|
143
|
+
def initial_state(self)->str:
|
|
144
|
+
try:
|
|
145
|
+
param_service = roslibpy.Param(self.websocket.client, 'initial_state')
|
|
146
|
+
param = param_service.get()
|
|
147
|
+
if param is None:
|
|
148
|
+
SDKLogger.error("initial_state parameter not found")
|
|
149
|
+
return None
|
|
150
|
+
return param
|
|
151
|
+
except Exception as e:
|
|
152
|
+
SDKLogger.error(f"Failed to get initial_state: {e}")
|
|
153
|
+
return None
|
|
154
|
+
|
|
155
|
+
|
|
156
|
+
def joint_names()->dict:
|
|
157
|
+
kuavo_ros_param = RosParamWebsocket()
|
|
158
|
+
|
|
159
|
+
robot_version = kuavo_ros_param.robot_version()
|
|
160
|
+
if robot_version is None:
|
|
161
|
+
SDKLogger.error("robot_version parameter not found")
|
|
162
|
+
return None
|
|
163
|
+
|
|
164
|
+
robot_version_major = (int(robot_version) // 10) % 10
|
|
165
|
+
|
|
166
|
+
if robot_version_major == 1:
|
|
167
|
+
leg_link_names = [
|
|
168
|
+
'leg_l1_link', 'leg_l2_link', 'leg_l3_link', 'leg_l4_link', 'leg_l5_link', 'leg_l6_link',
|
|
169
|
+
'leg_r1_link', 'leg_r2_link', 'leg_r3_link', 'leg_r4_link', 'leg_r5_link', 'leg_r6_link'
|
|
170
|
+
]
|
|
171
|
+
waist_link_names = [
|
|
172
|
+
'waist_yaw_link'
|
|
173
|
+
]
|
|
174
|
+
arm_link_names = [
|
|
175
|
+
'zarm_l1_link', 'zarm_l2_link', 'zarm_l3_link', 'zarm_l4_link',
|
|
176
|
+
'zarm_r1_link', 'zarm_r2_link', 'zarm_r3_link', 'zarm_r4_link',
|
|
177
|
+
]
|
|
178
|
+
head_link_names = [
|
|
179
|
+
'zhead_1_link', 'zhead_2_link'
|
|
180
|
+
]
|
|
181
|
+
elif robot_version_major == 4:
|
|
182
|
+
leg_link_names = [
|
|
183
|
+
'leg_l1_link', 'leg_l2_link', 'leg_l3_link', 'leg_l4_link', 'leg_l5_link', 'leg_l6_link',
|
|
184
|
+
'leg_r1_link', 'leg_r2_link', 'leg_r3_link', 'leg_r4_link', 'leg_r5_link', 'leg_r6_link'
|
|
185
|
+
]
|
|
186
|
+
waist_link_names = []
|
|
187
|
+
arm_link_names = [
|
|
188
|
+
'zarm_l1_link', 'zarm_l2_link', 'zarm_l3_link', 'zarm_l4_link', 'zarm_l5_link', 'zarm_l6_link', 'zarm_l7_link',
|
|
189
|
+
'zarm_r1_link', 'zarm_r2_link', 'zarm_r3_link', 'zarm_r4_link', 'zarm_r5_link', 'zarm_r6_link', 'zarm_r7_link',
|
|
190
|
+
]
|
|
191
|
+
head_link_names = [
|
|
192
|
+
'zhead_1_link', 'zhead_2_link'
|
|
193
|
+
]
|
|
194
|
+
elif robot_version_major == 5:
|
|
195
|
+
leg_link_names = [
|
|
196
|
+
'leg_l1_link', 'leg_l2_link', 'leg_l3_link', 'leg_l4_link', 'leg_l5_link', 'leg_l6_link',
|
|
197
|
+
'leg_r1_link', 'leg_r2_link', 'leg_r3_link', 'leg_r4_link', 'leg_r5_link', 'leg_r6_link'
|
|
198
|
+
]
|
|
199
|
+
waist_link_names = [
|
|
200
|
+
'waist_yaw_link'
|
|
201
|
+
]
|
|
202
|
+
arm_link_names = [
|
|
203
|
+
'zarm_l1_link', 'zarm_l2_link', 'zarm_l3_link', 'zarm_l4_link', 'zarm_l5_link', 'zarm_l6_link', 'zarm_l7_link',
|
|
204
|
+
'zarm_r1_link', 'zarm_r2_link', 'zarm_r3_link', 'zarm_r4_link', 'zarm_r5_link', 'zarm_r6_link', 'zarm_r7_link',
|
|
205
|
+
]
|
|
206
|
+
|
|
207
|
+
head_link_names = [
|
|
208
|
+
'zhead_1_link', 'zhead_2_link'
|
|
209
|
+
]
|
|
210
|
+
leg_link_names += waist_link_names
|
|
211
|
+
else:
|
|
212
|
+
leg_link_names = [
|
|
213
|
+
'knee_link', 'leg_link', 'waist_link', 'waist_yaw_link'
|
|
214
|
+
]
|
|
215
|
+
arm_link_names = []
|
|
216
|
+
head_link_names = []
|
|
217
|
+
|
|
218
|
+
robot_desc = kuavo_ros_param.humanoid_description()
|
|
219
|
+
if robot_desc is None:
|
|
220
|
+
return None
|
|
221
|
+
|
|
222
|
+
"""
|
|
223
|
+
<link name="leg_l1_link">
|
|
224
|
+
<inertial>
|
|
225
|
+
....
|
|
226
|
+
</inertial>
|
|
227
|
+
<visual>
|
|
228
|
+
...
|
|
229
|
+
<geometry>
|
|
230
|
+
<mesh filename="package://kuavo_assets/models/biped_s43/meshes/l_leg_roll.STL" />
|
|
231
|
+
</geometry>
|
|
232
|
+
...
|
|
233
|
+
</visual>
|
|
234
|
+
</link>
|
|
235
|
+
"""
|
|
236
|
+
root = ET.fromstring(robot_desc)
|
|
237
|
+
|
|
238
|
+
def process_link_name(link_name):
|
|
239
|
+
"""从URDF中提取与link对应的joint名称"""
|
|
240
|
+
# 查找child link等于目标link_name的joint
|
|
241
|
+
# 遍历所有joint,找到child link匹配的joint
|
|
242
|
+
for joint_elem in root.findall(".//joint"):
|
|
243
|
+
child_elem = joint_elem.find("child")
|
|
244
|
+
if child_elem is not None and child_elem.get("link") == link_name:
|
|
245
|
+
joint_name = joint_elem.get("name")
|
|
246
|
+
if joint_name:
|
|
247
|
+
return joint_name
|
|
248
|
+
|
|
249
|
+
# 如果找不到joint,记录警告并返回None
|
|
250
|
+
SDKLogger.warn(f"Warning: Joint for link {link_name} not found in URDF")
|
|
251
|
+
return None
|
|
252
|
+
leg_joint_names = [process_link_name(link_name) for link_name in leg_link_names if process_link_name(link_name) is not None]
|
|
253
|
+
arm_joint_names = [process_link_name(link_name) for link_name in arm_link_names if process_link_name(link_name) is not None]
|
|
254
|
+
head_joint_names = [process_link_name(link_name) for link_name in head_link_names if process_link_name(link_name) is not None]
|
|
255
|
+
|
|
256
|
+
# For robots with 4-dof arms, we allow arm_link_names to be fewer than expected
|
|
257
|
+
if robot_version_major == 1:
|
|
258
|
+
if len(leg_link_names) != len(leg_joint_names):
|
|
259
|
+
SDKLogger.warn(
|
|
260
|
+
f"leg_joint_names is not equal to leg_link_names, {len(leg_link_names)} != {len(leg_joint_names)}")
|
|
261
|
+
return None
|
|
262
|
+
if len(arm_link_names) != len(arm_joint_names):
|
|
263
|
+
SDKLogger.warn(
|
|
264
|
+
f"arm_joint_names is not equal to arm_link_names, {len(arm_link_names)}!= {len(arm_joint_names)}")
|
|
265
|
+
return None
|
|
266
|
+
if len(head_link_names) != len(head_joint_names):
|
|
267
|
+
SDKLogger.warn(
|
|
268
|
+
f"head_joint_names is not equal to head_link_names, {len(head_link_names)}!= {len(head_joint_names)}")
|
|
269
|
+
return None
|
|
270
|
+
else:
|
|
271
|
+
if len(leg_link_names) != len(leg_joint_names):
|
|
272
|
+
SDKLogger.warn(f"leg_joint_names is not equal to leg_link_names, {len(leg_link_names)} != {len(leg_joint_names)}")
|
|
273
|
+
return None
|
|
274
|
+
if len(arm_link_names)!= len(arm_joint_names):
|
|
275
|
+
SDKLogger.warn(f"arm_joint_names is not equal to arm_link_names, {len(arm_link_names)}!= {len(arm_joint_names)}")
|
|
276
|
+
return None
|
|
277
|
+
if len(head_link_names)!= len(head_joint_names):
|
|
278
|
+
SDKLogger.warn(f"head_joint_names is not equal to head_link_names, {len(head_link_names)}!= {len(head_joint_names)}")
|
|
279
|
+
return None
|
|
280
|
+
|
|
281
|
+
return leg_joint_names + arm_joint_names + head_joint_names
|
|
282
|
+
|
|
283
|
+
kuavo_ros_info = None
|
|
284
|
+
|
|
285
|
+
def end_frames_names()->dict:
|
|
286
|
+
default = ["torso", "zarm_l7_link", "zarm_r7_link", "zarm_l4_link", "zarm_r4_link"]
|
|
287
|
+
kuavo_ros_param = RosParamWebsocket()
|
|
288
|
+
|
|
289
|
+
kuavo_json = kuavo_ros_param.kuavo_config()
|
|
290
|
+
if kuavo_json is None:
|
|
291
|
+
return default
|
|
292
|
+
|
|
293
|
+
try:
|
|
294
|
+
kuavo_config = json.loads(kuavo_json)
|
|
295
|
+
# 为了兼容旧版本:优先使用 end_frames_names,如果没有则使用 end_frames_name_ik
|
|
296
|
+
if kuavo_config.get('end_frames_names') is not None:
|
|
297
|
+
return kuavo_config.get('end_frames_names')
|
|
298
|
+
elif kuavo_config.get('end_frames_name_ik') is not None:
|
|
299
|
+
return kuavo_config.get('end_frames_name_ik')
|
|
300
|
+
else:
|
|
301
|
+
return default
|
|
302
|
+
except Exception as e:
|
|
303
|
+
print(f"Failed to get end_frames_name_ik from kuavo_json: {e}")
|
|
304
|
+
return default
|
|
305
|
+
|
|
306
|
+
def make_robot_param()->dict:
|
|
307
|
+
global kuavo_ros_info
|
|
308
|
+
if kuavo_ros_info is not None:
|
|
309
|
+
return kuavo_ros_info
|
|
310
|
+
|
|
311
|
+
kuavo_ros_param = RosParamWebsocket()
|
|
312
|
+
|
|
313
|
+
kuavo_ros_info = {
|
|
314
|
+
'robot_version': kuavo_ros_param.robot_version(),
|
|
315
|
+
'arm_dof': kuavo_ros_param.arm_dof(),
|
|
316
|
+
'head_dof': kuavo_ros_param.head_dof(),
|
|
317
|
+
'leg_dof': kuavo_ros_param.leg_dof(),
|
|
318
|
+
'waist_dof': kuavo_ros_param.waist_dof(),
|
|
319
|
+
'end_effector_type': kuavo_ros_param.end_effector_type(),
|
|
320
|
+
'joint_names': joint_names(),
|
|
321
|
+
'end_frames_names': end_frames_names(),
|
|
322
|
+
'init_stand_height': kuavo_ros_param.init_stand_height()
|
|
323
|
+
}
|
|
324
|
+
|
|
325
|
+
for key, value in kuavo_ros_info.items():
|
|
326
|
+
if value is None and key != 'end_effector_type':
|
|
327
|
+
SDKLogger.debug(f"[Error]: Failed to get '{key}' from ROS.")
|
|
328
|
+
kuavo_ros_info = None
|
|
329
|
+
raise Exception(f"[Error]: Failed to get '{key}' from ROS.")
|
|
330
|
+
|
|
331
|
+
return kuavo_ros_info
|
|
332
|
+
|
|
333
|
+
# if __name__ == "__main__":
|
|
334
|
+
# rospy.init_node("kuavo_ros_param_test")
|
|
335
|
+
# 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()
|