kuavo-humanoid-sdk 0.1.0__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 +3 -0
- kuavo_humanoid_sdk/common/logger.py +42 -0
- kuavo_humanoid_sdk/interfaces/__init__.py +4 -0
- kuavo_humanoid_sdk/interfaces/data_types.py +122 -0
- kuavo_humanoid_sdk/interfaces/end_effector.py +43 -0
- kuavo_humanoid_sdk/interfaces/robot.py +22 -0
- kuavo_humanoid_sdk/interfaces/robot_info.py +56 -0
- kuavo_humanoid_sdk/kuavo/__init__.py +7 -0
- kuavo_humanoid_sdk/kuavo/core/core.py +388 -0
- kuavo_humanoid_sdk/kuavo/core/dex_hand_control.py +85 -0
- kuavo_humanoid_sdk/kuavo/core/leju_claw_control.py +67 -0
- kuavo_humanoid_sdk/kuavo/core/ros/control.py +758 -0
- kuavo_humanoid_sdk/kuavo/core/ros/param.py +171 -0
- kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
- kuavo_humanoid_sdk/kuavo/core/ros/state.py +325 -0
- kuavo_humanoid_sdk/kuavo/core/ros_env.py +196 -0
- kuavo_humanoid_sdk/kuavo/dexterous_hand.py +183 -0
- kuavo_humanoid_sdk/kuavo/leju_claw.py +225 -0
- kuavo_humanoid_sdk/kuavo/robot.py +309 -0
- kuavo_humanoid_sdk/kuavo/robot_arm.py +140 -0
- kuavo_humanoid_sdk/kuavo/robot_head.py +29 -0
- kuavo_humanoid_sdk/kuavo/robot_info.py +112 -0
- kuavo_humanoid_sdk/kuavo/robot_state.py +258 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/METADATA +217 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/RECORD +27 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/WHEEL +5 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/top_level.txt +1 -0
|
@@ -0,0 +1,171 @@
|
|
|
1
|
+
import rospy
|
|
2
|
+
import json
|
|
3
|
+
import xml.etree.ElementTree as ET
|
|
4
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
5
|
+
class RosParameter:
|
|
6
|
+
def __init__(self):
|
|
7
|
+
pass
|
|
8
|
+
def robot_version(self)->str:
|
|
9
|
+
if not rospy.has_param('/robot_version'):
|
|
10
|
+
rospy.logerr("robot_version parameter not found")
|
|
11
|
+
return None
|
|
12
|
+
return rospy.get_param('/robot_version')
|
|
13
|
+
|
|
14
|
+
def arm_dof(self)->int:
|
|
15
|
+
if not rospy.has_param('/armRealDof'):
|
|
16
|
+
rospy.logerr("armRealDof parameter not found")
|
|
17
|
+
return None
|
|
18
|
+
return rospy.get_param('/armRealDof')
|
|
19
|
+
|
|
20
|
+
def head_dof(self)->int:
|
|
21
|
+
if not rospy.has_param('/headRealDof'):
|
|
22
|
+
rospy.logerr("headRealDof parameter not found")
|
|
23
|
+
return None
|
|
24
|
+
return rospy.get_param('/headRealDof')
|
|
25
|
+
|
|
26
|
+
def leg_dof(self)->int:
|
|
27
|
+
if not rospy.has_param('/legRealDof'):
|
|
28
|
+
rospy.logerr("legRealDof parameter not found")
|
|
29
|
+
return None
|
|
30
|
+
return rospy.get_param('/legRealDof')
|
|
31
|
+
|
|
32
|
+
def end_effector_type(self)->str:
|
|
33
|
+
if not rospy.has_param('/end_effector_type'):
|
|
34
|
+
return None
|
|
35
|
+
return rospy.get_param('/end_effector_type')
|
|
36
|
+
|
|
37
|
+
def humanoid_description(self)->str:
|
|
38
|
+
if not rospy.has_param('/humanoid_description'):
|
|
39
|
+
rospy.logerr("humanoid_description parameter not found")
|
|
40
|
+
return None
|
|
41
|
+
return rospy.get_param('/humanoid_description')
|
|
42
|
+
|
|
43
|
+
def model_path(self)->str:
|
|
44
|
+
if not rospy.has_param('/modelPath'):
|
|
45
|
+
rospy.logerr("modelPath parameter not found")
|
|
46
|
+
return None
|
|
47
|
+
return rospy.get_param('/modelPath')
|
|
48
|
+
|
|
49
|
+
def kuavo_config(self)->str:
|
|
50
|
+
if not rospy.has_param('/kuavo_configuration'):
|
|
51
|
+
rospy.logerr("kuavo_configuration parameter not found")
|
|
52
|
+
return None
|
|
53
|
+
return rospy.get_param('/kuavo_configuration')
|
|
54
|
+
|
|
55
|
+
def initial_state(self)->str:
|
|
56
|
+
if not rospy.has_param('/initial_state'):
|
|
57
|
+
rospy.logerr("initial_state parameter not found")
|
|
58
|
+
return None
|
|
59
|
+
return rospy.get_param('/initial_state')
|
|
60
|
+
|
|
61
|
+
kuavo_ros_param = RosParameter()
|
|
62
|
+
|
|
63
|
+
def joint_names()->dict:
|
|
64
|
+
leg_link_names = [
|
|
65
|
+
'leg_l1_link', 'leg_l2_link', 'leg_l3_link', 'leg_l4_link', 'leg_l5_link', 'leg_l6_link',
|
|
66
|
+
'leg_r1_link', 'leg_r2_link', 'leg_r3_link', 'leg_r4_link', 'leg_r5_link', 'leg_r6_link'
|
|
67
|
+
]
|
|
68
|
+
arm_link_names = [
|
|
69
|
+
'zarm_l1_link', 'zarm_l2_link', 'zarm_l3_link', 'zarm_l4_link', 'zarm_l5_link', 'zarm_l6_link', 'zarm_l7_link',
|
|
70
|
+
'zarm_r1_link', 'zarm_r2_link', 'zarm_r3_link', 'zarm_r4_link', 'zarm_r5_link', 'zarm_r6_link', 'zarm_r7_link',
|
|
71
|
+
]
|
|
72
|
+
head_link_names = [
|
|
73
|
+
'zhead_1_link', 'zhead_2_link'
|
|
74
|
+
]
|
|
75
|
+
robot_desc = kuavo_ros_param.humanoid_description()
|
|
76
|
+
if robot_desc is None:
|
|
77
|
+
return None
|
|
78
|
+
|
|
79
|
+
"""
|
|
80
|
+
<link name="leg_l1_link">
|
|
81
|
+
<inertial>
|
|
82
|
+
....
|
|
83
|
+
</inertial>
|
|
84
|
+
<visual>
|
|
85
|
+
...
|
|
86
|
+
<geometry>
|
|
87
|
+
<mesh filename="package://kuavo_assets/models/biped_s43/meshes/l_leg_roll.STL" />
|
|
88
|
+
</geometry>
|
|
89
|
+
...
|
|
90
|
+
</visual>
|
|
91
|
+
</link>
|
|
92
|
+
"""
|
|
93
|
+
root = ET.fromstring(robot_desc)
|
|
94
|
+
process_link_name = lambda link_name: (
|
|
95
|
+
(root.find(f".//link[@name='{link_name}']") is not None and
|
|
96
|
+
root.find(f".//link[@name='{link_name}']/visual") is not None and
|
|
97
|
+
root.find(f".//link[@name='{link_name}']/visual/geometry") is not None and
|
|
98
|
+
root.find(f".//link[@name='{link_name}']/visual/geometry/mesh") is not None and
|
|
99
|
+
root.find(f".//link[@name='{link_name}']/visual/geometry/mesh").get("filename") is not None)
|
|
100
|
+
and (
|
|
101
|
+
# Extract the basename (without path and extension)
|
|
102
|
+
root.find(f".//link[@name='{link_name}']/visual/geometry/mesh")
|
|
103
|
+
.get("filename")
|
|
104
|
+
.split("/")[-1]
|
|
105
|
+
.split(".")[0]
|
|
106
|
+
)
|
|
107
|
+
or (
|
|
108
|
+
SDKLogger.warn(f"Warning: {link_name} is not found or incomplete in robot_desc"),
|
|
109
|
+
None
|
|
110
|
+
)[1] # Return None after printing the warning
|
|
111
|
+
)
|
|
112
|
+
leg_joint_names = [process_link_name(link_name) for link_name in leg_link_names if process_link_name(link_name) is not None]
|
|
113
|
+
arm_joint_names = [process_link_name(link_name) for link_name in arm_link_names if process_link_name(link_name) is not None]
|
|
114
|
+
head_joint_names = [process_link_name(link_name) for link_name in head_link_names if process_link_name(link_name) is not None]
|
|
115
|
+
|
|
116
|
+
if len(leg_link_names) != len(leg_joint_names):
|
|
117
|
+
SDKLogger.warn(f"leg_joint_names is not equal to leg_link_names, {len(leg_link_names)} != {len(leg_joint_names)}")
|
|
118
|
+
return None
|
|
119
|
+
if len(arm_link_names)!= len(arm_joint_names):
|
|
120
|
+
SDKLogger.warn(f"arm_joint_names is not equal to arm_link_names, {len(arm_link_names)}!= {len(arm_joint_names)}")
|
|
121
|
+
return None
|
|
122
|
+
if len(head_link_names)!= len(head_joint_names):
|
|
123
|
+
SDKLogger.warn(f"head_joint_names is not equal to head_link_names, {len(head_link_names)}!= {len(head_joint_names)}")
|
|
124
|
+
return None
|
|
125
|
+
|
|
126
|
+
return leg_joint_names + arm_joint_names + head_joint_names
|
|
127
|
+
|
|
128
|
+
kuavo_ros_info = None
|
|
129
|
+
|
|
130
|
+
def end_frames_names()->dict:
|
|
131
|
+
default = ["torso", "zarm_l7_link", "zarm_r7_link", "zarm_l4_link", "zarm_r4_link"]
|
|
132
|
+
kuavo_json = kuavo_ros_param.kuavo_config()
|
|
133
|
+
if kuavo_json is None:
|
|
134
|
+
return default
|
|
135
|
+
|
|
136
|
+
try:
|
|
137
|
+
kuavo_config = json.loads(kuavo_json)
|
|
138
|
+
if kuavo_config.get('end_frames_names') is not None:
|
|
139
|
+
return kuavo_config.get('end_frames_names')
|
|
140
|
+
else:
|
|
141
|
+
return default
|
|
142
|
+
except Exception as e:
|
|
143
|
+
print(f"Failed to get end_frames_names from kuavo_json: {e}")
|
|
144
|
+
return default
|
|
145
|
+
|
|
146
|
+
def make_robot_param()->dict:
|
|
147
|
+
global kuavo_ros_info
|
|
148
|
+
if kuavo_ros_info is not None:
|
|
149
|
+
return kuavo_ros_info
|
|
150
|
+
|
|
151
|
+
kuavo_ros_info = {
|
|
152
|
+
'robot_version': kuavo_ros_param.robot_version(),
|
|
153
|
+
'arm_dof': kuavo_ros_param.arm_dof(),
|
|
154
|
+
'head_dof': kuavo_ros_param.head_dof(),
|
|
155
|
+
'leg_dof': kuavo_ros_param.leg_dof(),
|
|
156
|
+
'end_effector_type': kuavo_ros_param.end_effector_type(),
|
|
157
|
+
'joint_names': joint_names(),
|
|
158
|
+
'end_frames_names': end_frames_names(),
|
|
159
|
+
}
|
|
160
|
+
|
|
161
|
+
for key, value in kuavo_ros_info.items():
|
|
162
|
+
if value is None and key != 'end_effector_type':
|
|
163
|
+
SDKLogger.debug(f"[Error]: Failed to get '{key}' from ROS.")
|
|
164
|
+
kuavo_ros_info = None
|
|
165
|
+
raise Exception(f"[Error]: Failed to get '{key}' from ROS.")
|
|
166
|
+
|
|
167
|
+
return kuavo_ros_info
|
|
168
|
+
|
|
169
|
+
if __name__ == "__main__":
|
|
170
|
+
rospy.init_node("kuavo_ros_param_test")
|
|
171
|
+
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()
|
|
@@ -0,0 +1,325 @@
|
|
|
1
|
+
import rospy
|
|
2
|
+
import copy
|
|
3
|
+
import time
|
|
4
|
+
from typing import Tuple
|
|
5
|
+
from std_msgs.msg import Float64
|
|
6
|
+
from nav_msgs.msg import Odometry
|
|
7
|
+
from kuavo_msgs.msg import sensorsData, lejuClawState, gaitTimeName
|
|
8
|
+
|
|
9
|
+
from kuavo_msgs.srv import changeArmCtrlMode, changeArmCtrlModeRequest, getCurrentGaitName, getCurrentGaitNameRequest
|
|
10
|
+
from ocs2_msgs.msg import mpc_observation
|
|
11
|
+
from kuavo_humanoid_sdk.interfaces.data_types import KuavoImuData, KuavoJointData, KuavoOdometry, KuavoArmCtrlMode, EndEffectorState
|
|
12
|
+
from kuavo_humanoid_sdk.kuavo.core.ros.param import make_robot_param
|
|
13
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
14
|
+
|
|
15
|
+
from collections import deque
|
|
16
|
+
from typing import Tuple, Optional
|
|
17
|
+
|
|
18
|
+
class GaitManager:
|
|
19
|
+
def __init__(self, max_size: int = 20):
|
|
20
|
+
self._max_size = max_size
|
|
21
|
+
self._gait_time_names = deque(maxlen=max_size)
|
|
22
|
+
|
|
23
|
+
@property
|
|
24
|
+
def is_empty(self) -> bool:
|
|
25
|
+
"""Check if there are any gait time names stored.
|
|
26
|
+
|
|
27
|
+
Returns:
|
|
28
|
+
bool: True if no gait time names are stored, False otherwise
|
|
29
|
+
"""
|
|
30
|
+
return len(self._gait_time_names) == 0
|
|
31
|
+
def add(self, start_time: float, name: str) -> None:
|
|
32
|
+
self._gait_time_names.append((start_time, name))
|
|
33
|
+
|
|
34
|
+
def get_gait(self, current_time: float) -> str:
|
|
35
|
+
if not self._gait_time_names:
|
|
36
|
+
return "No_Gait"
|
|
37
|
+
|
|
38
|
+
for start_time, name in reversed(self._gait_time_names):
|
|
39
|
+
if current_time >= start_time:
|
|
40
|
+
return name
|
|
41
|
+
|
|
42
|
+
return self._gait_time_names[0].name
|
|
43
|
+
|
|
44
|
+
def get_gait_name(self, current_time: float) -> str:
|
|
45
|
+
return self.get_gait(current_time)[1]
|
|
46
|
+
|
|
47
|
+
def get_last_gait_name(self) -> str:
|
|
48
|
+
if not self._gait_time_names:
|
|
49
|
+
return "No_Gait"
|
|
50
|
+
return self._gait_time_names[-1][1]
|
|
51
|
+
|
|
52
|
+
class KuavoRobotStateCore:
|
|
53
|
+
_instance = None
|
|
54
|
+
|
|
55
|
+
def __new__(cls, *args, **kwargs):
|
|
56
|
+
if not cls._instance:
|
|
57
|
+
cls._instance = super().__new__(cls)
|
|
58
|
+
return cls._instance
|
|
59
|
+
|
|
60
|
+
def __init__(self):
|
|
61
|
+
if not hasattr(self, '_initialized'):
|
|
62
|
+
rospy.Subscriber("/sensors_data_raw", sensorsData, self._sensors_data_raw_callback)
|
|
63
|
+
rospy.Subscriber("/odom", Odometry, self._odom_callback)
|
|
64
|
+
rospy.Subscriber("/humanoid/mpc/terrainHeight", Float64, self._terrain_height_callback)
|
|
65
|
+
rospy.Subscriber("/humanoid_mpc_gait_time_name", gaitTimeName, self._humanoid_mpc_gait_changed_callback)
|
|
66
|
+
rospy.Subscriber("/humanoid_mpc_observation", mpc_observation, self._humanoid_mpc_observation_callback)
|
|
67
|
+
|
|
68
|
+
kuavo_info = make_robot_param()
|
|
69
|
+
if kuavo_info['end_effector_type'] == "lejuclaw":
|
|
70
|
+
rospy.Subscriber("/leju_claw_state", lejuClawState, self._lejuclaw_state_callback)
|
|
71
|
+
elif kuavo_info['end_effector_type'] == "qiangnao":
|
|
72
|
+
pass # TODO(kuavo): add qiangnao state subscriber
|
|
73
|
+
# rospy.Subscriber("/robot_hand_state", robotHandState, self._dexterous_hand_state_callback)
|
|
74
|
+
|
|
75
|
+
""" data """
|
|
76
|
+
self._terrain_height = 0.0
|
|
77
|
+
self._imu_data = KuavoImuData(
|
|
78
|
+
gyro = (0.0, 0.0, 0.0),
|
|
79
|
+
acc = (0.0, 0.0, 0.0),
|
|
80
|
+
free_acc = (0.0, 0.0, 0.0),
|
|
81
|
+
quat = (0.0, 0.0, 0.0, 0.0)
|
|
82
|
+
)
|
|
83
|
+
self._joint_data = KuavoJointData(
|
|
84
|
+
position = [0.0] * 28,
|
|
85
|
+
velocity = [0.0] * 28,
|
|
86
|
+
torque = [0.0] * 28,
|
|
87
|
+
acceleration = [0.0] * 28
|
|
88
|
+
)
|
|
89
|
+
self._odom_data = KuavoOdometry(
|
|
90
|
+
position = (0.0, 0.0, 0.0),
|
|
91
|
+
orientation = (0.0, 0.0, 0.0, 0.0),
|
|
92
|
+
linear = (0.0, 0.0, 0.0),
|
|
93
|
+
angular = (0.0, 0.0, 0.0)
|
|
94
|
+
)
|
|
95
|
+
self._eef_state = (EndEffectorState(
|
|
96
|
+
position = 0.0,
|
|
97
|
+
velocity = 0.0,
|
|
98
|
+
effort = 0.0,
|
|
99
|
+
state=EndEffectorState.GraspingState.UNKNOWN
|
|
100
|
+
), EndEffectorState(
|
|
101
|
+
position = 0.0,
|
|
102
|
+
velocity = 0.0,
|
|
103
|
+
effort = 0.0,
|
|
104
|
+
state=EndEffectorState.GraspingState.UNKNOWN
|
|
105
|
+
))
|
|
106
|
+
|
|
107
|
+
# gait manager
|
|
108
|
+
self._gait_manager = GaitManager()
|
|
109
|
+
self._prev_gait_name = self.gait_name
|
|
110
|
+
|
|
111
|
+
# Wait for first MPC observation data
|
|
112
|
+
self._mpc_observation_data = None
|
|
113
|
+
start_time = time.time()
|
|
114
|
+
while self._mpc_observation_data is None:
|
|
115
|
+
if time.time() - start_time > 1.0: # 1.0s timeout
|
|
116
|
+
SDKLogger.warn("Timeout waiting for MPC observation data")
|
|
117
|
+
break
|
|
118
|
+
SDKLogger.debug("Waiting for first MPC observation data...")
|
|
119
|
+
time.sleep(0.1)
|
|
120
|
+
# 如果 gait_manager 为空,则把当前的状态添加到其中
|
|
121
|
+
if self._mpc_observation_data is not None:
|
|
122
|
+
if self._gait_manager.is_empty:
|
|
123
|
+
self._prev_gait_name = self.gait_name()
|
|
124
|
+
SDKLogger.debug(f"[State] Adding initial gait state: {self._prev_gait_name} at time {self._mpc_observation_data.time}")
|
|
125
|
+
self._gait_manager.add(self._mpc_observation_data.time, self._prev_gait_name)
|
|
126
|
+
|
|
127
|
+
# 获取当前手臂控制模式
|
|
128
|
+
self._arm_ctrl_mode = self._srv_get_arm_ctrl_mode()
|
|
129
|
+
self._initialized = True
|
|
130
|
+
|
|
131
|
+
@property
|
|
132
|
+
def com_height(self)->float:
|
|
133
|
+
# odom.position.z - terrain_height = com_height
|
|
134
|
+
return self._odom_data.position[2] - self._terrain_height
|
|
135
|
+
|
|
136
|
+
@property
|
|
137
|
+
def imu_data(self)->KuavoImuData:
|
|
138
|
+
return self._imu_data
|
|
139
|
+
|
|
140
|
+
@property
|
|
141
|
+
def joint_data(self)->KuavoJointData:
|
|
142
|
+
return self._joint_data
|
|
143
|
+
|
|
144
|
+
@property
|
|
145
|
+
def odom_data(self)->KuavoOdometry:
|
|
146
|
+
return self._odom_data
|
|
147
|
+
|
|
148
|
+
@property
|
|
149
|
+
def arm_control_mode(self) -> KuavoArmCtrlMode:
|
|
150
|
+
mode = self._srv_get_arm_ctrl_mode()
|
|
151
|
+
if mode is not None:
|
|
152
|
+
self._arm_ctrl_mode = mode
|
|
153
|
+
return self._arm_ctrl_mode
|
|
154
|
+
|
|
155
|
+
@property
|
|
156
|
+
def eef_state(self)->Tuple[EndEffectorState, EndEffectorState]:
|
|
157
|
+
return self._eef_state
|
|
158
|
+
|
|
159
|
+
@property
|
|
160
|
+
def current_observation_time(self) -> float:
|
|
161
|
+
"""Get the current observation time from MPC.
|
|
162
|
+
|
|
163
|
+
Returns:
|
|
164
|
+
float: Current observation time in seconds, or None if no observation data available
|
|
165
|
+
"""
|
|
166
|
+
if self._mpc_observation_data is None:
|
|
167
|
+
return None
|
|
168
|
+
return self._mpc_observation_data.time
|
|
169
|
+
|
|
170
|
+
@property
|
|
171
|
+
def current_gait_mode(self) -> int:
|
|
172
|
+
"""
|
|
173
|
+
Get the current gait mode from MPC observation.
|
|
174
|
+
|
|
175
|
+
Notes: FF=0, FH=1, FT=2, FS=3, HF=4, HH=5, HT=6, HS=7, TF=8, TH=9, TT=10, TS=11, SF=12, SH=13, ST=14, SS=15
|
|
176
|
+
|
|
177
|
+
Returns:
|
|
178
|
+
int: Current gait mode, or None if no observation data available
|
|
179
|
+
"""
|
|
180
|
+
if self._mpc_observation_data is None:
|
|
181
|
+
return None
|
|
182
|
+
return self._mpc_observation_data.mode
|
|
183
|
+
|
|
184
|
+
def gait_name(self)->str:
|
|
185
|
+
return self._srv_get_current_gait_name()
|
|
186
|
+
|
|
187
|
+
def is_gait(self, gait_name: str) -> bool:
|
|
188
|
+
"""Check if current gait matches the given gait name.
|
|
189
|
+
|
|
190
|
+
Args:
|
|
191
|
+
gait_name (str): Name of gait to check
|
|
192
|
+
|
|
193
|
+
Returns:
|
|
194
|
+
bool: True if current gait matches given name, False otherwise
|
|
195
|
+
"""
|
|
196
|
+
return self._gait_manager.get_gait(self._mpc_observation_data.time) == gait_name
|
|
197
|
+
|
|
198
|
+
def register_gait_changed_callback(self, callback):
|
|
199
|
+
"""Register a callback function that will be called when the gait changes.
|
|
200
|
+
|
|
201
|
+
Args:
|
|
202
|
+
callback: A function that takes current time (float) and gait name (str) as arguments
|
|
203
|
+
Raises:
|
|
204
|
+
ValueError: If callback does not accept 2 parameters: current_time (float), gait_name (str)
|
|
205
|
+
"""
|
|
206
|
+
if not hasattr(self, '_gait_changed_callbacks'):
|
|
207
|
+
self._gait_changed_callbacks = []
|
|
208
|
+
|
|
209
|
+
# Verify callback accepts current_time (float) and gait_name (str) parameters
|
|
210
|
+
from inspect import signature
|
|
211
|
+
sig = signature(callback)
|
|
212
|
+
if len(sig.parameters) != 2:
|
|
213
|
+
raise ValueError("Callback must accept 2 parameters: current_time (float), gait_name (str)")
|
|
214
|
+
if callback not in self._gait_changed_callbacks:
|
|
215
|
+
self._gait_changed_callbacks.append(callback)
|
|
216
|
+
|
|
217
|
+
""" ------------------------------- callback ------------------------------- """
|
|
218
|
+
def _terrain_height_callback(self, msg:Float64)->None:
|
|
219
|
+
self._terrain_height = msg.data
|
|
220
|
+
|
|
221
|
+
def _sensors_data_raw_callback(self, msg:sensorsData)->None:
|
|
222
|
+
# update imu data
|
|
223
|
+
self._imu_data = KuavoImuData(
|
|
224
|
+
gyro = (msg.imu_data.gyro.x, msg.imu_data.gyro.y, msg.imu_data.gyro.z),
|
|
225
|
+
acc = (msg.imu_data.acc.x, msg.imu_data.acc.y, msg.imu_data.acc.z),
|
|
226
|
+
free_acc = (msg.imu_data.free_acc.x, msg.imu_data.free_acc.y, msg.imu_data.free_acc.z),
|
|
227
|
+
quat = (msg.imu_data.quat.x, msg.imu_data.quat.y, msg.imu_data.quat.z, msg.imu_data.quat.w)
|
|
228
|
+
)
|
|
229
|
+
# update joint data
|
|
230
|
+
self._joint_data = KuavoJointData(
|
|
231
|
+
position = copy.deepcopy(msg.joint_data.joint_q),
|
|
232
|
+
velocity = copy.deepcopy(msg.joint_data.joint_v),
|
|
233
|
+
torque = copy.deepcopy(msg.joint_data.joint_vd),
|
|
234
|
+
acceleration = copy.deepcopy(msg.joint_data.joint_current)
|
|
235
|
+
)
|
|
236
|
+
|
|
237
|
+
def _odom_callback(self, msg:Odometry)->None:
|
|
238
|
+
# update odom data
|
|
239
|
+
self._odom_data = KuavoOdometry(
|
|
240
|
+
position = (msg.pose.pose.position.x, msg.pose.pose.position.y, msg.pose.pose.position.z),
|
|
241
|
+
orientation = (msg.pose.pose.orientation.x, msg.pose.pose.orientation.y, msg.pose.pose.orientation.z, msg.pose.pose.orientation.w),
|
|
242
|
+
linear = (msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z),
|
|
243
|
+
angular = (msg.twist.twist.angular.x, msg.twist.twist.angular.y, msg.twist.twist.angular.z)
|
|
244
|
+
)
|
|
245
|
+
|
|
246
|
+
def _lejuclaw_state_callback(self, msg:lejuClawState)->None:
|
|
247
|
+
self._eef_state = (EndEffectorState(
|
|
248
|
+
position = msg.data.position[0],
|
|
249
|
+
velocity = msg.data.velocity[0],
|
|
250
|
+
effort = msg.data.effort[0],
|
|
251
|
+
state=EndEffectorState.GraspingState(msg.state[0])
|
|
252
|
+
), EndEffectorState(
|
|
253
|
+
position = msg.data.position[1],
|
|
254
|
+
velocity = msg.data.velocity[1],
|
|
255
|
+
effort = msg.data.effort[1],
|
|
256
|
+
state=EndEffectorState.GraspingState(msg.state[1])
|
|
257
|
+
))
|
|
258
|
+
|
|
259
|
+
def _dexterous_hand_state_callback(self, msg)->None:
|
|
260
|
+
self._eef_state = (EndEffectorState(
|
|
261
|
+
position = msg.data.position[0],
|
|
262
|
+
velocity = msg.data.velocity[0],
|
|
263
|
+
effort = msg.data.effort[0],
|
|
264
|
+
state=EndEffectorState.GraspingState(msg.state[0])
|
|
265
|
+
), EndEffectorState(
|
|
266
|
+
position = msg.data.position[1],
|
|
267
|
+
velocity = msg.data.velocity[1],
|
|
268
|
+
effort = msg.data.effort[1],
|
|
269
|
+
state=EndEffectorState.GraspingState(msg.state[1])
|
|
270
|
+
))
|
|
271
|
+
def _humanoid_mpc_gait_changed_callback(self, msg: gaitTimeName):
|
|
272
|
+
"""
|
|
273
|
+
Callback function for gait change messages.
|
|
274
|
+
Updates the current gait name when a gait change occurs.
|
|
275
|
+
"""
|
|
276
|
+
SDKLogger.debug(f"[State] Received gait change message: {msg.gait_name} at time {msg.start_time}")
|
|
277
|
+
self._gait_manager.add(msg.start_time, msg.gait_name)
|
|
278
|
+
|
|
279
|
+
def _humanoid_mpc_observation_callback(self, msg: mpc_observation) -> None:
|
|
280
|
+
"""
|
|
281
|
+
Callback function for MPC observation messages.
|
|
282
|
+
Updates the current MPC state and input data.
|
|
283
|
+
"""
|
|
284
|
+
try:
|
|
285
|
+
self._mpc_observation_data = msg
|
|
286
|
+
# Only update gait info after initialization
|
|
287
|
+
if hasattr(self, '_initialized'):
|
|
288
|
+
curr_time = self._mpc_observation_data.time
|
|
289
|
+
current_gait = self._gait_manager.get_gait(curr_time)
|
|
290
|
+
if self._prev_gait_name != current_gait:
|
|
291
|
+
SDKLogger.debug(f"[State] Gait changed to: {current_gait} at time {curr_time}")
|
|
292
|
+
# Update previous gait name and notify callback if registered
|
|
293
|
+
self._prev_gait_name = current_gait
|
|
294
|
+
if hasattr(self, '_gait_changed_callbacks') and self._gait_changed_callbacks is not None:
|
|
295
|
+
for callback in self._gait_changed_callbacks:
|
|
296
|
+
callback(curr_time, current_gait)
|
|
297
|
+
except Exception as e:
|
|
298
|
+
SDKLogger.error(f"Error processing MPC observation: {e}")
|
|
299
|
+
|
|
300
|
+
def _srv_get_arm_ctrl_mode(self)-> KuavoArmCtrlMode:
|
|
301
|
+
try:
|
|
302
|
+
rospy.wait_for_service('/humanoid_get_arm_ctrl_mode')
|
|
303
|
+
get_arm_ctrl_mode_srv = rospy.ServiceProxy('/humanoid_get_arm_ctrl_mode', changeArmCtrlMode)
|
|
304
|
+
req = changeArmCtrlModeRequest()
|
|
305
|
+
resp = get_arm_ctrl_mode_srv(req)
|
|
306
|
+
return KuavoArmCtrlMode(resp.mode)
|
|
307
|
+
except rospy.ServiceException as e:
|
|
308
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
309
|
+
except Exception as e:
|
|
310
|
+
SDKLogger.error(f"[Error] get arm ctrl mode: {e}")
|
|
311
|
+
return None
|
|
312
|
+
|
|
313
|
+
def _srv_get_current_gait_name(self)->str:
|
|
314
|
+
try:
|
|
315
|
+
rospy.wait_for_service('/humanoid_get_current_gait_name', timeout=1.0)
|
|
316
|
+
srv = rospy.ServiceProxy('/humanoid_get_current_gait_name', getCurrentGaitName)
|
|
317
|
+
request = getCurrentGaitNameRequest()
|
|
318
|
+
response = srv(request)
|
|
319
|
+
if response.success:
|
|
320
|
+
return response.gait_name
|
|
321
|
+
else:
|
|
322
|
+
return None
|
|
323
|
+
except Exception as e:
|
|
324
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
325
|
+
return None
|