kuavo-humanoid-sdk-ws 1.3.2__20260122221834-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.2.dist-info/METADATA +276 -0
- kuavo_humanoid_sdk_ws-1.3.2.dist-info/RECORD +43 -0
- kuavo_humanoid_sdk_ws-1.3.2.dist-info/WHEEL +6 -0
- kuavo_humanoid_sdk_ws-1.3.2.dist-info/top_level.txt +1 -0
|
@@ -0,0 +1,235 @@
|
|
|
1
|
+
#!/usr/bin/env python3
|
|
2
|
+
# coding: utf-8
|
|
3
|
+
|
|
4
|
+
import math
|
|
5
|
+
from typing import Tuple
|
|
6
|
+
from kuavo_humanoid_sdk.interfaces.data_types import KuavoArmCtrlMode, KuavoIKParams, KuavoPose, KuavoManipulationMpcFrame, KuavoManipulationMpcCtrlMode, KuavoManipulationMpcControlFlow
|
|
7
|
+
from kuavo_humanoid_sdk.kuavo.core.core import KuavoRobotCore
|
|
8
|
+
from kuavo_humanoid_sdk.kuavo.robot_info import KuavoRobotInfo
|
|
9
|
+
|
|
10
|
+
class KuavoRobotArm:
|
|
11
|
+
def __init__(self):
|
|
12
|
+
self._kuavo_core = KuavoRobotCore()
|
|
13
|
+
self._robot_info = KuavoRobotInfo(robot_type="kuavo")
|
|
14
|
+
|
|
15
|
+
def arm_reset(self)-> bool:
|
|
16
|
+
return self._kuavo_core.robot_arm_reset()
|
|
17
|
+
|
|
18
|
+
def manipulation_mpc_reset(self)-> bool:
|
|
19
|
+
return self._kuavo_core.robot_manipulation_mpc_reset()
|
|
20
|
+
|
|
21
|
+
def control_arm_joint_positions(self, joint_position:list)->bool:
|
|
22
|
+
"""
|
|
23
|
+
Control the position of the robot arm joint.
|
|
24
|
+
Args:
|
|
25
|
+
joint_position (list): List of joint positions in radians
|
|
26
|
+
Raises:
|
|
27
|
+
ValueError: If the joint position list is not of the correct length.
|
|
28
|
+
RuntimeError: If the robot is not in stance state when trying to control the arm.
|
|
29
|
+
Returns:
|
|
30
|
+
True if the control was successful, False otherwise.
|
|
31
|
+
Note:
|
|
32
|
+
Joint positions that exceed physical limits will be automatically clipped to the limit values.
|
|
33
|
+
"""
|
|
34
|
+
if len(joint_position) != self._robot_info.arm_joint_dof:
|
|
35
|
+
raise ValueError("Invalid position length. Expected {}, got {}".format(self._robot_info.arm_joint_dof, len(joint_position)))
|
|
36
|
+
|
|
37
|
+
# Automatically clip joint positions to physical limits
|
|
38
|
+
arm_min, arm_max = self._robot_info.get_arm_joint_limits()
|
|
39
|
+
joint_position_clipped = list(joint_position) # Create a copy to avoid modifying the original list
|
|
40
|
+
|
|
41
|
+
for i, pos in enumerate(joint_position):
|
|
42
|
+
if pos < arm_min[i] or pos > arm_max[i]:
|
|
43
|
+
# Automatically clip to limits
|
|
44
|
+
joint_position_clipped[i] = max(arm_min[i], min(pos, arm_max[i]))
|
|
45
|
+
|
|
46
|
+
return self._kuavo_core.control_robot_arm_joint_positions(joint_data=joint_position_clipped)
|
|
47
|
+
|
|
48
|
+
def control_arm_joint_trajectory(self, times:list, joint_q:list)->bool:
|
|
49
|
+
"""
|
|
50
|
+
Control the target poses of the robot arm.
|
|
51
|
+
Args:
|
|
52
|
+
times (list): List of time intervals in seconds
|
|
53
|
+
joint_q (list): List of joint positions in radians
|
|
54
|
+
Raises:
|
|
55
|
+
ValueError: If the times list is not of the correct length.
|
|
56
|
+
ValueError: If the joint position list is not of the correct length.
|
|
57
|
+
RuntimeError: If the robot is not in stance state when trying to control the arm.
|
|
58
|
+
Returns:
|
|
59
|
+
bool: True if the control was successful, False otherwise.
|
|
60
|
+
Note:
|
|
61
|
+
Joint positions that exceed physical limits will be automatically clipped to the limit values.
|
|
62
|
+
"""
|
|
63
|
+
if len(times) != len(joint_q):
|
|
64
|
+
raise ValueError("Invalid input. times and joint_q must have thesame length.")
|
|
65
|
+
|
|
66
|
+
# Automatically clip joint positions to physical limits
|
|
67
|
+
arm_min, arm_max = self._robot_info.get_arm_joint_limits()
|
|
68
|
+
q_degs = []
|
|
69
|
+
for frame_idx, q in enumerate(joint_q):
|
|
70
|
+
if len(q) != self._robot_info.arm_joint_dof:
|
|
71
|
+
raise ValueError("Invalid position length. Expected {}, got {}".format(self._robot_info.arm_joint_dof, len(q)))
|
|
72
|
+
|
|
73
|
+
# Create a copy to avoid modifying the original list
|
|
74
|
+
q_clipped = list(q)
|
|
75
|
+
|
|
76
|
+
# Automatically clip each joint position to physical limits
|
|
77
|
+
for joint_idx, pos in enumerate(q):
|
|
78
|
+
if pos < arm_min[joint_idx] or pos > arm_max[joint_idx]:
|
|
79
|
+
# Automatically clip to limits
|
|
80
|
+
q_clipped[joint_idx] = max(arm_min[joint_idx], min(pos, arm_max[joint_idx]))
|
|
81
|
+
|
|
82
|
+
# Convert joint positions from radians to degrees
|
|
83
|
+
q_degs.append([(p * 180.0 / math.pi) for p in q_clipped])
|
|
84
|
+
|
|
85
|
+
return self._kuavo_core.control_robot_arm_joint_trajectory(times=times, joint_q=q_degs)
|
|
86
|
+
|
|
87
|
+
def control_robot_end_effector_pose(self, left_pose: KuavoPose, right_pose: KuavoPose, frame: KuavoManipulationMpcFrame)->bool:
|
|
88
|
+
"""
|
|
89
|
+
Control the end effector pose of the robot arm.
|
|
90
|
+
Args:
|
|
91
|
+
left_pose (KuavoPose): Pose of the robot left arm, xyz and quat.
|
|
92
|
+
right_pose (KuavoPose): Pose of the robot right arm, xyz and quat.
|
|
93
|
+
frame (KuavoManipulationMpcFrame): Frame of the robot end effector pose.
|
|
94
|
+
Returns:
|
|
95
|
+
bool: True if the control was successful, False otherwise.
|
|
96
|
+
"""
|
|
97
|
+
return self._kuavo_core.control_robot_end_effector_pose(left_pose, right_pose, frame)
|
|
98
|
+
|
|
99
|
+
def is_arm_collision(self)->bool:
|
|
100
|
+
"""Check if the arm is in collision.
|
|
101
|
+
"""
|
|
102
|
+
return self._kuavo_core.is_arm_collision()
|
|
103
|
+
|
|
104
|
+
def is_arm_collision_mode(self)->bool:
|
|
105
|
+
"""Check if arm collision mode is enabled.
|
|
106
|
+
|
|
107
|
+
Returns:
|
|
108
|
+
bool: True if collision mode is enabled, False otherwise.
|
|
109
|
+
"""
|
|
110
|
+
return self._kuavo_core.is_arm_collision_mode()
|
|
111
|
+
|
|
112
|
+
def wait_arm_collision_complete(self):
|
|
113
|
+
"""Wait for the arm collision to complete.
|
|
114
|
+
"""
|
|
115
|
+
self._kuavo_core.wait_arm_collision_complete()
|
|
116
|
+
|
|
117
|
+
def release_arm_collision_mode(self):
|
|
118
|
+
"""Release the arm collision mode.
|
|
119
|
+
"""
|
|
120
|
+
self._kuavo_core.release_arm_collision_mode()
|
|
121
|
+
|
|
122
|
+
def set_arm_collision_mode(self, enable: bool):
|
|
123
|
+
"""Set the arm collision mode.
|
|
124
|
+
"""
|
|
125
|
+
self._kuavo_core.set_arm_collision_mode(enable)
|
|
126
|
+
|
|
127
|
+
def set_fixed_arm_mode(self) -> bool:
|
|
128
|
+
"""
|
|
129
|
+
Freezes the robot arm.
|
|
130
|
+
Returns:
|
|
131
|
+
bool: True if the arm is frozen successfully, False otherwise.
|
|
132
|
+
"""
|
|
133
|
+
return self._kuavo_core.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ArmFixed)
|
|
134
|
+
|
|
135
|
+
def set_auto_swing_arm_mode(self) -> bool:
|
|
136
|
+
"""
|
|
137
|
+
Swing the robot arm.
|
|
138
|
+
Returns:
|
|
139
|
+
bool: True if the arm is swinging successfully, False otherwise.
|
|
140
|
+
"""
|
|
141
|
+
return self._kuavo_core.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.AutoSwing)
|
|
142
|
+
|
|
143
|
+
def set_external_control_arm_mode(self) -> bool:
|
|
144
|
+
"""
|
|
145
|
+
External control the robot arm.
|
|
146
|
+
Returns:
|
|
147
|
+
bool: True if the arm is external controlled successfully, False otherwise.
|
|
148
|
+
"""
|
|
149
|
+
return self._kuavo_core.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ExternalControl)
|
|
150
|
+
|
|
151
|
+
def set_manipulation_mpc_mode(self, ctrl_mode: KuavoManipulationMpcCtrlMode) -> bool:
|
|
152
|
+
"""
|
|
153
|
+
Set the manipulation mpc mode.
|
|
154
|
+
Returns:
|
|
155
|
+
bool: True if the manipulation mpc mode is set successfully, False otherwise.
|
|
156
|
+
"""
|
|
157
|
+
return self._kuavo_core.change_manipulation_mpc_ctrl_mode(ctrl_mode)
|
|
158
|
+
|
|
159
|
+
def set_manipulation_mpc_control_flow(self, control_flow: KuavoManipulationMpcControlFlow) -> bool:
|
|
160
|
+
"""
|
|
161
|
+
Set the manipulation mpc control flow.
|
|
162
|
+
Returns:
|
|
163
|
+
bool: True if the manipulation mpc control flow is set successfully, False otherwise.
|
|
164
|
+
"""
|
|
165
|
+
return self._kuavo_core.change_manipulation_mpc_control_flow(control_flow)
|
|
166
|
+
|
|
167
|
+
def set_manipulation_mpc_frame(self, frame: KuavoManipulationMpcFrame) -> bool:
|
|
168
|
+
"""
|
|
169
|
+
Set the manipulation mpc frame.
|
|
170
|
+
Returns:
|
|
171
|
+
bool: True if the manipulation mpc frame is set successfully, False otherwise.
|
|
172
|
+
"""
|
|
173
|
+
return self._kuavo_core.change_manipulation_mpc_frame(frame)
|
|
174
|
+
|
|
175
|
+
""" Arm Forward kinematics && Arm Inverse kinematics """
|
|
176
|
+
def arm_ik(self,
|
|
177
|
+
left_pose: KuavoPose,
|
|
178
|
+
right_pose: KuavoPose,
|
|
179
|
+
left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
|
|
180
|
+
right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
|
|
181
|
+
arm_q0: list = None,
|
|
182
|
+
params: KuavoIKParams=None) -> list:
|
|
183
|
+
"""Inverse kinematics for the robot arm.
|
|
184
|
+
|
|
185
|
+
Args:
|
|
186
|
+
left_pose (KuavoPose): Pose of the robot left arm, xyz and quat.
|
|
187
|
+
right_pose (KuavoPose): Pose of the robot right arm, xyz and quat.
|
|
188
|
+
left_elbow_pos_xyz (list): Position of the robot left elbow. If [0.0, 0.0, 0.0], will be ignored.
|
|
189
|
+
right_elbow_pos_xyz (list): Position of the robot right elbow. If [0.0, 0.0, 0.0], will be ignored.
|
|
190
|
+
arm_q0 (list, optional): Initial joint positions in radians. If None, will be ignored.
|
|
191
|
+
params (KuavoIKParams, optional): Parameters for the inverse kinematics. If None, will be ignored.
|
|
192
|
+
Contains:
|
|
193
|
+
- major_optimality_tol: Major optimality tolerance
|
|
194
|
+
- major_feasibility_tol: Major feasibility tolerance
|
|
195
|
+
- minor_feasibility_tol: Minor feasibility tolerance
|
|
196
|
+
- major_iterations_limit: Major iterations limit
|
|
197
|
+
- oritation_constraint_tol: Orientation constraint tolerance
|
|
198
|
+
- pos_constraint_tol: Position constraint tolerance, works when pos_cost_weight==0.0
|
|
199
|
+
- pos_cost_weight: Position cost weight. Set to 0.0 for high accuracy
|
|
200
|
+
|
|
201
|
+
Returns:
|
|
202
|
+
list: List of joint positions in radians, or None if inverse kinematics failed.
|
|
203
|
+
|
|
204
|
+
Warning:
|
|
205
|
+
This function requires initializing the SDK with the :attr:`KuavoSDK.Options.WithIK`.
|
|
206
|
+
"""
|
|
207
|
+
return self._kuavo_core.arm_ik(left_pose, right_pose, left_elbow_pos_xyz, right_elbow_pos_xyz, arm_q0, params)
|
|
208
|
+
|
|
209
|
+
def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
|
|
210
|
+
"""Forward kinematics for the robot arm.
|
|
211
|
+
|
|
212
|
+
Args:
|
|
213
|
+
q (list): List of joint positions in radians.
|
|
214
|
+
|
|
215
|
+
Returns:
|
|
216
|
+
Tuple[KuavoPose, KuavoPose]: Tuple of poses for the robot left arm and right arm,
|
|
217
|
+
or (None, None) if forward kinematics failed.
|
|
218
|
+
|
|
219
|
+
Warning:
|
|
220
|
+
This function requires initializing the SDK with the :attr:`KuavoSDK.Options.WithIK`.
|
|
221
|
+
"""
|
|
222
|
+
if len(q) != self._robot_info.arm_joint_dof:
|
|
223
|
+
raise ValueError("Invalid position length. Expected {}, got {}".format(self._robot_info.arm_joint_dof, len(q)))
|
|
224
|
+
|
|
225
|
+
result = self._kuavo_core.arm_fk(q)
|
|
226
|
+
if result is None:
|
|
227
|
+
return None, None
|
|
228
|
+
return result
|
|
229
|
+
|
|
230
|
+
# if __name__ == "__main__":
|
|
231
|
+
# arm = KuavoRobotArm()
|
|
232
|
+
# arm.set_manipulation_mpc_mode(KuavoManipulationMpcCtrlMode.ArmOnly)
|
|
233
|
+
# arm.set_manipulation_mpc_control_flow(KuavoManipulationMpcControlFlow.DirectToWbc)
|
|
234
|
+
# arm.set_manipulation_mpc_frame(KuavoManipulationMpcFrame.WorldFrame)
|
|
235
|
+
# arm.control_robot_end_effector_pose(KuavoPose(position=[0.3, 0.4, 0.9], orientation=[0.0, 0.0, 0.0, 1.0]), KuavoPose(position=[0.3, -0.5, 1.0], orientation=[0.0, 0.0, 0.0, 1.0]), KuavoManipulationMpcFrame.WorldFrame)
|
|
@@ -0,0 +1,39 @@
|
|
|
1
|
+
#!/usr/bin/env python3
|
|
2
|
+
# coding: utf-8
|
|
3
|
+
from kuavo_humanoid_sdk.kuavo.core.audio import KuavoRobotAudioCore
|
|
4
|
+
|
|
5
|
+
class KuavoRobotAudio:
|
|
6
|
+
"""Audio system interface for controlling audio playback functionality of Kuavo humanoid robot.
|
|
7
|
+
|
|
8
|
+
Provides functionality to play music files.
|
|
9
|
+
"""
|
|
10
|
+
|
|
11
|
+
def __init__(self):
|
|
12
|
+
"""Initialize the audio system."""
|
|
13
|
+
self.audio = KuavoRobotAudioCore()
|
|
14
|
+
|
|
15
|
+
def play_audio(self, file_name: str, volume: int = 100, speed: float = 1.0) -> bool:
|
|
16
|
+
"""Play the specified audio file.
|
|
17
|
+
|
|
18
|
+
Args:
|
|
19
|
+
file_name (str): Name of the audio file to play
|
|
20
|
+
|
|
21
|
+
Returns:
|
|
22
|
+
bool: True if the play request was successfully sent, False otherwise
|
|
23
|
+
"""
|
|
24
|
+
return self.audio.play_audio(file_name, volume, speed)
|
|
25
|
+
|
|
26
|
+
def stop_music(self):
|
|
27
|
+
"""Stop the currently playing audio."""
|
|
28
|
+
return self.audio.stop_music()
|
|
29
|
+
|
|
30
|
+
def text_to_speech(self, text: str, volume: float = 0.5) -> bool:
|
|
31
|
+
"""Synthesize and play the specified text.
|
|
32
|
+
|
|
33
|
+
Args:
|
|
34
|
+
text (str): Text to be played
|
|
35
|
+
|
|
36
|
+
Returns:
|
|
37
|
+
bool: True if the play request was successfully sent, False otherwise
|
|
38
|
+
"""
|
|
39
|
+
return self.audio.text_to_speech(text, volume)
|
|
@@ -0,0 +1,39 @@
|
|
|
1
|
+
#!/usr/bin/env python3
|
|
2
|
+
# coding: utf-8
|
|
3
|
+
import math
|
|
4
|
+
from kuavo_humanoid_sdk.kuavo.core.core import KuavoRobotCore
|
|
5
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
6
|
+
|
|
7
|
+
class KuavoRobotHead:
|
|
8
|
+
def __init__(self):
|
|
9
|
+
self._kuavo_core = KuavoRobotCore()
|
|
10
|
+
|
|
11
|
+
def control_head(self, yaw: float, pitch: float)->bool:
|
|
12
|
+
"""
|
|
13
|
+
Control the head of the robot.
|
|
14
|
+
Args:
|
|
15
|
+
yaw (float): The yaw angle of the head in radians, range [-1.396, 1.396] (-80 to 80 degrees).
|
|
16
|
+
pitch (float): The pitch angle of the head in radians, range [-0.436, 0.436] (-25 to 25 degrees).
|
|
17
|
+
Returns:
|
|
18
|
+
bool: True if the head is controlled successfully, False otherwise.
|
|
19
|
+
"""
|
|
20
|
+
# Check yaw limits (-80 to 80 degrees)
|
|
21
|
+
if yaw < -math.pi*4/9 or yaw > math.pi*4/9: # -80 to 80 degrees in radians
|
|
22
|
+
SDKLogger.warn(f"[Robot] yaw {yaw} exceeds limit [-{math.pi*4/9:.3f}, {math.pi*4/9:.3f}] radians (-80 to 80 degrees), will be limited")
|
|
23
|
+
limited_yaw = min(math.pi*4/9, max(-math.pi*4/9, yaw))
|
|
24
|
+
|
|
25
|
+
# Check pitch limits (-25 to 25 degrees)
|
|
26
|
+
if pitch < -math.pi/7.2 or pitch > math.pi/7.2: # -25 to 25 degrees in radians
|
|
27
|
+
SDKLogger.warn(f"[Robot] pitch {pitch} exceeds limit [-{math.pi/7.2:.3f}, {math.pi/7.2:.3f}] radians (-25 to 25 degrees), will be limited")
|
|
28
|
+
limited_pitch = min(math.pi/7.2, max(-math.pi/7.2, pitch))
|
|
29
|
+
return self._kuavo_core.control_robot_head(yaw=limited_yaw, pitch=limited_pitch)
|
|
30
|
+
|
|
31
|
+
def enable_head_tracking(self, target_id: int)->bool:
|
|
32
|
+
"""Enable the head tracking.
|
|
33
|
+
"""
|
|
34
|
+
return self._kuavo_core.enable_head_tracking(target_id)
|
|
35
|
+
|
|
36
|
+
def disable_head_tracking(self)->bool:
|
|
37
|
+
"""Disable the head tracking.
|
|
38
|
+
"""
|
|
39
|
+
return self._kuavo_core.disable_head_tracking()
|
|
@@ -0,0 +1,235 @@
|
|
|
1
|
+
#!/usr/bin/env python3
|
|
2
|
+
# coding: utf-8
|
|
3
|
+
from typing import Tuple
|
|
4
|
+
import math
|
|
5
|
+
import xml.etree.ElementTree as ET
|
|
6
|
+
from kuavo_humanoid_sdk.interfaces.robot_info import RobotInfoBase
|
|
7
|
+
from kuavo_humanoid_sdk.kuavo.core.ros.param import RosParamWebsocket, make_robot_param
|
|
8
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
9
|
+
|
|
10
|
+
class KuavoRobotInfo(RobotInfoBase):
|
|
11
|
+
def __init__(self, robot_type: str = "kuavo"):
|
|
12
|
+
super().__init__(robot_type=robot_type)
|
|
13
|
+
|
|
14
|
+
# Load robot parameters from ROS parameter server
|
|
15
|
+
kuavo_ros_param = make_robot_param()
|
|
16
|
+
self._ros_param = RosParamWebsocket()
|
|
17
|
+
|
|
18
|
+
self._robot_version = kuavo_ros_param['robot_version']
|
|
19
|
+
self._robot_version_major = (int(self._robot_version) // 10) % 10
|
|
20
|
+
self._end_effector_type = kuavo_ros_param['end_effector_type']
|
|
21
|
+
self._arm_joint_dof = kuavo_ros_param['arm_dof']
|
|
22
|
+
self._leg_joint_dof = kuavo_ros_param['leg_dof']
|
|
23
|
+
self._waist_joint_dof = kuavo_ros_param.get('waist_dof', 0) # 腰部关节自由度,默认为0
|
|
24
|
+
self._joint_dof = kuavo_ros_param['arm_dof'] + kuavo_ros_param['leg_dof'] + kuavo_ros_param['head_dof'] + self._waist_joint_dof
|
|
25
|
+
self._joint_names = kuavo_ros_param['joint_names']
|
|
26
|
+
self._end_frames_names = kuavo_ros_param['end_frames_names']
|
|
27
|
+
self._head_joint_dof = kuavo_ros_param['head_dof']
|
|
28
|
+
|
|
29
|
+
|
|
30
|
+
# 动态计算关节索引,避免硬编码
|
|
31
|
+
self._head_joint_names = self._joint_names[-self._head_joint_dof:]
|
|
32
|
+
|
|
33
|
+
if self._waist_joint_dof > 0:
|
|
34
|
+
self._waist_joint_names = self._joint_names[self._leg_joint_dof:self._leg_joint_dof + self._waist_joint_dof]
|
|
35
|
+
else:
|
|
36
|
+
self._waist_joint_names = []
|
|
37
|
+
|
|
38
|
+
# 根据版本计算手臂关节索引
|
|
39
|
+
if self._robot_version_major == 6:
|
|
40
|
+
wheel_joint_dof = 4
|
|
41
|
+
arm_start_idx = wheel_joint_dof
|
|
42
|
+
self._arm_joint_names = self._joint_names[arm_start_idx:arm_start_idx + self._arm_joint_dof]
|
|
43
|
+
else:
|
|
44
|
+
# 手臂关节起始索引需要考虑腰部关节的偏移
|
|
45
|
+
arm_start_idx = self._leg_joint_dof + self._waist_joint_dof
|
|
46
|
+
self._arm_joint_names = self._joint_names[arm_start_idx:arm_start_idx + self._arm_joint_dof]
|
|
47
|
+
self._init_stand_height = kuavo_ros_param['init_stand_height']
|
|
48
|
+
@property
|
|
49
|
+
def robot_version(self) -> str:
|
|
50
|
+
"""Return the version of the robot.
|
|
51
|
+
|
|
52
|
+
Returns:
|
|
53
|
+
str: The robot version, e.g. "42", "43"...
|
|
54
|
+
"""
|
|
55
|
+
return self._robot_version
|
|
56
|
+
|
|
57
|
+
@property
|
|
58
|
+
def end_effector_type(self) -> str:
|
|
59
|
+
"""Return the type of the end effector.
|
|
60
|
+
|
|
61
|
+
Returns:
|
|
62
|
+
str: The end effector type, where:
|
|
63
|
+
- "qiangnao" means "dexteroushand"
|
|
64
|
+
- "lejuclaw" means "lejuclaw"
|
|
65
|
+
- "qiangnao_touch" means "touchdexteroushand"
|
|
66
|
+
- ...
|
|
67
|
+
"""
|
|
68
|
+
return self._end_effector_type
|
|
69
|
+
|
|
70
|
+
@property
|
|
71
|
+
def joint_names(self) -> list:
|
|
72
|
+
"""Return the names of all joints in the robot.
|
|
73
|
+
|
|
74
|
+
Returns:
|
|
75
|
+
list: A list containing the names of all robot joints.
|
|
76
|
+
"""
|
|
77
|
+
return self._joint_names
|
|
78
|
+
|
|
79
|
+
@property
|
|
80
|
+
def joint_dof(self) -> int:
|
|
81
|
+
"""Return the total number of joints in the robot.
|
|
82
|
+
|
|
83
|
+
Returns:
|
|
84
|
+
int: Total number of joints, e.g. 28
|
|
85
|
+
"""
|
|
86
|
+
return self._joint_dof
|
|
87
|
+
|
|
88
|
+
@property
|
|
89
|
+
def arm_joint_dof(self) -> int:
|
|
90
|
+
"""Return the number of joints in the double-arm.
|
|
91
|
+
|
|
92
|
+
Returns:
|
|
93
|
+
int: Number of joints in double-arm, e.g. 14
|
|
94
|
+
"""
|
|
95
|
+
return self._arm_joint_dof
|
|
96
|
+
|
|
97
|
+
@property
|
|
98
|
+
def arm_joint_names(self) -> list:
|
|
99
|
+
"""Return the names of joints in the double-arm.
|
|
100
|
+
|
|
101
|
+
Returns:
|
|
102
|
+
list: A list containing the names of joints in the double-arm.
|
|
103
|
+
"""
|
|
104
|
+
return self._arm_joint_names
|
|
105
|
+
|
|
106
|
+
@property
|
|
107
|
+
def head_joint_dof(self) -> int:
|
|
108
|
+
"""Return the number of joints in the head.
|
|
109
|
+
|
|
110
|
+
Returns:
|
|
111
|
+
int: Number of joints in head, e.g. 2
|
|
112
|
+
"""
|
|
113
|
+
return self._head_joint_dof
|
|
114
|
+
|
|
115
|
+
@property
|
|
116
|
+
def waist_joint_dof(self) -> int:
|
|
117
|
+
"""Return the number of joints in the waist.
|
|
118
|
+
|
|
119
|
+
Returns:
|
|
120
|
+
int: Number of joints in waist, e.g. 0 or 1
|
|
121
|
+
"""
|
|
122
|
+
return self._waist_joint_dof
|
|
123
|
+
|
|
124
|
+
@property
|
|
125
|
+
def waist_joint_names(self) -> list:
|
|
126
|
+
"""Return the names of joints in the waist.
|
|
127
|
+
|
|
128
|
+
Returns:
|
|
129
|
+
list: A list containing the names of joints in the waist.
|
|
130
|
+
Note: For websocket SDK, joint_names() does not include waist joints,
|
|
131
|
+
so this will always return an empty list.
|
|
132
|
+
"""
|
|
133
|
+
return self._waist_joint_names
|
|
134
|
+
|
|
135
|
+
@property
|
|
136
|
+
def head_joint_names(self) -> list:
|
|
137
|
+
"""Return the names of joints in the head.
|
|
138
|
+
|
|
139
|
+
Returns:
|
|
140
|
+
list: A list containing the names of joints in the head.
|
|
141
|
+
"""
|
|
142
|
+
return self._head_joint_names
|
|
143
|
+
|
|
144
|
+
@property
|
|
145
|
+
def eef_frame_names(self) -> Tuple[str, str]:
|
|
146
|
+
"""Returns the names of the end effector frames.
|
|
147
|
+
|
|
148
|
+
Returns:
|
|
149
|
+
Tuple[str, str]:
|
|
150
|
+
A tuple containing the end effector frame names, where:
|
|
151
|
+
- First element is the left hand frame name
|
|
152
|
+
- Second element is the right hand frame name
|
|
153
|
+
e.g. ("zarm_l7_link", "zarm_r7_link")
|
|
154
|
+
"""
|
|
155
|
+
return self._end_frames_names[1], self._end_frames_names[2]
|
|
156
|
+
|
|
157
|
+
@property
|
|
158
|
+
def init_stand_height(self) -> float:
|
|
159
|
+
"""Return the height of the robot's center of mass.
|
|
160
|
+
"""
|
|
161
|
+
return self._init_stand_height
|
|
162
|
+
|
|
163
|
+
def get_arm_joint_limits(self) -> Tuple[list, list]:
|
|
164
|
+
"""获取手臂关节的角度限制范围(基于URDF文件中的真实物理限制)。
|
|
165
|
+
|
|
166
|
+
返回每个关节的最小值和最大值(单位:弧度)。
|
|
167
|
+
这些限制从URDF文件中解析得到,基于机器人的真实物理结构,用于防止电机堵转。
|
|
168
|
+
|
|
169
|
+
Returns:
|
|
170
|
+
Tuple[list, list]: (arm_min, arm_max)
|
|
171
|
+
- arm_min: 每个关节的最小角度值列表(弧度)
|
|
172
|
+
- arm_max: 每个关节的最大角度值列表(弧度)
|
|
173
|
+
|
|
174
|
+
Note:
|
|
175
|
+
这些限制从URDF文件的 <joint><limit> 标签中解析得到,针对每个关节的真实角度范围进行了定义。
|
|
176
|
+
动态从URDF中提取所有手臂相关的link和关节,兼容不同机器人版本。
|
|
177
|
+
"""
|
|
178
|
+
try:
|
|
179
|
+
# 获取URDF内容
|
|
180
|
+
robot_desc = self._ros_param.humanoid_description()
|
|
181
|
+
if robot_desc is None:
|
|
182
|
+
SDKLogger.warn("Failed to get URDF description, using default limits")
|
|
183
|
+
return self._get_default_arm_joint_limits()
|
|
184
|
+
|
|
185
|
+
# 解析URDF XML
|
|
186
|
+
root = ET.fromstring(robot_desc)
|
|
187
|
+
|
|
188
|
+
# 获取关节限制
|
|
189
|
+
arm_min = []
|
|
190
|
+
arm_max = []
|
|
191
|
+
|
|
192
|
+
# 直接使用 arm_joint_names 从 URDF 中查找对应的关节
|
|
193
|
+
for joint_name in self._arm_joint_names:
|
|
194
|
+
# 直接通过关节名称查找
|
|
195
|
+
joint_elem = root.find(f".//joint[@name='{joint_name}']")
|
|
196
|
+
|
|
197
|
+
if joint_elem is not None:
|
|
198
|
+
limit_elem = joint_elem.find("limit")
|
|
199
|
+
if limit_elem is not None:
|
|
200
|
+
lower = float(limit_elem.get("lower", str(-math.pi)))
|
|
201
|
+
upper = float(limit_elem.get("upper", str(math.pi)))
|
|
202
|
+
arm_min.append(lower)
|
|
203
|
+
arm_max.append(upper)
|
|
204
|
+
else:
|
|
205
|
+
SDKLogger.warn(f"Joint {joint_name} has no limit tag, using default [-π, π]")
|
|
206
|
+
arm_min.append(-math.pi)
|
|
207
|
+
arm_max.append(math.pi)
|
|
208
|
+
else:
|
|
209
|
+
SDKLogger.warn(f"Joint {joint_name} not found in URDF, using default [-π, π]")
|
|
210
|
+
arm_min.append(-math.pi)
|
|
211
|
+
arm_max.append(math.pi)
|
|
212
|
+
|
|
213
|
+
if len(arm_min) != self._arm_joint_dof or len(arm_max) != self._arm_joint_dof:
|
|
214
|
+
SDKLogger.warn(f"Failed to parse all joint limits from URDF (got {len(arm_min)}/{self._arm_joint_dof}), using default limits")
|
|
215
|
+
return self._get_default_arm_joint_limits()
|
|
216
|
+
|
|
217
|
+
return arm_min, arm_max
|
|
218
|
+
|
|
219
|
+
except Exception as e:
|
|
220
|
+
SDKLogger.error(f"Error parsing joint limits from URDF: {e}, using default limits")
|
|
221
|
+
return self._get_default_arm_joint_limits()
|
|
222
|
+
|
|
223
|
+
def _get_default_arm_joint_limits(self) -> Tuple[list, list]:
|
|
224
|
+
"""获取默认的手臂关节限制(当无法从URDF解析时使用)。
|
|
225
|
+
|
|
226
|
+
Returns:
|
|
227
|
+
Tuple[list, list]: (arm_min, arm_max) 默认限制值
|
|
228
|
+
"""
|
|
229
|
+
# 默认使用较大的范围作为后备方案
|
|
230
|
+
arm_min = [-math.pi] * self._arm_joint_dof
|
|
231
|
+
arm_max = [math.pi] * self._arm_joint_dof
|
|
232
|
+
return arm_min, arm_max
|
|
233
|
+
|
|
234
|
+
def __str__(self) -> str:
|
|
235
|
+
return f"KuavoRobotInfo(robot_type={self.robot_type}, robot_version={self.robot_version}, end_effector_type={self.end_effector_type}, joint_names={self.joint_names}, joint_dof={self.joint_dof}, arm_joint_dof={self.arm_joint_dof}, init_stand_height={self.init_stand_height})"
|
|
@@ -0,0 +1,69 @@
|
|
|
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.kuavo.core.ros.observation import KuavoRobotObservationCoreWebsocket
|
|
6
|
+
|
|
7
|
+
class KuavoRobotObservation:
|
|
8
|
+
"""Class for accessing robot observation data.
|
|
9
|
+
|
|
10
|
+
This class provides a high-level interface to access robot observation data,
|
|
11
|
+
including joint commands, velocity commands, and pose commands.
|
|
12
|
+
|
|
13
|
+
Attributes:
|
|
14
|
+
_obs_core: The core observation object that handles ROS communication.
|
|
15
|
+
"""
|
|
16
|
+
|
|
17
|
+
def __init__(self, robot_type: str = "kuavo"):
|
|
18
|
+
"""Initialize the robot observation interface.
|
|
19
|
+
|
|
20
|
+
Args:
|
|
21
|
+
robot_type (str): Type of the robot. Defaults to "kuavo".
|
|
22
|
+
"""
|
|
23
|
+
self._obs_core = KuavoRobotObservationCoreWebsocket()
|
|
24
|
+
|
|
25
|
+
@property
|
|
26
|
+
def joint_command(self) -> KuavoJointCommand:
|
|
27
|
+
"""Get the current joint command.
|
|
28
|
+
|
|
29
|
+
Returns:
|
|
30
|
+
KuavoJointCommand: Object containing position, velocity, and torque commands
|
|
31
|
+
for all robot joints.
|
|
32
|
+
"""
|
|
33
|
+
return self._obs_core.joint_command
|
|
34
|
+
|
|
35
|
+
@property
|
|
36
|
+
def cmd_vel(self) -> KuavoTwist:
|
|
37
|
+
"""Get the current velocity command.
|
|
38
|
+
|
|
39
|
+
Returns:
|
|
40
|
+
KuavoTwist: Object containing linear velocity (m/s) and angular velocity (rad/s) commands.
|
|
41
|
+
"""
|
|
42
|
+
return self._obs_core.cmd_vel
|
|
43
|
+
|
|
44
|
+
@property
|
|
45
|
+
def cmd_pose(self) -> KuavoTwist:
|
|
46
|
+
"""Get the current pose command.
|
|
47
|
+
|
|
48
|
+
Returns:
|
|
49
|
+
KuavoTwist: Object containing linear pose commands (m) and angular pose commands (rad).
|
|
50
|
+
"""
|
|
51
|
+
return self._obs_core.cmd_pose
|
|
52
|
+
|
|
53
|
+
@property
|
|
54
|
+
def arm_position_command(self) -> list:
|
|
55
|
+
"""Get the position commands for the arm joints.
|
|
56
|
+
|
|
57
|
+
Returns:
|
|
58
|
+
list: Position commands for arm joints (indices 12-25) in radians.
|
|
59
|
+
"""
|
|
60
|
+
return self._obs_core.arm_position_command
|
|
61
|
+
|
|
62
|
+
@property
|
|
63
|
+
def head_position_command(self) -> list:
|
|
64
|
+
"""Get the position commands for the head joints.
|
|
65
|
+
|
|
66
|
+
Returns:
|
|
67
|
+
list: Position commands for head joints (indices 26-27) in radians.
|
|
68
|
+
"""
|
|
69
|
+
return self._obs_core.head_position_command
|