kuavo-humanoid-sdk 1.1.2a924__py3-none-any.whl → 1.1.3a1226__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.

Files changed (45) hide show
  1. kuavo_humanoid_sdk/common/global_config.py +15 -0
  2. kuavo_humanoid_sdk/common/websocket_kuavo_sdk.py +23 -0
  3. kuavo_humanoid_sdk/interfaces/data_types.py +46 -0
  4. kuavo_humanoid_sdk/kuavo/__init__.py +3 -0
  5. kuavo_humanoid_sdk/kuavo/core/audio.py +33 -0
  6. kuavo_humanoid_sdk/kuavo/core/core.py +16 -6
  7. kuavo_humanoid_sdk/kuavo/core/ros/audio.py +87 -0
  8. kuavo_humanoid_sdk/kuavo/core/ros/control.py +645 -19
  9. kuavo_humanoid_sdk/kuavo/core/ros/param.py +142 -4
  10. kuavo_humanoid_sdk/kuavo/core/ros/state.py +329 -15
  11. kuavo_humanoid_sdk/kuavo/core/ros/tools.py +149 -0
  12. kuavo_humanoid_sdk/kuavo/core/ros/vision.py +272 -0
  13. kuavo_humanoid_sdk/kuavo/core/ros_env.py +229 -1
  14. kuavo_humanoid_sdk/kuavo/dexterous_hand.py +6 -2
  15. kuavo_humanoid_sdk/kuavo/leju_claw.py +6 -2
  16. kuavo_humanoid_sdk/kuavo/robot.py +43 -22
  17. kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
  18. kuavo_humanoid_sdk/kuavo/robot_info.py +7 -2
  19. kuavo_humanoid_sdk/kuavo/robot_state.py +6 -2
  20. kuavo_humanoid_sdk/kuavo/robot_tool.py +62 -0
  21. kuavo_humanoid_sdk/kuavo/robot_vision.py +87 -0
  22. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetection.py +306 -0
  23. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetectionArray.py +437 -0
  24. kuavo_humanoid_sdk/msg/kuavo_msgs/msg/__init__.py +9 -0
  25. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_armHandPose.py +2 -2
  26. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_handPose.py +2 -2
  27. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_ikSolveError.py +13 -13
  28. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_ikSolveParam.py +2 -2
  29. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_robotArmQVVD.py +2 -2
  30. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_twoArmHandPose.py +13 -13
  31. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/msg/_twoArmHandPoseCmd.py +15 -15
  32. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SpeechSynthesis.py +270 -0
  33. kuavo_humanoid_sdk/msg/kuavo_msgs/srv/__init__.py +5 -0
  34. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/srv/_changeArmCtrlModeKuavo.py +5 -5
  35. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/srv/_fkSrv.py +13 -13
  36. kuavo_humanoid_sdk/msg/{motion_capture_ik/srv/_changeArmCtrlMode.py → kuavo_msgs/srv/_playmusic.py} +97 -98
  37. kuavo_humanoid_sdk/msg/{motion_capture_ik → kuavo_msgs}/srv/_twoArmHandPoseCmdSrv.py +23 -23
  38. {kuavo_humanoid_sdk-1.1.2a924.dist-info → kuavo_humanoid_sdk-1.1.3a1226.dist-info}/METADATA +2 -1
  39. {kuavo_humanoid_sdk-1.1.2a924.dist-info → kuavo_humanoid_sdk-1.1.3a1226.dist-info}/RECORD +41 -33
  40. kuavo_humanoid_sdk/msg/motion_capture_ik/msg/__init__.py +0 -9
  41. kuavo_humanoid_sdk/msg/motion_capture_ik/msg/_headBodyPose.py +0 -145
  42. kuavo_humanoid_sdk/msg/motion_capture_ik/msg/_robotHandPosition.py +0 -225
  43. kuavo_humanoid_sdk/msg/motion_capture_ik/srv/__init__.py +0 -4
  44. {kuavo_humanoid_sdk-1.1.2a924.dist-info → kuavo_humanoid_sdk-1.1.3a1226.dist-info}/WHEEL +0 -0
  45. {kuavo_humanoid_sdk-1.1.2a924.dist-info → kuavo_humanoid_sdk-1.1.3a1226.dist-info}/top_level.txt +0 -0
@@ -0,0 +1,149 @@
1
+ #! /usr/bin/env python3
2
+ # coding: utf-8
3
+ import rospy
4
+ import copy
5
+ import time
6
+ import numpy as np
7
+ import tf2_ros
8
+ import tf.transformations as tf_trans
9
+ from typing import Tuple, Union
10
+ from std_msgs.msg import Float64
11
+ from nav_msgs.msg import Odometry
12
+ from sensor_msgs.msg import JointState
13
+ from kuavo_humanoid_sdk.msg.kuavo_msgs.msg import sensorsData, lejuClawState, gaitTimeName, dexhandTouchState
14
+ from kuavo_humanoid_sdk.interfaces.data_types import (PoseQuaternion, HomogeneousMatrix)
15
+ from kuavo_humanoid_sdk.kuavo.core.ros.param import make_robot_param, EndEffectorType
16
+ from kuavo_humanoid_sdk.common.logger import SDKLogger
17
+ from geometry_msgs.msg import TransformStamped
18
+
19
+ class KuavoRobotToolsCore:
20
+ """Provides core ROS tools for Kuavo humanoid robot transformations.
21
+
22
+ Attributes:
23
+ tf_buffer (tf2_ros.Buffer): TF2 transform buffer for storing transforms
24
+ tf_listener (tf2_ros.TransformListener): TF2 transform listener
25
+ """
26
+
27
+ def __init__(self):
28
+ """Initializes TF2 buffer and listener for coordinate transformations."""
29
+ if not hasattr(self, '_initialized'):
30
+ # 初始化TF2相关组件
31
+ self.tf_buffer = tf2_ros.Buffer(cache_time=rospy.Duration(10))
32
+ self.tf_listener = tf2_ros.TransformListener(self.tf_buffer)
33
+
34
+ def _get_tf_tree_transform(self, target_frame: str, source_frame: str,
35
+ time=rospy.Time(0), timeout=1.0,
36
+ return_type: str = "pose_quaternion") -> Union[PoseQuaternion, HomogeneousMatrix, None]:
37
+ """Gets transform between coordinate frames.
38
+
39
+ Args:
40
+ target_frame (str): Target coordinate frame name
41
+ source_frame (str): Source coordinate frame name
42
+ time (rospy.Time, optional): Time of transform. Defaults to latest.
43
+ timeout (float, optional): Wait timeout in seconds. Defaults to 1.0.
44
+ return_type (str, optional): Return data format. Options:
45
+ "pose_quaternion", "homogeneous". Defaults to "pose_quaternion".
46
+
47
+ Returns:
48
+ Union[PoseQuaternion, HomogeneousMatrix, None]: Requested transform data
49
+ or None if failed
50
+
51
+ Raises:
52
+ tf2_ros.LookupException: If transform is not available
53
+ tf2_ros.ConnectivityException: If transform connectivity issue
54
+ tf2_ros.ExtrapolationException: If transform time is out of range
55
+ """
56
+ try:
57
+ transform = self.tf_buffer.lookup_transform(
58
+ target_frame,
59
+ source_frame,
60
+ time,
61
+ rospy.Duration(timeout)
62
+ )
63
+ return self._parse_transform(transform.transform, return_type)
64
+ except Exception as e:
65
+ SDKLogger.error(f"Transform error: {str(e)}")
66
+ return None
67
+
68
+ def _parse_transform(self, transform, return_type: str) -> Union[PoseQuaternion, HomogeneousMatrix, None]:
69
+ """Parses transform data to specified format.
70
+
71
+ Args:
72
+ transform (geometry_msgs/Transform): Input transform data
73
+ return_type (str): Output format type. Valid values:
74
+ "pose_quaternion", "homogeneous"
75
+
76
+ Returns:
77
+ Union[PoseQuaternion, HomogeneousMatrix, None]: Parsed transform data
78
+ in requested format, or None if invalid input
79
+
80
+ Note:
81
+ Falls back to pose_quaternion format if invalid return_type specified
82
+ """
83
+ if return_type == "pose_quaternion":
84
+ return PoseQuaternion(
85
+ position=(transform.translation.x,
86
+ transform.translation.y,
87
+ transform.translation.z),
88
+ orientation=(transform.rotation.x,
89
+ transform.rotation.y,
90
+ transform.rotation.z,
91
+ transform.rotation.w)
92
+ )
93
+ elif return_type == "homogeneous":
94
+ return HomogeneousMatrix(
95
+ matrix=self._transform_to_homogeneous(transform)
96
+ )
97
+ else:
98
+ SDKLogger.warn(f"Invalid return_type: {return_type}, using default(pose_quaternion)")
99
+ return self._parse_transform(transform, "pose_quaternion")
100
+
101
+ def _transform_to_homogeneous(self, transform) -> np.ndarray:
102
+ """Converts geometry_msgs/Transform to homogeneous matrix.
103
+
104
+ Args:
105
+ transform (geometry_msgs/Transform): Input transform message
106
+
107
+ Returns:
108
+ np.ndarray: 4x4 homogeneous transformation matrix (numpy.float32)
109
+
110
+ Example:
111
+ >>> matrix = _transform_to_homogeneous(transform_msg)
112
+ >>> print(matrix.shape)
113
+ (4, 4)
114
+ """
115
+ # 四元数转旋转矩阵
116
+ rotation = [
117
+ transform.rotation.x,
118
+ transform.rotation.y,
119
+ transform.rotation.z,
120
+ transform.rotation.w
121
+ ]
122
+ rot_matrix = tf_trans.quaternion_matrix(rotation)
123
+
124
+ # 设置平移分量
125
+ translation = [
126
+ transform.translation.x,
127
+ transform.translation.y,
128
+ transform.translation.z
129
+ ]
130
+ rot_matrix[:3, 3] = translation
131
+
132
+ return rot_matrix.astype(np.float32) # 确保矩阵数据类型一致
133
+
134
+ # if __name__ == "__main__":
135
+ # robot_tools = KuavoRobotToolsCore()
136
+ # time.sleep(0.1)
137
+ # # 获取位姿信息
138
+ # pose = robot_tools._get_tf_tree_transform("odom", "base_link", return_type="pose_quaternion")
139
+ # print(f"Position: {pose.position}")
140
+ # print(f"Orientation: {pose.orientation}")
141
+
142
+ # # 获取齐次矩阵
143
+ # homogeneous = robot_tools._get_tf_tree_transform("odom", "base_link", return_type="homogeneous")
144
+ # print(f"Transformation matrix:\n{homogeneous.matrix}")
145
+
146
+ # # 矩阵运算示例
147
+ # transform_matrix = homogeneous.matrix
148
+ # inverse_matrix = np.linalg.inv(transform_matrix) # 求逆变换
149
+ # print(f"Inverse matrix:\n{inverse_matrix}")
@@ -0,0 +1,272 @@
1
+ #! /usr/bin/env python3
2
+ # coding: utf-8
3
+ import rospy
4
+ import copy
5
+ import time
6
+ from collections import deque
7
+ from typing import Tuple, Optional
8
+
9
+ from kuavo_humanoid_sdk.kuavo.core.ros.param import make_robot_param, EndEffectorType
10
+ from kuavo_humanoid_sdk.common.logger import SDKLogger
11
+ from kuavo_humanoid_sdk.interfaces.data_types import (AprilTagData)
12
+
13
+ from std_msgs.msg import Float64
14
+ from nav_msgs.msg import Odometry
15
+ from sensor_msgs.msg import JointState
16
+ from apriltag_ros.msg import AprilTagDetectionArray
17
+ from geometry_msgs.msg import TransformStamped, PoseStamped
18
+ import tf2_ros
19
+ import tf2_geometry_msgs
20
+
21
+ class KuavoRobotVisionCore:
22
+ """Handles vision-related data processing for Kuavo humanoid robot.
23
+
24
+ Attributes:
25
+ tf_buffer (tf2_ros.Buffer): TF2 transform buffer
26
+ tf_listener (tf2_ros.TransformListener): TF2 transform listener
27
+ tf_broadcaster (tf2_ros.TransformBroadcaster): TF2 transform broadcaster
28
+ """
29
+
30
+ def __init__(self):
31
+ """Initializes vision system components including TF and AprilTag subscribers."""
32
+ if not hasattr(self, '_initialized'):
33
+ self.tf_buffer = tf2_ros.Buffer()
34
+ self.tf_listener = tf2_ros.TransformListener(self.tf_buffer)
35
+ self.tf_broadcaster = tf2_ros.TransformBroadcaster()
36
+ self._apriltag_data_camera_sub = rospy.Subscriber('/tag_detections', AprilTagDetectionArray, self._apriltag_data_callback_camera)
37
+ self._apriltag_data_base_sub = rospy.Subscriber('/robot_tag_info', AprilTagDetectionArray, self._apriltag_data_callback_base)
38
+
39
+ # 添加TF2监听器
40
+ self._tf_buffer = tf2_ros.Buffer()
41
+ self._tf_listener = tf2_ros.TransformListener(self._tf_buffer)
42
+
43
+ """ data """
44
+ self._apriltag_data_from_camera = AprilTagData(
45
+ id = [],
46
+ size = [],
47
+ pose = []
48
+ )
49
+
50
+ self._apriltag_data_from_base = AprilTagData(
51
+ id = [],
52
+ size = [],
53
+ pose = []
54
+ )
55
+
56
+ self._apriltag_data_from_odom = AprilTagData(
57
+ id = [],
58
+ size = [],
59
+ pose = []
60
+ )
61
+
62
+ def _apriltag_data_callback_camera(self, data: AprilTagDetectionArray):
63
+ """Callback for processing AprilTag detections from camera.
64
+
65
+ Args:
66
+ data (AprilTagDetectionArray): Raw detection data from camera
67
+ """
68
+ # 清空之前的数据
69
+ self._apriltag_data_from_camera.id = []
70
+ self._apriltag_data_from_camera.size = []
71
+ self._apriltag_data_from_camera.pose = []
72
+
73
+ # 处理每个标签检测
74
+ for detection in data.detections:
75
+ # 添加ID
76
+ for id in detection.id:
77
+ self._apriltag_data_from_camera.id.append(id)
78
+
79
+ # 添加尺寸 (从size数组中获取)
80
+ if detection.size and len(detection.size) > 0:
81
+ self._apriltag_data_from_camera.size.append(detection.size[0])
82
+ else:
83
+ self._apriltag_data_from_camera.size.append(0.0)
84
+
85
+ # 添加姿态
86
+ self._apriltag_data_from_camera.pose.append(detection.pose.pose.pose)
87
+ # # debug
88
+ # rospy.loginfo("Apriltag data from camera: %s", self._apriltag_data_from_camera)
89
+
90
+ def _apriltag_data_callback_base(self, data: AprilTagDetectionArray):
91
+ """Callback for processing AprilTag detections from base link.
92
+
93
+ Args:
94
+ data (AprilTagDetectionArray): Raw detection data from base frame
95
+ """
96
+ # 清空之前的数据
97
+ self._apriltag_data_from_base.id = []
98
+ self._apriltag_data_from_base.size = []
99
+ self._apriltag_data_from_base.pose = []
100
+
101
+ # 处理每个标签检测
102
+ for detection in data.detections:
103
+ # 添加ID
104
+ for id in detection.id:
105
+ self._apriltag_data_from_base.id.append(id)
106
+
107
+ # 添加尺寸 (从size数组中获取)
108
+ if detection.size and len(detection.size) > 0:
109
+ self._apriltag_data_from_base.size.append(detection.size[0])
110
+ else:
111
+ self._apriltag_data_from_base.size.append(0.0)
112
+
113
+ # 添加姿态
114
+ self._apriltag_data_from_base.pose.append(detection.pose.pose.pose)
115
+
116
+ # # debug
117
+ # rospy.loginfo("Apriltag data from base: %s", self._apriltag_data_from_base)
118
+
119
+ # 在基础数据处理完后,尝试进行odom坐标系的变换
120
+ self._transform_base_to_odom()
121
+
122
+ def _transform_base_to_odom(self):
123
+ """Transforms AprilTag poses from base_link to odom coordinate frame.
124
+
125
+ Performs:
126
+ - Coordinate transformation using TF2
127
+ - TF broadcasting for transformed poses
128
+ - Data validation and error handling
129
+
130
+ Raises:
131
+ tf2_ros.LookupException: If transform is not available
132
+ tf2_ros.ConnectivityException: If transform chain is broken
133
+ tf2_ros.ExtrapolationException: If transform time is out of range
134
+ """
135
+ # 添加节点状态检查
136
+ if rospy.is_shutdown():
137
+ return
138
+
139
+ # 清空之前的数据
140
+ self._apriltag_data_from_odom.id = []
141
+ self._apriltag_data_from_odom.size = []
142
+ self._apriltag_data_from_odom.pose = []
143
+
144
+ # 如果base数据为空,则不处理
145
+ if not self._apriltag_data_from_base.id:
146
+ SDKLogger.warn("No base tag data, skip transform")
147
+ return
148
+
149
+ try:
150
+ # 获取从base_link到odom的变换
151
+ transform = self._tf_buffer.lookup_transform(
152
+ "odom",
153
+ "base_link",
154
+ rospy.Time(0),
155
+ rospy.Duration(1.0)
156
+ )
157
+
158
+ # 复制ID和尺寸信息
159
+ self._apriltag_data_from_odom.id = self._apriltag_data_from_base.id.copy()
160
+ self._apriltag_data_from_odom.size = self._apriltag_data_from_base.size.copy()
161
+
162
+ # 对每个姿态进行变换
163
+ for idx, (tag_id, pose) in enumerate(zip(self._apriltag_data_from_base.id, self._apriltag_data_from_base.pose)):
164
+ # 创建PoseStamped消息
165
+ pose_stamped = PoseStamped()
166
+ pose_stamped.header.frame_id = "base_link"
167
+ pose_stamped.header.stamp = rospy.Time.now()
168
+ pose_stamped.pose = pose
169
+
170
+ # 执行变换
171
+ transformed_pose = tf2_geometry_msgs.do_transform_pose(pose_stamped, transform)
172
+
173
+ # 将变换后的姿态添加到odom数据中
174
+ self._apriltag_data_from_odom.pose.append(transformed_pose.pose)
175
+
176
+ # 创建并广播TF
177
+ transform_stamped = TransformStamped()
178
+ transform_stamped.header.stamp = rospy.Time.now()
179
+ transform_stamped.header.frame_id = "odom"
180
+ transform_stamped.child_frame_id = f"tag_odom_{tag_id}"
181
+ transform_stamped.transform.translation.x = transformed_pose.pose.position.x
182
+ transform_stamped.transform.translation.y = transformed_pose.pose.position.y
183
+ transform_stamped.transform.translation.z = transformed_pose.pose.position.z
184
+ transform_stamped.transform.rotation = transformed_pose.pose.orientation
185
+
186
+ # 发送变换前再次检查节点状态
187
+ if not rospy.is_shutdown():
188
+ self.tf_broadcaster.sendTransform(transform_stamped)
189
+
190
+ except (tf2_ros.LookupException,
191
+ tf2_ros.ConnectivityException,
192
+ tf2_ros.ExtrapolationException,
193
+ rospy.ROSException) as e: # 添加ROSException捕获
194
+ SDKLogger.warn(f"TF变换异常: {str(e)}")
195
+
196
+ @property
197
+ def apriltag_data_from_camera(self) -> AprilTagData:
198
+ """AprilTag detection data in camera coordinate frame.
199
+
200
+ Returns:
201
+ AprilTagData: Contains lists of tag IDs, sizes and poses
202
+ """
203
+ return self._apriltag_data_from_camera
204
+
205
+ @property
206
+ def apriltag_data_from_base(self) -> AprilTagData:
207
+ """AprilTag detection data in base_link coordinate frame.
208
+
209
+ Returns:
210
+ AprilTagData: Contains lists of tag IDs, sizes and poses
211
+ """
212
+ return self._apriltag_data_from_base
213
+
214
+ @property
215
+ def apriltag_data_from_odom(self) -> AprilTagData:
216
+ """AprilTag detection data in odom coordinate frame.
217
+
218
+ Returns:
219
+ AprilTagData: Contains lists of tag IDs, sizes and transformed poses
220
+ """
221
+ return self._apriltag_data_from_odom
222
+
223
+ def _get_data_by_id(self, target_id: int, data_source: str = "base") -> Optional[dict]:
224
+ """Retrieves AprilTag data by specific ID from selected source.
225
+
226
+ Args:
227
+ target_id (int): AprilTag ID to search for
228
+ data_source (str): Data source selector, valid options:
229
+ "camera", "base", "odom"
230
+
231
+ Returns:
232
+ Optional[dict]: Dictionary containing 'sizes' and 'poses' lists if found,
233
+ None if no matching data
234
+
235
+ Raises:
236
+ ValueError: If invalid data_source is specified
237
+ """
238
+ data_map = {
239
+ "camera": self._apriltag_data_from_camera,
240
+ "base": self._apriltag_data_from_base,
241
+ "odom": self._apriltag_data_from_odom
242
+ }
243
+
244
+ if data_source not in data_map:
245
+ SDKLogger.error(f"Invalid data source: {data_source}, must be one of {list(data_map.keys())}")
246
+ return None
247
+
248
+ data = data_map[data_source]
249
+
250
+ # 查找所有匹配的索引
251
+ indices = [i for i, tag_id in enumerate(data.id) if tag_id == target_id]
252
+
253
+ if not indices:
254
+ SDKLogger.debug(f"No data found for tag ID {target_id} in {data_source} source")
255
+ return None
256
+
257
+ return {
258
+ "sizes": [data.size[i] for i in indices],
259
+ "poses": [data.pose[i] for i in indices]
260
+ }
261
+
262
+ # if __name__ == "__main__":
263
+
264
+ # kuavo_robot_vision_core = KuavoRobotVisionCore()
265
+ # time.sleep(5)
266
+ # print("apriltag_data_from_camera:")
267
+ # print(kuavo_robot_vision_core.apriltag_data_from_camera)
268
+ # print("apriltag_data_from_base:")
269
+ # print(kuavo_robot_vision_core.apriltag_data_from_base)
270
+ # print("apriltag_data_from_odom:")
271
+ # print(kuavo_robot_vision_core.apriltag_data_from_odom)
272
+ # rospy.spin()
@@ -2,10 +2,15 @@
2
2
  # coding: utf-8
3
3
 
4
4
  import os
5
- import rospy
5
+ try:
6
+ import rospy
7
+ except ImportError:
8
+ pass
6
9
  import subprocess
7
10
  import atexit
8
11
  from kuavo_humanoid_sdk.common.logger import SDKLogger
12
+ from kuavo_humanoid_sdk.common.websocket_kuavo_sdk import WebSocketKuavoSDK
13
+ import roslibpy
9
14
 
10
15
  class KuavoROSEnv:
11
16
  _instance = None
@@ -232,3 +237,226 @@ class KuavoROSEnv:
232
237
  except Exception as e:
233
238
  SDKLogger.error(f"Error checking if node {node_name} exists: {e}")
234
239
  return False
240
+
241
+ class KuavoROSEnvWebsocket:
242
+ _instance = None
243
+ _processes = [] # Store all subprocess instances
244
+
245
+ def __new__(cls):
246
+ if cls._instance is None:
247
+ cls._instance = super(KuavoROSEnvWebsocket, cls).__new__(cls)
248
+ cls._instance._initialized = False
249
+ cls._instance._init_success = False # Add flag to track successful Init() call
250
+ # Register cleanup handler
251
+ atexit.register(cls._cleanup_processes)
252
+ return cls._instance
253
+
254
+ def __init__(self):
255
+ if not self._initialized:
256
+ self._initialized = True
257
+ self.websocket = None
258
+
259
+ @classmethod
260
+ def _cleanup_processes(cls):
261
+ """Cleanup all registered processes on exit"""
262
+ for process in cls._processes:
263
+ if process.poll() is None: # Process is still running
264
+ process.terminate()
265
+ try:
266
+ process.wait(timeout=3) # Wait for process to terminate
267
+ except subprocess.TimeoutExpired:
268
+ process.kill() # Force kill if not terminated
269
+ cls._processes.clear()
270
+
271
+ def _get_kuavo_ws_root(self) -> str:
272
+ # For WebSocket version, we'll use environment variable instead of ROS param
273
+ model_path = os.environ.get('KUAVO_MODEL_PATH')
274
+ if not model_path:
275
+ raise Exception("KUAVO_MODEL_PATH environment variable not found")
276
+
277
+ if not os.path.exists(model_path):
278
+ raise Exception(f"Model path {model_path} not found")
279
+
280
+ # ws
281
+ return model_path.replace('/src/kuavo_assets/models', '')
282
+
283
+ def Init(self) -> bool:
284
+ """
285
+ Initialize the WebSocket environment.
286
+ Raises:
287
+ Exception: If the KUAVO_MODEL_PATH environment variable is not found or the path is not valid.
288
+ """
289
+ # if generate docs, skip init.
290
+ if 'GEN_KUAVO_HUMANOID_SDK_DOCS' in os.environ:
291
+ return True
292
+
293
+ # Return directly if already initialized successfully
294
+ if self._init_success:
295
+ return True
296
+
297
+ # Check if WebSocket server is running
298
+ try:
299
+
300
+ self.websocket = WebSocketKuavoSDK()
301
+ if not self.websocket.client.is_connected:
302
+ print(f"\033[31m\nError: Can't connect to WebSocket server. Please ensure the server is running.\033[0m"
303
+ "\nMaybe manually launch the app first?"
304
+ "\n - for example(sim): roslaunch humanoid_controller load_kuavo_mujoco_sim.launch, "
305
+ "\n - for example(real): roslaunch humanoid_controller load_kuavo_real.launch\n")
306
+ exit(1)
307
+ except Exception as e:
308
+ print(f"\033[31m\nError: Failed to connect to WebSocket server: {e}\033[0m")
309
+ exit(1)
310
+
311
+ # Only check nodes exist when Init SDK, if not, tips user manually launch nodes.
312
+ deps_nodes = ['/humanoid_gait_switch_by_name']
313
+ for node in deps_nodes:
314
+ if not self.check_rosnode_exists(node):
315
+ print(f"\033[31m\nError: Node {node} not found. Please launch it manually.\033[0m")
316
+ exit(1)
317
+
318
+ self._init_success = True # Set flag after successful initialization
319
+
320
+ return True
321
+
322
+ def _launch_ros_node(self, node_name, launch_cmd, log_name):
323
+ """Launch a ROS node with the given command and log the output.
324
+
325
+ Args:
326
+ node_name (str): Name of the node to launch
327
+ launch_cmd (str): Full launch command including source and roslaunch
328
+ log_name (str): Name for the log file
329
+
330
+ Raises:
331
+ Exception: If node launch fails
332
+ """
333
+ # Launch in background and check if successful
334
+ try:
335
+ os.makedirs('/var/log/kuavo_humanoid_sdk', exist_ok=True)
336
+ log_path = f'/var/log/kuavo_humanoid_sdk/{log_name}.log'
337
+ except PermissionError:
338
+ os.makedirs('log/kuavo_humanoid_sdk', exist_ok=True)
339
+ log_path = f'log/kuavo_humanoid_sdk/{log_name}.log'
340
+
341
+ with open(log_path, 'w') as log_file:
342
+ process = subprocess.Popen(launch_cmd, shell=True, executable='/bin/bash', stdout=log_file, stderr=log_file)
343
+ self._processes.append(process) # Add process to tracking list
344
+
345
+ if process.returncode is not None and process.returncode != 0:
346
+ raise Exception(f"Failed to launch {node_name}, return code: {process.returncode}")
347
+
348
+ SDKLogger.info(f"{node_name} launched successfully")
349
+
350
+ def _get_setup_file(self, ws_root=None):
351
+ """Get the appropriate ROS setup file path based on shell type.
352
+
353
+ Args:
354
+ ws_root (str, optional): ROS workspace root path. If None, uses ROS_WORKSPACE.
355
+
356
+ Returns:
357
+ str: Path to the setup file
358
+
359
+ Raises:
360
+ Exception: If setup file not found
361
+ """
362
+ is_zsh = 'zsh' in os.environ.get('SHELL', '')
363
+
364
+ if ws_root is None:
365
+ ws_root = os.environ['ROS_WORKSPACE']
366
+
367
+ setup_files = {
368
+ 'zsh': os.path.join(ws_root, 'devel/setup.zsh'),
369
+ 'bash': os.path.join(ws_root, 'devel/setup.bash')
370
+ }
371
+
372
+ setup_file = setup_files['zsh'] if is_zsh else setup_files['bash']
373
+ if not os.path.exists(setup_file):
374
+ setup_file = setup_file.replace('devel', 'install')
375
+ if not os.path.exists(setup_file):
376
+ raise Exception(f"Setup file not found in either devel or install: {setup_file}")
377
+
378
+ return setup_file
379
+
380
+ def launch_ik_node(self):
381
+ # nodes: /arms_ik_node
382
+ # services: /ik/two_arm_hand_pose_cmd_srv, /ik/fk_srv
383
+ try:
384
+ if not self.websocket or not self.websocket.client.is_connected:
385
+ raise Exception("WebSocket server is not running")
386
+ except Exception as e:
387
+ raise Exception(f"WebSocket server is not running: {e}")
388
+
389
+ # Check if IK node and services exist
390
+ try:
391
+ # Check if arms_ik_node is running using roslibpy
392
+ service = roslibpy.Service(self.websocket.client, '/rosnode/list', 'rosapi/Nodes')
393
+ response = service.call({})
394
+ nodes = response.get('nodes', [])
395
+
396
+ if '/arms_ik_node' not in nodes:
397
+ # Launch IK node if not running
398
+ kuavo_ws_root = self._get_kuavo_ws_root()
399
+ setup_file = self._get_setup_file(kuavo_ws_root)
400
+ source_cmd = f"source {setup_file}"
401
+
402
+ # Get robot version from environment variable
403
+ robot_version = os.environ.get('ROBOT_VERSION')
404
+ if robot_version is None:
405
+ raise Exception("Failed to get ROBOT_VERSION from environment variables")
406
+
407
+ # Launch IK node
408
+ launch_cmd = f"roslaunch motion_capture_ik ik_node.launch robot_version:={robot_version}"
409
+ full_cmd = f"{source_cmd} && {launch_cmd}"
410
+
411
+ self._launch_ros_node('IK node', full_cmd, 'launch_ik')
412
+
413
+ return True
414
+
415
+ except Exception as e:
416
+ raise Exception(f"Failed to verify IK node and services: {e}")
417
+
418
+
419
+ def launch_gait_switch_node(self)-> bool:
420
+ """Verify that the gait switch node is running, launch if not."""
421
+ try:
422
+ # Check if node exists using roslibpy
423
+ service = roslibpy.Service(self.websocket.client, '/rosnode/list', 'rosapi/Nodes')
424
+ response = service.call({})
425
+ nodes = response.get('nodes', [])
426
+
427
+ if '/humanoid_gait_switch_by_name' not in nodes:
428
+ kuavo_ws_root = self._get_kuavo_ws_root()
429
+ setup_file = self._get_setup_file(kuavo_ws_root)
430
+ source_cmd = f"source {setup_file}"
431
+
432
+ # Launch gait switch node
433
+ launch_cmd = "roslaunch humanoid_interface_ros humanoid_switch_gait.launch"
434
+ full_cmd = f"{source_cmd} && {launch_cmd}"
435
+
436
+ self._launch_ros_node('Gait switch node', full_cmd, 'launch_gait_switch')
437
+
438
+ except Exception as e:
439
+ raise Exception(f"Failed to launch gait_switch node: {e}")
440
+
441
+ @staticmethod
442
+ def check_rosnode_exists(node_name):
443
+ """Check if a ROS node is running using roslibpy.
444
+
445
+ Args:
446
+ node_name (str): Name of the node to check
447
+
448
+ Returns:
449
+ bool: True if node is running, False otherwise
450
+ """
451
+ websocket = WebSocketKuavoSDK()
452
+ try:
453
+ if not websocket or not websocket.client.is_connected:
454
+ return False
455
+
456
+ service = roslibpy.Service(websocket.client, '/rosapi/nodes', 'rosapi/Nodes')
457
+ response = service.call({})
458
+ nodes = response.get('nodes', [])
459
+ return node_name in nodes
460
+ except Exception as e:
461
+ SDKLogger.error(f"Error checking if node {node_name} exists: {e}")
462
+ return False
@@ -4,7 +4,8 @@ from typing import Tuple
4
4
  from kuavo_humanoid_sdk.interfaces.end_effector import EndEffector
5
5
  from kuavo_humanoid_sdk.interfaces.data_types import EndEffectorSide, EndEffectorState, KuavoDexHandTouchState
6
6
  from kuavo_humanoid_sdk.kuavo.core.dex_hand_control import DexHandControl
7
- from kuavo_humanoid_sdk.kuavo.core.ros.state import KuavoRobotStateCore
7
+ from kuavo_humanoid_sdk.kuavo.core.ros.state import KuavoRobotStateCore, KuavoRobotStateCoreWebsocket
8
+ from kuavo_humanoid_sdk.common.global_config import GlobalConfig
8
9
 
9
10
  class DexterousHand(EndEffector):
10
11
  def __init__(self):
@@ -12,7 +13,10 @@ class DexterousHand(EndEffector):
12
13
  'r_thumb', 'r_thumb_aux', 'r_index', 'r_middle', 'r_ring', 'r_pinky',]
13
14
  super().__init__(joint_names=joint_names)
14
15
  self.dex_hand_control = DexHandControl()
15
- self._rb_state = KuavoRobotStateCore()
16
+ if GlobalConfig.use_websocket:
17
+ self._rb_state = KuavoRobotStateCoreWebsocket()
18
+ else:
19
+ self._rb_state = KuavoRobotStateCore()
16
20
 
17
21
  def control(self, target_positions:list, target_velocities:list=None, target_torques:list=None)->bool:
18
22
  """Set the position of the hand.