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.
Files changed (43) hide show
  1. kuavo_humanoid_sdk/__init__.py +6 -0
  2. kuavo_humanoid_sdk/common/launch_robot_tool.py +170 -0
  3. kuavo_humanoid_sdk/common/logger.py +45 -0
  4. kuavo_humanoid_sdk/common/websocket_kuavo_sdk.py +26 -0
  5. kuavo_humanoid_sdk/interfaces/__init__.py +4 -0
  6. kuavo_humanoid_sdk/interfaces/data_types.py +293 -0
  7. kuavo_humanoid_sdk/interfaces/end_effector.py +62 -0
  8. kuavo_humanoid_sdk/interfaces/robot.py +22 -0
  9. kuavo_humanoid_sdk/interfaces/robot_info.py +56 -0
  10. kuavo_humanoid_sdk/kuavo/__init__.py +12 -0
  11. kuavo_humanoid_sdk/kuavo/core/audio.py +32 -0
  12. kuavo_humanoid_sdk/kuavo/core/core.py +755 -0
  13. kuavo_humanoid_sdk/kuavo/core/dex_hand_control.py +114 -0
  14. kuavo_humanoid_sdk/kuavo/core/leju_claw_control.py +67 -0
  15. kuavo_humanoid_sdk/kuavo/core/ros/audio.py +86 -0
  16. kuavo_humanoid_sdk/kuavo/core/ros/control.py +1325 -0
  17. kuavo_humanoid_sdk/kuavo/core/ros/observation.py +125 -0
  18. kuavo_humanoid_sdk/kuavo/core/ros/param.py +335 -0
  19. kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
  20. kuavo_humanoid_sdk/kuavo/core/ros/state.py +426 -0
  21. kuavo_humanoid_sdk/kuavo/core/ros/tools.py +197 -0
  22. kuavo_humanoid_sdk/kuavo/core/ros/vision.py +280 -0
  23. kuavo_humanoid_sdk/kuavo/core/ros_env.py +236 -0
  24. kuavo_humanoid_sdk/kuavo/dexterous_hand.py +198 -0
  25. kuavo_humanoid_sdk/kuavo/leju_claw.py +232 -0
  26. kuavo_humanoid_sdk/kuavo/robot.py +550 -0
  27. kuavo_humanoid_sdk/kuavo/robot_arm.py +235 -0
  28. kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
  29. kuavo_humanoid_sdk/kuavo/robot_head.py +39 -0
  30. kuavo_humanoid_sdk/kuavo/robot_info.py +235 -0
  31. kuavo_humanoid_sdk/kuavo/robot_observation.py +69 -0
  32. kuavo_humanoid_sdk/kuavo/robot_state.py +346 -0
  33. kuavo_humanoid_sdk/kuavo/robot_tool.py +58 -0
  34. kuavo_humanoid_sdk/kuavo/robot_vision.py +82 -0
  35. kuavo_humanoid_sdk/kuavo/robot_waist.py +53 -0
  36. kuavo_humanoid_sdk/kuavo_strategy/__init__.py +2 -0
  37. kuavo_humanoid_sdk/kuavo_strategy/grasp_box/grasp_box_strategy.py +418 -0
  38. kuavo_humanoid_sdk/kuavo_strategy/kuavo_strategy.py +63 -0
  39. kuavo_humanoid_sdk/msg/__init__.py +4 -0
  40. kuavo_humanoid_sdk_ws-1.3.2b397.dist-info/METADATA +279 -0
  41. kuavo_humanoid_sdk_ws-1.3.2b397.dist-info/RECORD +43 -0
  42. kuavo_humanoid_sdk_ws-1.3.2b397.dist-info/WHEEL +6 -0
  43. kuavo_humanoid_sdk_ws-1.3.2b397.dist-info/top_level.txt +1 -0
@@ -0,0 +1,6 @@
1
+ from .msg import *
2
+ from .interfaces import *
3
+ from .kuavo import *
4
+ #from .kuavo_strategy import *
5
+ #from .kuavo_strategy.grasp_box import *
6
+ from kuavo_humanoid_sdk.common.logger import SDKLogger, disable_sdk_logging
@@ -0,0 +1,170 @@
1
+ import roslibpy
2
+ import time
3
+ from typing import Tuple
4
+ from kuavo_humanoid_sdk.common.logger import SDKLogger
5
+ from kuavo_humanoid_sdk.common.websocket_kuavo_sdk import WebSocketKuavoSDK
6
+
7
+
8
+ class LaunchRobotStatus:
9
+ # 与硬件节点保持一致
10
+ UNLAUNCH = 'unlaunch'
11
+ INITING = 'initing'
12
+ UNKNOWN = 'unknown'
13
+ READY_STANCE = 'ready_stance'
14
+ CALIBRATE = 'calibrate'
15
+ LAUNCHED = 'launched'
16
+
17
+ class LaunchRobotTool:
18
+ def __init__(self):
19
+ self._websocket = WebSocketKuavoSDK()
20
+ self._stand_timeout = 10.0
21
+ self._srv_robot_start = roslibpy.Service(self._websocket.client, '/websocket_sdk_srv/start_robot', 'std_srvs/Trigger')
22
+ self._srv_robot_stand = roslibpy.Service(self._websocket.client, '/websocket_sdk_srv/stand_robot', 'std_srvs/Trigger')
23
+ self._srv_get_robot_launch_status = roslibpy.Service(self._websocket.client, '/websocket_sdk_srv/get_robot_launch_status', 'std_srvs/Trigger')
24
+ self._srv_robot_stop = roslibpy.Service(self._websocket.client, '/websocket_sdk_srv/stop_robot', 'std_srvs/Trigger')
25
+
26
+ def is_unlaunch(self, status:str)->bool:
27
+ return status == LaunchRobotStatus.UNLAUNCH or status == LaunchRobotStatus.UNKNOWN
28
+
29
+ def is_launched(self, status:str)->bool:
30
+ return status == LaunchRobotStatus.LAUNCHED
31
+
32
+ def is_launching(self, status:str)->bool:
33
+ return self.is_calibrate(status) or self.is_ready_stance(status)
34
+
35
+ def is_calibrate(self, status:str)->bool:
36
+ return status == LaunchRobotStatus.CALIBRATE
37
+
38
+ def is_ready_stance(self, status:str)->bool:
39
+ return status == LaunchRobotStatus.READY_STANCE
40
+
41
+ def robot_start(self) -> bool:
42
+ # launch robot
43
+ if not self.pub_start_command():
44
+ return False
45
+ try:
46
+ timeout = 120 # 120s 等待进入校准或准备姿态
47
+ start_time = time.time()
48
+ last_print = time.time()
49
+ print("\033[32m>_ 机器人启动中\033[0m", end="", flush=True)
50
+ while True:
51
+ if time.time() - start_time > timeout:
52
+ SDKLogger.error("Robot launch timed out")
53
+ return False
54
+ success, status = self.get_robot_launch_status()
55
+ # 如果机器人启动成功,已经进入校准或准备状态或者launched状态,则启动成功
56
+ if success and (self.is_launched(status) or self.is_launching(status)):
57
+ print("\n")
58
+ return True
59
+
60
+ current_time = time.time()
61
+ if current_time - last_print >= 0.8:
62
+ print("\033[32m.\033[0m", end="", flush=True)
63
+ last_print = current_time
64
+ time.sleep(0.2)
65
+ except KeyboardInterrupt:
66
+ print("\n")
67
+ SDKLogger.info("Received keyboard interrupt, stopping robot launch")
68
+ return False
69
+
70
+ def robot_stop(self)->bool:
71
+ """
72
+ 停止机器人
73
+ """
74
+ try:
75
+ request = roslibpy.ServiceRequest({})
76
+ response = self._srv_robot_stop.call(request)
77
+ return response.get('success', False)
78
+ except Exception as e:
79
+ SDKLogger.error(f"[Error] calling stop robot service: {e}")
80
+ return False
81
+
82
+ def robot_stand(self)->bool:
83
+ try:
84
+ while True:
85
+ # 获取当前启动状态, 如果已启动则返回
86
+ success, status = self.get_robot_launch_status()
87
+ if not success:
88
+ SDKLogger.error(f"[Error] Failed to get robot launch status: {status}")
89
+ return False
90
+ if self.is_launched(status):
91
+ return True
92
+
93
+ # 从当前状态确认下一个状态
94
+ next_state = None
95
+ if self.is_calibrate(status):
96
+ print("\033[32m>_ [校准状态]: 机器人当前处于校准状态,确认无误,请输入 y 键进入准备姿态\033[0m")
97
+ next_state = LaunchRobotStatus.READY_STANCE
98
+ elif self.is_ready_stance(status):
99
+ print("\033[32m>_ [准备姿态]: 请等待机器人缩腿到下蹲姿势,并将其下降到距离地面 2cm 处,确认无误后,请输入 y 键\033[0m")
100
+ next_state = LaunchRobotStatus.LAUNCHED
101
+
102
+ if self.is_calibrate(status) or self.is_ready_stance(status):
103
+ while True:
104
+ try:
105
+ choice = input().lower()
106
+ if choice == 'y':
107
+ break
108
+ elif choice == 'n':
109
+ return False
110
+ else:
111
+ SDKLogger.error("输入错误,请输入 y 键")
112
+ except KeyboardInterrupt:
113
+ return False
114
+
115
+ # 发布站立命令
116
+ if not self.pub_stand_command():
117
+ return False
118
+
119
+ # 等待进入下一个状态
120
+ start_time = time.time()
121
+ while True:
122
+ if time.time() - start_time > self._stand_timeout:
123
+ break
124
+ success, current_status = self.get_robot_launch_status()
125
+ if not success:
126
+ SDKLogger.error(f"[Error] Wait next state Failed to get robot launch status: {current_status}")
127
+ return False
128
+ if self.is_launched(current_status):
129
+ return True
130
+ elif current_status == next_state:
131
+ # 成功进入下一个状态
132
+ break
133
+ time.sleep(0.2)
134
+ time.sleep(0.2)
135
+ except KeyboardInterrupt:
136
+ SDKLogger.info("Received keyboard interrupt, stopping robot stand")
137
+ return False
138
+
139
+ def pub_start_command(self) -> bool:
140
+ try:
141
+ request = roslibpy.ServiceRequest({})
142
+ response = self._srv_robot_start.call(request)
143
+ result = response.get('success', False)
144
+ return result
145
+ except Exception as e:
146
+ SDKLogger.error(f"[Error] calling start service: {e}")
147
+ return False
148
+
149
+ def pub_stand_command(self) -> bool:
150
+ try:
151
+ request = {}
152
+ response = self._srv_robot_stand.call(request)
153
+ if not response.get('success', False):
154
+ SDKLogger.error(f"Failed to make robot stand: {response.get('message', '')}")
155
+ return response.get('success', False)
156
+ except Exception as e:
157
+ SDKLogger.error(f"[Error] calling stand service: {e}")
158
+ return False
159
+
160
+
161
+ def get_robot_launch_status(self)->Tuple[bool, str]:
162
+ try:
163
+ request = roslibpy.ServiceRequest({})
164
+ response = self._srv_get_robot_launch_status.call(request)
165
+ success = response.get('success', False)
166
+ status = response.get('message', 'unknown')
167
+ return success, status
168
+ except Exception as e:
169
+ SDKLogger.error(f"[Error] calling get robot launch status service: {e}")
170
+ return False, "unknown"
@@ -0,0 +1,45 @@
1
+ import logging
2
+ import os
3
+ from pathlib import Path
4
+ from logging.handlers import RotatingFileHandler
5
+ def setup_logger():
6
+ logger = logging.getLogger('kuavo-humanoid-sdk')
7
+ logger.setLevel(logging.DEBUG)
8
+ log_suffix = f'log/kuavo_humanoid_sdk'
9
+ log_dir = f'/var/{log_suffix}'
10
+ try:
11
+ # Check if we have write permission for /var directory
12
+ if not os.access('/var/log/', os.W_OK):
13
+ log_dir = f'./{log_suffix}'
14
+ Path(log_dir).mkdir(parents=True, exist_ok=True)
15
+ except Exception as e:
16
+ # If creation in /var fails, create in current directory
17
+ log_dir = f'./{log_suffix}'
18
+ Path(log_dir).mkdir(parents=True, exist_ok=True)
19
+ log_file = f'{log_dir}/kuavo_humanoid_sdk.log'
20
+
21
+ print(f'kuavo-humanoid-sdk log_file: {log_file}')
22
+
23
+ fh = RotatingFileHandler(log_file, maxBytes=2*1024*1024, backupCount=5) # 每个日志文件最大 2 MB,保留 5 个备份文件
24
+ fh.setLevel(logging.DEBUG)
25
+
26
+ ch = logging.StreamHandler()
27
+ ch.setLevel(logging.DEBUG)
28
+
29
+ formatter = logging.Formatter('%(asctime)s - %(levelname)s - %(message)s')
30
+ fh.setFormatter(formatter)
31
+ ch.setFormatter(formatter)
32
+
33
+ logger.addHandler(fh)
34
+ logger.addHandler(ch)
35
+ return logger
36
+
37
+ def disable_sdk_logging():
38
+ """
39
+ Disable SDK logging.
40
+ """
41
+ logging.disable()
42
+
43
+
44
+ """ Logger """
45
+ SDKLogger = setup_logger()
@@ -0,0 +1,26 @@
1
+ import roslibpy
2
+
3
+ class WebSocketKuavoSDK:
4
+
5
+ _instance = None
6
+ _initialized = False
7
+
8
+ websocket_host = '127.0.0.1'
9
+ websocket_port = 9090
10
+ websocket_timeout = 5.0
11
+
12
+ def __new__(cls, *args, **kwargs):
13
+ if cls._instance is None:
14
+ cls._instance = super().__new__(cls)
15
+ return cls._instance
16
+
17
+ def __init__(self):
18
+ if not self._initialized:
19
+ self._initialized = True
20
+ self.client = roslibpy.Ros(host=WebSocketKuavoSDK.websocket_host, port=WebSocketKuavoSDK.websocket_port)
21
+ self.client.run(timeout=WebSocketKuavoSDK.websocket_timeout)
22
+
23
+
24
+ def __del__(self):
25
+ self.client.terminate()
26
+ self.instance = None
@@ -0,0 +1,4 @@
1
+ from .data_types import *
2
+ from .robot import *
3
+ from .end_effector import *
4
+ from .robot_info import *
@@ -0,0 +1,293 @@
1
+ from typing import Tuple
2
+ from enum import Enum
3
+ from dataclasses import dataclass
4
+ import numpy as np
5
+
6
+ @dataclass
7
+ class KuavoJointData:
8
+ """Data class representing joint states of the robot.
9
+
10
+ Args:
11
+ position (list): List of joint positions (angles) in radians
12
+ velocity (list): List of joint velocities in radians/second
13
+ torque (list): List of joint torques/efforts in Newton-meters or Amperes
14
+ acceleration (list): List of joint accelerations in radians/second^2
15
+ """
16
+ position: list
17
+ velocity: list
18
+ torque: list
19
+ acceleration:list
20
+
21
+ @dataclass
22
+ class KuavoImuData:
23
+ """Data class representing IMU (Inertial Measurement Unit) data from the robot.
24
+
25
+ Args:
26
+ gyro (Tuple[float, float, float]): Angular velocity around x, y, z axes in rad/s
27
+ acc (Tuple[float, float, float]): Linear acceleration in x, y, z axes in m/s^2
28
+ free_acc (Tuple[float, float, float]): Free acceleration (gravity compensated) in x, y, z axes in m/s^2
29
+ quat (Tuple[float, float, float, float]): Orientation quaternion (x, y, z, w)
30
+ """
31
+ gyro : Tuple[float, float, float]
32
+ acc : Tuple[float, float, float]
33
+ free_acc: Tuple[float, float, float]
34
+ quat: Tuple[float, float, float, float]
35
+
36
+ @dataclass
37
+ class KuavoOdometry:
38
+ """Data class representing odometry data from the robot.
39
+
40
+ Args:
41
+ position (Tuple[float, float, float]): Robot position (x, y, z) in world coordinates in meters
42
+ orientation (Tuple[float, float, float, float]): Robot orientation as quaternion (x, y, z, w)
43
+ linear (Tuple[float, float, float]): Linear velocity (x, y, z) in world coordinates in m/s
44
+ angular (Tuple[float, float, float]): Angular velocity (x, y, z) in world coordinates in rad/s
45
+ """
46
+ position: Tuple[float, float, float]
47
+ orientation: Tuple[float, float, float, float]
48
+ linear: Tuple[float, float, float]
49
+ angular: Tuple[float, float, float]
50
+
51
+ class KuavoArmCtrlMode(Enum):
52
+ """Enum class representing the control modes for the Kuavo robot arm.
53
+
54
+ Attributes:
55
+ ArmFixed: The robot arm is fixed in position (value: 0)
56
+ AutoSwing: The robot arm is in automatic swinging mode (value: 1)
57
+ ExternalControl: The robot arm is controlled by external commands (value: 2)
58
+ """
59
+ ArmFixed = 0
60
+ AutoSwing = 1
61
+ ExternalControl = 2
62
+
63
+ class KuavoManipulationMpcFrame(Enum):
64
+ """Enum class representing the manipulation mpc frame for the Kuavo robot end effector.
65
+
66
+ Attributes:
67
+ KeepCurrentFrame: Keep the current frame (value: 0)
68
+ WorldFrame: World frame (value: 1)
69
+ LocalFrame: Local frame (value: 2)
70
+ VRFrame: VR frame (value: 3)
71
+ ManipulationWorldFrame: Manipulation world frame (value: 4)
72
+ """
73
+ KeepCurrentFrame = 0
74
+ WorldFrame = 1
75
+ LocalFrame = 2
76
+ VRFrame = 3
77
+ ManipulationWorldFrame = 4
78
+ ERROR = -1
79
+
80
+ class KuavoManipulationMpcCtrlMode(Enum):
81
+ """Enum class representing the control mode for the Kuavo robot manipulation MPC.
82
+
83
+ Attributes:
84
+ NoControl: No control (value: 0)
85
+ ArmOnly: Only control the arm (value: 1)
86
+ BaseOnly: Only control the base (value: 2)
87
+ BaseArm: Control both the base and the arm (value: 3)
88
+ ERROR: Error state (value: -1)
89
+ """
90
+ NoControl = 0
91
+ ArmOnly = 1
92
+ BaseOnly = 2
93
+ BaseArm = 3
94
+ ERROR = -1
95
+
96
+ class KuavoManipulationMpcControlFlow(Enum):
97
+ """Enum class representing the control data flow for the Kuavo robot manipulation.
98
+
99
+ Attributes:
100
+ ThroughFullBodyMpc: Control data flows through full-body MPC before entering WBC (value: 0)
101
+ DirectToWbc: Control data flows directly to WBC without full-body MPC (value: 1)
102
+ Error: Invalid control path (value: -1)
103
+ """
104
+ ThroughFullBodyMpc = 0
105
+ DirectToWbc = 1
106
+ Error = -1
107
+
108
+ @dataclass
109
+ class EndEffectorState:
110
+ """Data class representing the state of the end effector.
111
+
112
+ Args:
113
+ position (list): float, Position of the end effector, range: [0, 100]
114
+ velocity (list): float, ...
115
+ effort (list): float, ...
116
+ """
117
+ position: list
118
+ velocity: list
119
+ effort: list
120
+ class GraspingState(Enum):
121
+ """Enum class representing the grasping states of the end effector.
122
+
123
+ Attributes:
124
+ ERROR: Error state (value: -1)
125
+ UNKNOWN: Unknown state (value: 0)
126
+ REACHED: Target position reached (value: 1)
127
+ MOVING: Moving to target position (value: 2)
128
+ GRABBED: Object successfully grasped (value: 3)
129
+ """
130
+ ERROR = -1
131
+ UNKNOWN = 0
132
+ MOVING = 1
133
+ REACHED = 2
134
+ GRABBED = 3
135
+
136
+ state: GraspingState # gripper grasping states
137
+
138
+ class EndEffectorSide(Enum):
139
+ """Enum class representing the sides of the end effector.
140
+
141
+ Attributes:
142
+ LEFT: The left side of the end effector (value: 'left')
143
+ RIGHT: The right side of the end effector (value: 'right')
144
+ BOTH: Both sides of the end effector (value: 'both')
145
+ """
146
+ LEFT = 'left'
147
+ RIGHT = 'right'
148
+ BOTH = 'both'
149
+
150
+ @dataclass
151
+ class KuavoPose:
152
+ """Data class representing the pose of the robot."""
153
+ position: Tuple[float, float, float] # x, y, z
154
+ orientation: Tuple[float, float, float, float] # x, y, z, w
155
+
156
+ @dataclass
157
+ class KuavoIKParams:
158
+ """Data class representing the parameters for the IK node."""
159
+ # snopt params
160
+ major_optimality_tol: float = 1e-3
161
+ major_feasibility_tol: float = 1e-3
162
+ minor_feasibility_tol: float = 1e-3
163
+ major_iterations_limit: float = 100
164
+ # constraint and cost params
165
+ oritation_constraint_tol: float = 1e-3
166
+ pos_constraint_tol: float = 1e-3 # 0.001m, work when pos_cost_weight==0.0
167
+ pos_cost_weight: float = 0.0 # If U need high accuracy, set this to 0.0 !!!
168
+
169
+ @dataclass
170
+ class KuavoDexHandTouchState:
171
+ """Data class representing the touch state of the dexterous hand."""
172
+
173
+ @dataclass
174
+ class KuavoTouchState:
175
+ """Data class representing the touch state of the dexterous hand."""
176
+ normal_force1: int # 法向力1
177
+ normal_force2: int # 法向力2
178
+ normal_force3: int # 法向力3
179
+ tangential_force1: int # 切向力1
180
+ tangential_force2: int # 切向力2
181
+ tangential_force3: int # 切向力3
182
+ tangential_direction1: int # 切向力方向1
183
+ tangential_direction2: int # 切向力方向2
184
+ tangential_direction3: int # 切向力方向3
185
+ self_proximity1: int # 自电容接近传感器1
186
+ self_proximity2: int # 自电容接近传感器2
187
+ mutual_proximity: int # 互电容接近传感器
188
+ status: int # 传感器状态
189
+ # 5 fingers
190
+ data: Tuple[KuavoTouchState, KuavoTouchState, KuavoTouchState, KuavoTouchState, KuavoTouchState]
191
+
192
+ @dataclass
193
+ class AprilTagData:
194
+ """Represents detected AprilTag information with pose estimation.
195
+
196
+ Attributes:
197
+ id (list): List of detected AprilTag IDs (integers)
198
+ size (list): List of tag physical sizes in meters (floats)
199
+ pose (list): List of PoseQuaternion objects representing tag poses
200
+ """
201
+ id: list
202
+ size: list
203
+ pose: list
204
+
205
+ @dataclass
206
+ class HomogeneousMatrix:
207
+ """4x4 homogeneous transformation matrix for 3D transformations.
208
+
209
+ Represents both rotation and translation in 3D space. Can be used for
210
+ coordinate frame transformations and pose composition.
211
+
212
+ Attributes:
213
+ matrix (np.ndarray): 4x4 numpy array of shape (4, 4) containing::
214
+
215
+ [[R, t],
216
+ [0, 1]]
217
+
218
+ where R is 3x3 rotation matrix and t is 3x1 translation
219
+ """
220
+ matrix: np.ndarray # Shape (4,4) homogeneous transformation matrix
221
+
222
+ @dataclass
223
+ class PoseQuaternion:
224
+ """3D pose representation using position and quaternion orientation.
225
+
226
+ Provides a singularity-free orientation representation. Commonly used
227
+ in robotics for smooth interpolation between orientations.
228
+
229
+ Attributes:
230
+ position (Tuple[float, float, float]): XYZ coordinates in meters
231
+ orientation (Tuple[float, float, float, float]): Unit quaternion in
232
+ (x, y, z, w) format following ROS convention
233
+ """
234
+ position: Tuple[float, float, float]
235
+ orientation: Tuple[float, float, float, float]
236
+
237
+
238
+ @dataclass
239
+ class KuavoJointCommand:
240
+ """Data class representing joint command for the robot.
241
+
242
+ Args:
243
+ joint_q (list): List of joint position commands in radians
244
+ joint_v (list): List of joint velocity commands in radians/second
245
+ tau (list): List of joint torque/effort commands in Newton-meters or Amperes
246
+ tau_max (list): List of maximum allowable torques for each joint
247
+ tau_ratio (list): List of torque ratios (actual/maximum) for each joint
248
+ joint_kp (list): List of position control proportional gains
249
+ joint_kd (list): List of velocity control derivative gains
250
+ control_modes (list): List of control mode integers for each joint
251
+ """
252
+ joint_q: list
253
+ joint_v: list
254
+ tau: list
255
+ tau_max: list
256
+ tau_ratio: list
257
+ joint_kp: list
258
+ joint_kd: list
259
+ control_modes: list
260
+
261
+
262
+ @dataclass
263
+ class KuavoTwist:
264
+ """Data class representing twist (velocity) data for the robot.
265
+
266
+ Args:
267
+ linear (Tuple[float, float, float]): Linear velocity (x, y, z)
268
+ angular (Tuple[float, float, float]): Angular velocity (x, y, z)
269
+ """
270
+ linear: Tuple[float, float, float]
271
+ angular: Tuple[float, float, float]
272
+
273
+
274
+
275
+ @dataclass
276
+ class AprilTagDetection:
277
+ """表示AprilTag检测结果的数据类"""
278
+
279
+ @dataclass
280
+ class Point:
281
+ x: float
282
+ y: float
283
+ z: float
284
+
285
+ @dataclass
286
+ class Quaternion:
287
+ x: float
288
+ y: float
289
+ z: float
290
+ w: float
291
+
292
+ position: Point
293
+ orientation: Quaternion
@@ -0,0 +1,62 @@
1
+ from abc import ABC, abstractmethod
2
+ from typing import Tuple
3
+ from kuavo_humanoid_sdk.interfaces.data_types import EndEffectorSide, EndEffectorState
4
+
5
+ class EndEffector(ABC):
6
+ def __init__(self, joint_names: list):
7
+ self._joint_names = joint_names
8
+
9
+ def joint_names(self)->list:
10
+ """Returns the joint names of the end effector.
11
+
12
+ Returns:
13
+ list: The joint names of the end effector.
14
+ """
15
+ return self._joint_names
16
+
17
+ def joint_count(self) -> int:
18
+ """Returns the total number of joints in the end effector.
19
+
20
+ The joint_names list contains joints for both left and right end effectors.
21
+ For a single end effector, the number of joints would be joint_names.size/2.
22
+
23
+ Returns:
24
+ int: The total number of joints in the end effector.
25
+ """
26
+ return len(self._joint_names)
27
+
28
+ @abstractmethod
29
+ def control(self, target_positions:list, target_velocities:list, target_torques:list)->bool:
30
+ pass
31
+
32
+ @abstractmethod
33
+ def control_right(self, target_positions:list, target_velocities:list, target_torques:list)->bool:
34
+ pass
35
+
36
+ @abstractmethod
37
+ def control_left(self, target_positions:list, target_velocities:list, target_torques:list)->bool:
38
+ pass
39
+
40
+ @abstractmethod
41
+ def open(self, side:EndEffectorSide)->bool:
42
+ pass
43
+
44
+ @abstractmethod
45
+ def get_state(self)->Tuple[EndEffectorState, EndEffectorState]:
46
+ pass
47
+
48
+ @abstractmethod
49
+ def get_position(self)->Tuple[list, list]:
50
+ pass
51
+
52
+ @abstractmethod
53
+ def get_velocity(self)->Tuple[list, list]:
54
+ pass
55
+
56
+ @abstractmethod
57
+ def get_effort(self)->Tuple[list, list]:
58
+ pass
59
+
60
+ @abstractmethod
61
+ def get_grasping_state(self)->Tuple[EndEffectorState.GraspingState, EndEffectorState.GraspingState]:
62
+ pass
@@ -0,0 +1,22 @@
1
+
2
+ from abc import ABC, abstractmethod
3
+
4
+ class RobotBase(ABC):
5
+ def __init__(self, robot_type: str = "kuavo"):
6
+ self._robot_type = robot_type
7
+
8
+ @property
9
+ def robot_type(self) -> str:
10
+ return self._robot_type
11
+
12
+ @abstractmethod
13
+ def trot(self):
14
+ pass
15
+
16
+ @abstractmethod
17
+ def stance(self):
18
+ pass
19
+
20
+ @abstractmethod
21
+ def jump(self):
22
+ pass
@@ -0,0 +1,56 @@
1
+ from abc import ABC, abstractmethod
2
+
3
+ class RobotInfoBase(ABC):
4
+ def __init__(self, robot_type: str = "kuavo"):
5
+ self._robot_type = robot_type
6
+
7
+ @property
8
+ def robot_type(self) -> str:
9
+ """
10
+ Get the robot type, e.g. "kuavo"
11
+ """
12
+ return self._robot_type
13
+
14
+ @property
15
+ @abstractmethod
16
+ def robot_version(self) -> str:
17
+ """
18
+ Get the robot version, e.g. "42", "43"
19
+ """
20
+ pass
21
+
22
+ @property
23
+ @abstractmethod
24
+ def end_effector_type(self) -> str:
25
+ """
26
+ Get the end effector type, e.g. "lejuclaw"...
27
+ """
28
+ pass
29
+
30
+ @property
31
+ @abstractmethod
32
+ def joint_names(self) -> list:
33
+ """
34
+ Get the joint names, e.g. ["joint1", "joint2", ...]
35
+ """
36
+ pass
37
+
38
+ @property
39
+ @abstractmethod
40
+ def joint_dof(self) -> int:
41
+ """
42
+ Get the joint degrees of freedom, e.g. 28
43
+ """
44
+ pass
45
+
46
+ @property
47
+ @abstractmethod
48
+ def arm_joint_dof(self) -> int:
49
+ """
50
+ Get the arm joint degrees of freedom, e.g. 14
51
+ """
52
+ pass
53
+
54
+ def __str__(self) -> str:
55
+ pass
56
+