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.

@@ -0,0 +1,258 @@
1
+ #!/usr/bin/env python3
2
+ # coding: utf-8
3
+ import time
4
+ from typing import Tuple
5
+ from kuavo_humanoid_sdk.interfaces.data_types import (
6
+ KuavoImuData, KuavoJointData, KuavoOdometry, KuavoArmCtrlMode,EndEffectorState)
7
+ from kuavo_humanoid_sdk.kuavo.core.ros.state import KuavoRobotStateCore
8
+
9
+ class KuavoRobotState:
10
+ def __init__(self, robot_type: str = "kuavo"):
11
+ self._rs_core = KuavoRobotStateCore()
12
+
13
+ @property
14
+ def imu_data(self) -> KuavoImuData:
15
+ """Get Robot IMU Data.
16
+
17
+ Gets the current IMU sensor data from the robot, including gyroscope, accelerometer,
18
+ free acceleration and orientation quaternion measurements.
19
+
20
+ Returns:
21
+ :class:`KuavoImuData`: IMU data containing:
22
+ * gyro (:obj:`tuple` of :obj:`float`): Gyroscope measurements (x, y, z) in rad/s
23
+ * acc (:obj:`tuple` of :obj:`float`): Accelerometer measurements (x, y, z) in m/s^2
24
+ * free_acc (:obj:`tuple` of :obj:`float`): Free acceleration (x, y, z) in m/s^2
25
+ * quat (:obj:`tuple` of :obj:`float`): Orientation quaternion (x, y, z, w)
26
+ """
27
+ return self._rs_core.imu_data
28
+
29
+ @property
30
+ def joint_state(self) -> KuavoJointData:
31
+ """Get Robot Joint Data.
32
+
33
+ Get Robot Joint Data, including joint positions, velocities, torques and accelerations.
34
+
35
+ The data includes:
36
+ - Joint positions (angles) in radians
37
+ - Joint velocities in radians/second
38
+ - Joint torques/efforts in Newton-meters, A
39
+ - Joint acceleration
40
+
41
+ Returns:
42
+ KuavoJointData: A dictionary containing joint state data with the following keys:
43
+ position (list[float]): Joint positions, length = joint_dof(28)
44
+ velocity (list[float]): Joint velocities, length = joint_dof(28)
45
+ torque (list[float]): Joint torques, length = joint_dof(28)
46
+ acceleration (list[float]): Joint accelerations, length = joint_dof(28)
47
+ """
48
+ return self._rs_core.joint_data
49
+
50
+ @property
51
+ def com_height(self)->float:
52
+ """Get the height of the robot's center of mass.
53
+
54
+ Returns:
55
+ float: The height of the robot's center of mass in meters.
56
+ """
57
+ return self._rs_core.com_height
58
+
59
+ @property
60
+ def odometry(self) -> KuavoOdometry:
61
+ """Get Robot Odometry Data.
62
+
63
+ Gets the current odometry data from the robot, including position, orientation,
64
+ linear velocity and angular velocity measurements.
65
+
66
+ Returns:
67
+ KuavoOdometry: A dictionary containing odometry data with the following keys:
68
+ position (tuple): Position (x, y, z) in meters
69
+ orientation (tuple): Orientation as quaternion (x, y, z, w)
70
+ linear (tuple): Linear velocity (x, y, z) in m/s
71
+ angular (tuple): Angular velocity (x, y, z) in rad/s
72
+ """
73
+ return self._rs_core.odom_data
74
+
75
+
76
+ def robot_position(self) -> Tuple[float, float, float]:
77
+ """Returns the robot's position in world coordinates.
78
+
79
+ Returns:
80
+ Tuple[float, float, float]: Position (x, y, z) in meters.
81
+ """
82
+ return self._rs_core.odom_data.position
83
+
84
+ def robot_orientation(self) -> Tuple[float, float, float, float]:
85
+ """Returns the robot's orientation in world coordinates.
86
+
87
+ Returns:
88
+ Tuple[float, float, float, float]: Orientation as quaternion (x, y, z, w).
89
+ """
90
+ return self._rs_core.odom_data.orientation
91
+
92
+ def linear_velocity(self) -> Tuple[float, float, float]:
93
+ """Returns the robot's linear velocity in world coordinates.
94
+
95
+ Returns:
96
+ Tuple[float, float, float]: Linear velocity (x, y, z) in m/s.
97
+ """
98
+ return self._rs_core.odom_data.linear
99
+
100
+
101
+ def angular_velocity(self) -> Tuple[float, float, float]:
102
+ """Returns the robot's angular velocity in world coordinates.
103
+
104
+ Returns:
105
+ Tuple[float, float, float]: Angular velocity (x, y, z).
106
+ """
107
+ return self._rs_core.odom_data.angular
108
+
109
+ def arm_joint_state(self) -> KuavoJointData:
110
+ """Get the current state of the robot arm joints.
111
+
112
+ Get the current state of the robot arm joints, including:
113
+ - Joint positions (angles) in radians
114
+ - Joint velocities in radians/second
115
+ - Joint torques/efforts in Newton-meters, A
116
+ - Joint acceleration
117
+
118
+ Returns:
119
+ KuavoJointData: Arm joint data containing:
120
+ position: list[float] * arm_dof(14)
121
+ velocity: list[float] * arm_dof(14)
122
+ torque: list[float] * arm_dof(14)
123
+ acceleration: list[float] * arm_dof(14)
124
+ """
125
+ # Get arm joint states from index 12 to 25 (14 arm joints)
126
+ arm_joint_indices = range(12, 12+14)
127
+ return KuavoJointData(
128
+ position=[self._rs_core.joint_data.position[i] for i in arm_joint_indices],
129
+ velocity=[self._rs_core.joint_data.velocity[i] for i in arm_joint_indices],
130
+ torque=[self._rs_core.joint_data.torque[i] for i in arm_joint_indices],
131
+ acceleration=[self._rs_core.joint_data.acceleration[i] for i in arm_joint_indices]
132
+ )
133
+
134
+ def arm_control_mode(self) -> KuavoArmCtrlMode:
135
+ """Get the current control mode of the robot arm.
136
+
137
+ Returns:
138
+ KuavoArmCtrlMode: Current arm control mode:
139
+ ArmFixed: 0 - The robot arm is in a fixed position.
140
+ AutoSwing: 1 - The robot arm is in automatic swing mode.
141
+ ExternalControl: 2 - The robot arm is controlled externally.
142
+ or None.
143
+ """
144
+ return self._rs_core.arm_control_mode
145
+
146
+ def head_joint_state(self) -> KuavoJointData:
147
+ """Get the current state of the robot head joints.
148
+
149
+ Gets the current state data for the robot's head joints, including position,
150
+ velocity, torque and acceleration values.
151
+
152
+ Returns:
153
+ KuavoJointData: A data structure containing the head joint states:
154
+ position (list[float]): Joint positions in radians, length=head_dof(2)
155
+ velocity (list[float]): Joint velocities in rad/s, length=head_dof(2)
156
+ torque (list[float]): Joint torques in Nm, length=head_dof(2)
157
+ acceleration (list[float]): Joint accelerations in rad/s^2, length=head_dof(2)
158
+
159
+ The joint order is [yaw, pitch].
160
+ """
161
+ # Get head joint states from last 2 indices
162
+ head_joint_indices = range(len(self._rs_core.joint_data.position)-2, len(self._rs_core.joint_data.position))
163
+ return KuavoJointData(
164
+ position=[self._rs_core.joint_data.position[i] for i in head_joint_indices],
165
+ velocity=[self._rs_core.joint_data.velocity[i] for i in head_joint_indices],
166
+ torque=[self._rs_core.joint_data.torque[i] for i in head_joint_indices],
167
+ acceleration=[self._rs_core.joint_data.acceleration[i] for i in head_joint_indices]
168
+ )
169
+
170
+ def eef_state(self)->Tuple[EndEffectorState, EndEffectorState]:
171
+ """Get the current state of the robot's end effectors.
172
+
173
+ Returns:
174
+ Tuple[EndEffectorState, EndEffectorState]: A tuple containing the state of the left and right end effectors.
175
+ Each EndEffectorState contains:
176
+ - position: (float, float, float) - XYZ position in meters
177
+ - orientation: (float, float, float, float) - Quaternion orientation
178
+ - state: EndEffectorState.GraspingState - Current grasping state (UNKNOWN, OPEN, CLOSED)
179
+ """
180
+ return self._rs_core.eef_state
181
+
182
+ def gait_name(self)->str:
183
+ """Get the current gait name of the robot.
184
+
185
+ Returns:
186
+ str: The name of the current gait, e.g. 'trot', 'walk', 'stance', 'custom_gait'.
187
+ """
188
+ return self._rs_core.gait_name()
189
+
190
+
191
+ def is_stance(self) -> bool:
192
+ """Check if the robot is currently in stance mode.
193
+
194
+ Returns:
195
+ bool: True if robot is in stance mode, False otherwise.
196
+ """
197
+ return self._rs_core.is_gait('stance')
198
+
199
+ def is_walk(self) -> bool:
200
+ """Check if the robot is currently in walk mode.
201
+
202
+ Returns:
203
+ bool: True if robot is in walk mode, False otherwise.
204
+ """
205
+ return self._rs_core.is_gait('walk')
206
+
207
+ def is_step_control(self) -> bool:
208
+ """Check if the robot is currently in step control mode.
209
+
210
+ Returns:
211
+ bool: True if robot is in step control mode, False otherwise.
212
+ """
213
+ return self._rs_core.is_gait('custom_gait')
214
+
215
+ def wait_for_stance(self, timeout:float=5.0)->bool:
216
+ """Wait for the robot to enter stance state.
217
+
218
+ Args:
219
+ timeout (float): The maximum time to wait for the robot to enter stance state in seconds.
220
+
221
+ Returns:
222
+ bool: True if the robot enters stance state within the specified timeout, False otherwise.
223
+ """
224
+ wait_time = 0
225
+ while not self._rs_core.is_gait('stance') and wait_time < timeout:
226
+ time.sleep(0.1)
227
+ wait_time += 0.1
228
+ return self._rs_core.is_gait('stance')
229
+
230
+ def wait_for_walk(self, timeout:float=5.0)->bool:
231
+ """Wait for the robot to enter walk state.
232
+
233
+ Args:
234
+ timeout (float): The maximum time to wait for the robot to enter walk state in seconds.
235
+
236
+ Returns:
237
+ bool: True if the robot enters walk state within the specified timeout, False otherwise.
238
+ """
239
+ wait_time = 0
240
+ while not self._rs_core.is_gait('walk') and wait_time < timeout:
241
+ time.sleep(0.1)
242
+ wait_time += 0.1
243
+ return self._rs_core.is_gait('walk')
244
+
245
+ def wait_for_step_control(self, timeout:float=5.0)->bool:
246
+ """Wait for the robot to enter step control state.
247
+
248
+ Args:
249
+ timeout (float): The maximum time to wait for the robot to enter step control state in seconds.
250
+
251
+ Returns:
252
+ bool: True if the robot enters step control state within the specified timeout, False otherwise.
253
+ """
254
+ wait_time = 0
255
+ while not self._rs_core.is_gait('custom_gait') and wait_time < timeout:
256
+ time.sleep(0.1)
257
+ wait_time += 0.1
258
+ return self._rs_core.is_gait('custom_gait')
@@ -0,0 +1,217 @@
1
+ Metadata-Version: 2.1
2
+ Name: kuavo-humanoid-sdk
3
+ Version: 0.1.0
4
+ Summary: A Python SDK for kuavo humanoid robot.
5
+ Home-page: https://gitee.com/leju-robot/kuavo-ros-opensource/
6
+ Author: ['lejurobot']
7
+ Author-email: ['edu@lejurobot.com']
8
+ License: MIT
9
+ Project-URL: Documentation, https://gitee.com/leju-robot/kuavo-ros-opensource/
10
+ Project-URL: Source Code, https://gitee.com/leju-robot/kuavo-ros-opensource/
11
+ Keywords: kuavo,humanoid,robot,robotics,lejurobot,ros
12
+ Platform: UNKNOWN
13
+ Classifier: Development Status :: 4 - Beta
14
+ Classifier: Intended Audience :: Developers
15
+ Classifier: License :: OSI Approved :: MIT License
16
+ Classifier: Operating System :: POSIX :: Linux
17
+ Classifier: Programming Language :: Python :: 3
18
+ Classifier: Programming Language :: Python :: 3.8
19
+ Classifier: Programming Language :: Python :: 3.9
20
+ Classifier: Programming Language :: Python :: 3.10
21
+ Classifier: Topic :: Software Development :: Libraries :: Python Modules
22
+ Requires-Python: >=3.8
23
+ Description-Content-Type: text/markdown
24
+ Requires-Dist: numpy
25
+ Requires-Dist: transitions
26
+
27
+ # Kuavo Humanoid SDK
28
+
29
+ A comprehensive Python SDK for controlling Kuavo humanoid robots. This SDK provides interfaces for robot state management, arm and head control, and end-effector operations. It is designed to work with ROS (Robot Operating System) environments.
30
+
31
+ **Warning**: This SDK currently only supports **ROS1**. ROS2 support is not available.
32
+
33
+ ![Kuavo 4Pro Robot](https://kuavo.lejurobot.com/manual/assets/images/kuavo_4pro-cf84d43f1c370666c6e810d2807ae3e4.png)
34
+
35
+ ## Features
36
+
37
+ - Robot State Management
38
+ - IMU data (acceleration, angular velocity, euler angles)
39
+ - Joint/motor states (position, velocity, torque)
40
+ - Torso state (position, orientation, velocity)
41
+ - Odometry information
42
+ - End-effector states:
43
+ - Gripper: position, velocity, torque, grasp status
44
+ - Dexterous hand: position, velocity, torque
45
+ - End-effector position and orientation
46
+ - Motion states: stand, walk, step_control, trot
47
+
48
+ - Motion Control
49
+ - Arm Control
50
+ - Joint position control
51
+ - End-effector 6D control via inverse kinematics
52
+ - Forward kinematics (FK) for computing end-effector pose
53
+ - Keyframe sequence control for complex motions
54
+ - End-effector Control
55
+ - Gripper control (position control with configurable velocity and torque)
56
+ - Dexterous hand control
57
+ - Position control
58
+ - Pre-defined hand gestures (OK, 666, fist, etc.)
59
+ - Head Control
60
+ - Position control
61
+ - Torso Control
62
+ - Height control (squatting)
63
+ - Forward/backward tilt control
64
+ - Dynamic Motion Control
65
+ - Stance
66
+ - Trot
67
+ - Walking (xy and yaw velocity control)
68
+ - Stepping (gait switching)
69
+
70
+ - Robot Basic Information
71
+ - Robot type (kuavo)
72
+ - Robot version
73
+ - End-effector type
74
+ - Joint names
75
+ - Total degrees of freedom (28)
76
+ - Arm degrees of freedom (7 per arm)
77
+ - Head degrees of freedom (2)
78
+ - Leg degrees of freedom (12)
79
+
80
+ ## Installation
81
+
82
+ To install Kuavo Humanoid SDK, you can use pip:
83
+ ```bash
84
+ pip install kuavo-humanoid-sdk
85
+ ```
86
+
87
+ For development installation (editable mode), use:
88
+ ```bash
89
+ pip install -e .
90
+ ```
91
+
92
+ ## Package Information
93
+
94
+ You can check the package information using pip:
95
+ ```bash
96
+ pip show kuavo-humanoid-sdk
97
+ ```
98
+
99
+ ## Quick Start
100
+
101
+ Here's a simple example to get started with Kuavo Humanoid SDK:
102
+
103
+ > **Warning**: Before running any code, make sure to start the robot first by executing either:
104
+ > - For simulation: `roslaunch humanoid_controllers load_kuavo_mujoco_sim.launch` (Example command)
105
+ > - For real robot: `roslaunch humanoid_controllers load_kuavo_real.launch` (Example command)
106
+ ```python3
107
+ # Copyright (c) 2025 Leju Robotics. Licensed under the MIT License.
108
+ import time
109
+ from kuavo_humanoid_sdk import KuavoSDK, KuavoRobot
110
+
111
+ def main():
112
+ if not KuavoSDK().Init(): # Init! !!! IMPORTANT !!!
113
+ print("Init KuavoSDK failed, exit!")
114
+ exit(1)
115
+ robot = KuavoRobot()
116
+
117
+ """ arm reset """
118
+ print("Switching to arm reset mode...")
119
+ robot.arm_reset()
120
+
121
+ """ stance """
122
+ print("Switching to stance mode...")
123
+ robot.stance()
124
+
125
+ """ trot """
126
+ print("Switching to trot mode...")
127
+ robot.trot()
128
+
129
+ """ walk forward """
130
+ print("Starting forward walk...")
131
+ duration = 4.0 # seconds
132
+ speed = 0.3 # m/s
133
+ start_time = time.time()
134
+ while (time.time() - start_time < duration):
135
+ robot.walk(linear_x=speed, linear_y=0.0, angular_z=0.0)
136
+ time.sleep(0.1) # Small sleep to prevent busy loop
137
+
138
+ if __name__ == "__main__":
139
+ main()
140
+ ```
141
+
142
+ ## Examples
143
+
144
+ #### WARNING
145
+ Before running any code examples, make sure to start the robot first by executing either:
146
+
147
+ - For simulation: `roslaunch humanoid_controllers load_kuavo_mujoco_sim.launch` (Example command)
148
+ - For real robot: `roslaunch humanoid_controllers load_kuavo_real.launch` (Example command)
149
+
150
+ ### Robot Info
151
+
152
+ Examples showing how to get basic robot information.
153
+
154
+ [https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/robot_info_example.py](https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/robot_info_example.py)
155
+
156
+ ### Basic Robot Control
157
+
158
+ A basic example showing how to initialize the SDK and control the robot’s movement.
159
+
160
+ [https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/motion_example.py](https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/motion_example.py)
161
+
162
+ ### End Effector Control
163
+
164
+ #### LejuClaw Gripper
165
+
166
+ Examples demonstrating how to control the LejuClaw gripper end effector, including position, velocity and torque control.
167
+
168
+ [https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/lejuclaw_example.py](https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/lejuclaw_example.py)
169
+
170
+ #### QiangNao DexHand
171
+
172
+ Examples showing how to control the QiangNao DexHand, a dexterous robotic hand with multiple degrees of freedom for complex manipulation tasks.
173
+
174
+ [https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/dexhand_example.py](https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/dexhand_example.py)
175
+
176
+ ### Arm Control
177
+
178
+ Examples showing arm trajectory control and target pose control.
179
+
180
+ [https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/ctrl_arm_example.py](https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/ctrl_arm_example.py)
181
+
182
+ ### Forward and Inverse Kinematics
183
+
184
+ Examples demonstrating how to use forward kinematics (FK) to compute end-effector positions from joint angles, and inverse kinematics (IK) to calculate joint angles needed to achieve desired end-effector poses.
185
+
186
+ [https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/arm_ik_example.py](https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/arm_ik_example.py)
187
+
188
+ ### Head Control
189
+
190
+ Examples showing how to control the robot’s head movements, including nodding (pitch) and shaking (yaw) motions.
191
+
192
+ [https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/ctrl_head_example.py](https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/ctrl_head_example.py)
193
+
194
+ ### Step-by-Step Control
195
+
196
+ Examples showing how to control the robot’s movements step by step, including individual foot placement and trajectory control.
197
+
198
+ [https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/step_control_example.py](https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/examples/step_control_example.py)
199
+
200
+
201
+ ## Docs
202
+
203
+ https://gitee.com/leju-robot/kuavo-ros-opensource/tree/master/src/kuavo_humanoid_sdk/docs/markdown/index.md
204
+
205
+ ## License
206
+
207
+ This project is licensed under the MIT License - see the LICENSE file for details.
208
+
209
+ ## Contact & Support
210
+
211
+ For any questions, support, or bug reports, please contact:
212
+ - Email: edu@lejurobot.com
213
+ - Website: https://gitee.com/leju-robot/kuavo-ros-opensource/
214
+ - Source Code: https://gitee.com/leju-robot/kuavo-ros-opensource/
215
+ - Issue Tracker: https://gitee.com/leju-robot/kuavo-ros-opensource/issues
216
+
217
+
@@ -0,0 +1,27 @@
1
+ kuavo_humanoid_sdk/__init__.py,sha256=alEgqxypKm-gg2CSlhoHK5P3Crg1f8NEI74bbX37uDI,122
2
+ kuavo_humanoid_sdk/common/logger.py,sha256=nSIbsJaW4nDcaQdhZebZkjtji6kmWVR8tYO-sUTz3Gg,1246
3
+ kuavo_humanoid_sdk/interfaces/__init__.py,sha256=_zXDinj2T3X7UH19-Xrotc7uYZWHmZqHaMCWU1FYR5I,100
4
+ kuavo_humanoid_sdk/interfaces/data_types.py,sha256=fQ_9ZPL8KFsFExDnfRI3II_qy7-WgcNYudywA7iLCAQ,4266
5
+ kuavo_humanoid_sdk/interfaces/end_effector.py,sha256=gOnbZudoFHL2ZZjfcbteqcFVhF-T6khtEpoF6PjVffo,1244
6
+ kuavo_humanoid_sdk/interfaces/robot.py,sha256=qqnq7gRc_mK8xEWnF5pJ7AJUPtry1bpN9eDl8nmE3EM,393
7
+ kuavo_humanoid_sdk/interfaces/robot_info.py,sha256=-rh7VXjMJFYTsx7Ktok5VuI6JF_W2BpJBUbqtYJRkkA,1176
8
+ kuavo_humanoid_sdk/kuavo/__init__.py,sha256=s4UZkSKP22K1712vLR96dBiXgOAaWd88bCr-WAKNuus,271
9
+ kuavo_humanoid_sdk/kuavo/dexterous_hand.py,sha256=tHqpKH5Bti4qcI4U_AnAGg9s7qSAVHMwDvsPOzUwt0I,8026
10
+ kuavo_humanoid_sdk/kuavo/leju_claw.py,sha256=HqTg3Q4NO9icwv7MJzLFxTADLJAjrD92Z3AQULJ5Epo,9624
11
+ kuavo_humanoid_sdk/kuavo/robot.py,sha256=Xou9Zi5j8HyiClXzEXbNBgBc1QZf8Q5EKW17D37Cj2Y,13132
12
+ kuavo_humanoid_sdk/kuavo/robot_arm.py,sha256=M7u_cwBLF7TKCbU85rGKMHAu3E3WKvUCsvadVtBMkVw,6690
13
+ kuavo_humanoid_sdk/kuavo/robot_head.py,sha256=8caHrPNwg98b4jf5cLJUbsGNovgtXetOqBvuG5vWSXA,1526
14
+ kuavo_humanoid_sdk/kuavo/robot_info.py,sha256=XcrShWG0yG2kuuVbiM0RW8Frh-M9dcFASlSuwJX_pVo,3850
15
+ kuavo_humanoid_sdk/kuavo/robot_state.py,sha256=dE2bqdYdev_pQyAAgpU9vS_69brF92EmqQxYJzP7grw,10470
16
+ kuavo_humanoid_sdk/kuavo/core/core.py,sha256=QHneyt7UqX73XqrC0mCmRnMtCEOtrl9kjJPjUT6gKyU,17668
17
+ kuavo_humanoid_sdk/kuavo/core/dex_hand_control.py,sha256=pJr50Nxx1OGJa7D5pg1w6BkX3_k8a3Ot70N-OAJ-Mlw,3665
18
+ kuavo_humanoid_sdk/kuavo/core/leju_claw_control.py,sha256=RCrnWTMW-L0fOMa1op7t43aGWSyMVqrOjR0lVtIFzqY,3432
19
+ kuavo_humanoid_sdk/kuavo/core/ros_env.py,sha256=P0tiURlwxhW_WUrPUmz_bigTTFm0XuQqjQsh2hK8FMs,7871
20
+ kuavo_humanoid_sdk/kuavo/core/ros/control.py,sha256=8DKfxqKFWy3zRSTWYPWyiJWsq6NIA8Oa3yWY95qWrwg,31996
21
+ kuavo_humanoid_sdk/kuavo/core/ros/param.py,sha256=H-Kvy5QokHuYB3vCplwd6IFuVFK4lJV0KuYErVV5Qcs,6625
22
+ kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py,sha256=AhBNM-s9nVwRiLZ8gtqC2RvPImkT9uulONSLXk3KooI,3317
23
+ kuavo_humanoid_sdk/kuavo/core/ros/state.py,sha256=ZmP8Ku18nTzCSO-VNWXdr9BKVN0IS-8N6xeHjNEMNHw,13776
24
+ kuavo_humanoid_sdk-0.1.0.dist-info/METADATA,sha256=0LYI0m07z70-zRKb_sMsZu_Mytyjrejiso2IZ2pIrQY,8336
25
+ kuavo_humanoid_sdk-0.1.0.dist-info/WHEEL,sha256=bFJAMchF8aTQGUgMZzHJyDDMPTO3ToJ7x23SLJa1SVo,92
26
+ kuavo_humanoid_sdk-0.1.0.dist-info/top_level.txt,sha256=9uSyZoiOEykRMOf0Gm-N9mkyQQg9yOSimfsb632G99c,19
27
+ kuavo_humanoid_sdk-0.1.0.dist-info/RECORD,,
@@ -0,0 +1,5 @@
1
+ Wheel-Version: 1.0
2
+ Generator: bdist_wheel (0.45.0)
3
+ Root-Is-Purelib: true
4
+ Tag: py3-none-any
5
+
@@ -0,0 +1 @@
1
+ kuavo_humanoid_sdk