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,309 @@
1
+ #!/usr/bin/env python3
2
+ # coding: utf-8
3
+ from kuavo_humanoid_sdk.kuavo.core.ros_env import KuavoROSEnv
4
+ kuavo_ros_env = KuavoROSEnv()
5
+ if not kuavo_ros_env.Init():
6
+ raise RuntimeError("Failed to initialize ROS environment")
7
+ else:
8
+ import time
9
+ from typing import Tuple
10
+ from kuavo_humanoid_sdk.kuavo.robot_info import KuavoRobotInfo
11
+ from kuavo_humanoid_sdk.kuavo.robot_arm import KuavoRobotArm
12
+ from kuavo_humanoid_sdk.kuavo.robot_head import KuavoRobotHead
13
+ from kuavo_humanoid_sdk.kuavo.core.core import KuavoRobotCore
14
+ from kuavo_humanoid_sdk.interfaces.robot import RobotBase
15
+ from kuavo_humanoid_sdk.interfaces.data_types import KuavoPose, KuavoIKParams
16
+ from kuavo_humanoid_sdk.common.logger import SDKLogger, disable_sdk_logging
17
+ """
18
+ Kuavo SDK - Python Interface for Kuavo Robot Control
19
+
20
+ This module provides the main interface for controlling Kuavo robots through Python.
21
+ It includes two main classes:
22
+
23
+ KuavoSDK:
24
+ A static class providing SDK initialization and configuration functionality.
25
+ Handles core setup, ROS environment initialization, and logging configuration.
26
+
27
+ KuavoRobot:
28
+ The main robot control interface class that provides access to:
29
+ - Robot information and status (via KuavoRobotInfo)
30
+ - Arm control capabilities (via KuavoRobotArm)
31
+ - Head control capabilities (via KuavoRobotHead)
32
+ - Core robot functions (via KuavoRobotCore)
33
+
34
+ The module requires a properly configured ROS environment to function.
35
+ """
36
+ __all__ = ["KuavoSDK", "KuavoRobot"]
37
+
38
+ class KuavoSDK:
39
+ def __init__(self):
40
+ pass
41
+
42
+ @staticmethod
43
+ def Init(log_level: str = "INFO")-> bool:
44
+ """Initialize the SDK.
45
+
46
+ Args:
47
+ log_level (str): The logging level to use. Can be "ERROR", "WARN", "INFO", "DEBUG".
48
+ Defaults to "INFO".
49
+
50
+ Returns:
51
+ bool: True if initialization is successful, False otherwise.
52
+
53
+ Raises:
54
+ RuntimeError: If the initialization fails.
55
+ """
56
+ SDKLogger.setLevel(log_level.upper())
57
+ # Initialize core components, connect ROS Topics...
58
+ kuavo_core = KuavoRobotCore()
59
+ if log_level.upper() == 'DEBUG':
60
+ debug = True
61
+ else:
62
+ debug = False
63
+ if not kuavo_core.initialize(debug=debug):
64
+ SDKLogger.error("[SDK] Failed to initialize core components.")
65
+ return False
66
+
67
+ return True
68
+
69
+ @staticmethod
70
+ def DisableLogging():
71
+ """Disable all logging output from the SDK."""
72
+ disable_sdk_logging()
73
+
74
+ class KuavoRobot(RobotBase):
75
+ def __init__(self):
76
+ super().__init__(robot_type="kuavo")
77
+ self._robot_info = KuavoRobotInfo()
78
+ self._robot_arm = KuavoRobotArm()
79
+ self._robot_head = KuavoRobotHead()
80
+ self._kuavo_core = KuavoRobotCore()
81
+
82
+ def stance(self)->bool:
83
+ """Put the robot into 'stance' mode.
84
+
85
+ Returns:
86
+ bool: True if the robot is put into stance mode successfully, False otherwise.
87
+
88
+ Note:
89
+ You can call KuavoRobotState.wait_for_stance() to wait until the robot enters stance mode.
90
+ """
91
+ return self._kuavo_core.to_stance()
92
+
93
+ def trot(self)->bool:
94
+ """Put the robot into 'trot' mode.
95
+
96
+ Returns:
97
+ bool: True if the robot is put into trot mode successfully, False otherwise.
98
+
99
+ Note:
100
+ You can call KuavoRobotState.wait_for_walk() to wait until the robot enters trot mode.
101
+ """
102
+ return self._kuavo_core.to_trot()
103
+
104
+ def walk(self, linear_x:float, linear_y:float, angular_z:float)->bool:
105
+ """Control the robot's motion.
106
+
107
+ Args:
108
+ linear_x (float): The linear velocity along the x-axis in m/s, range [-0.4, 0.4].
109
+ linear_y (float): The linear velocity along the y-axis in m/s, range [-0.2, 0.2].
110
+ angular_z (float): The angular velocity around the z-axis in rad/s, range [-0.4, 0.4].
111
+
112
+ Returns:
113
+ bool: True if the motion is controlled successfully, False otherwise.
114
+
115
+ Note:
116
+ You can call KuavoRobotState.wait_for_walk() to wait until the robot enters walk mode.
117
+ """
118
+ # Limit velocity ranges
119
+ limited_linear_x = min(0.4, max(-0.4, linear_x))
120
+ limited_linear_y = min(0.2, max(-0.2, linear_y))
121
+ limited_angular_z = min(0.4, max(-0.4, angular_z))
122
+
123
+ # Check if any velocity exceeds limits.
124
+ if abs(linear_x) > 0.4:
125
+ SDKLogger.warn(f"[Robot] linear_x velocity {linear_x} exceeds limit [-0.4, 0.4], will be limited")
126
+ if abs(linear_y) > 0.2:
127
+ SDKLogger.warn(f"[Robot] linear_y velocity {linear_y} exceeds limit [-0.2, 0.2], will be limited")
128
+ if abs(angular_z) > 0.4:
129
+ SDKLogger.warn(f"[Robot] angular_z velocity {angular_z} exceeds limit [-0.4, 0.4], will be limited")
130
+ return self._kuavo_core.walk(limited_linear_x, limited_linear_y, limited_angular_z)
131
+
132
+ def jump(self):
133
+ """Jump the robot."""
134
+ pass
135
+
136
+ def squat(self, height: float, pitch: float=0.0)->bool:
137
+ """Control the robot's squat height and pitch.
138
+ Args:
139
+ height (float): The height offset from normal standing height in meters, range [-0.3, 0.0],Negative values indicate squatting down.
140
+ pitch (float): The pitch angle of the robot's torso in radians, range [-0.4, 0.4].
141
+
142
+ Returns:
143
+ bool: True if the squat is controlled successfully, False otherwise.
144
+ """
145
+ # Limit height range
146
+ limited_height = min(0.0, max(-0.3, height))
147
+
148
+ # Check if height exceeds limits
149
+ if height > 0.0 or height < -0.3:
150
+ SDKLogger.warn(f"[Robot] height {height} exceeds limit [-0.3, 0.0], will be limited")
151
+ # Limit pitch range
152
+ limited_pitch = min(0.4, max(-0.4, pitch))
153
+
154
+ # Check if pitch exceeds limits
155
+ if abs(pitch) > 0.4:
156
+ SDKLogger.warn(f"[Robot] pitch {pitch} exceeds limit [-0.4, 0.4], will be limited")
157
+
158
+ return self._kuavo_core.squat(limited_height, limited_pitch)
159
+
160
+ def step_by_step(self, target_pose:list, dt:float=0.4, is_left_first_default:bool=True, collision_check:bool=True)->bool:
161
+ """Control the robot's motion by step.
162
+
163
+ Args:
164
+ target_pose (list): The target position of the robot in [x, y, z, yaw] m, rad.
165
+ dt (float): The time interval between each step in seconds. Defaults to 0.4s.
166
+ is_left_first_default (bool): Whether to start with the left foot. Defaults to True.
167
+ collision_check (bool): Whether to check for collisions. Defaults to True.
168
+
169
+ Returns:
170
+ bool: True if motion is successful, False otherwise.
171
+
172
+ Raises:
173
+ RuntimeError: If the robot is not in stance state when trying to control step motion.
174
+ ValueError: If target_pose length is not 4.
175
+ """
176
+ if len(target_pose) != 4:
177
+ raise ValueError(f"[Robot] target_pose length must be 4 (x, y, z, yaw), but got {len(target_pose)}")
178
+
179
+ return self._kuavo_core.step_control(target_pose, dt, is_left_first_default, collision_check)
180
+
181
+ def control_head(self, yaw: float, pitch: float)->bool:
182
+ """Control the head of the robot.
183
+
184
+ Args:
185
+ yaw (float): The yaw angle of the head in radians, range [-1.396, 1.396] (-80 to 80 degrees).
186
+ pitch (float): The pitch angle of the head in radians, range [-0.436, 0.436] (-25 to 25 degrees).
187
+
188
+ Returns:
189
+ bool: True if the head is controlled successfully, False otherwise.
190
+ """
191
+ return self._robot_head.control_head(yaw=yaw, pitch=pitch)
192
+
193
+ """ Robot Arm Control """
194
+ def arm_reset(self)->bool:
195
+ """Reset the robot arm.
196
+
197
+ Returns:
198
+ bool: True if the arm is reset successfully, False otherwise.
199
+ """
200
+ return self._robot_arm.arm_reset()
201
+
202
+ def control_arm_position(self, joint_positions:list)->bool:
203
+ """Control the position of the arm.
204
+
205
+ Args:
206
+ joint_positions (list): The target position of the arm in radians.
207
+
208
+ Returns:
209
+ bool: True if the arm is controlled successfully, False otherwise.
210
+
211
+ Raises:
212
+ ValueError: If the joint position list is not of the correct length.
213
+ ValueError: If the joint position is outside the range of [-π, π].
214
+ RuntimeError: If the robot is not in stance state when trying to control the arm.
215
+ """
216
+ if len(joint_positions) != self._robot_info.arm_joint_dof:
217
+ print("The length of the position list must be equal to the number of DOFs of the arm.")
218
+ return False
219
+
220
+ return self._robot_arm.control_arm_position(joint_positions)
221
+
222
+ def control_arm_target_poses(self, times:list, q_frames:list)->bool:
223
+ """Control the target poses of the robot arm.
224
+
225
+ Args:
226
+ times (list): List of time intervals in seconds.
227
+ q_frames (list): List of joint positions in radians.
228
+
229
+ Returns:
230
+ bool: True if the control was successful, False otherwise.
231
+
232
+ Raises:
233
+ ValueError: If the times list is not of the correct length.
234
+ ValueError: If the joint position list is not of the correct length.
235
+ ValueError: If the joint position is outside the range of [-π, π].
236
+ RuntimeError: If the robot is not in stance state when trying to control the arm.
237
+
238
+ Note:
239
+ This is an asynchronous interface. The function returns immediately after sending the command.
240
+ Users need to wait for the motion to complete on their own.
241
+ """
242
+ return self._robot_arm.control_arm_target_poses(times, q_frames)
243
+
244
+ def set_fixed_arm_mode(self) -> bool:
245
+ """Freezes the robot arm.
246
+
247
+ Returns:
248
+ bool: True if the arm is frozen successfully, False otherwise.
249
+ """
250
+ return self._robot_arm.set_fixed_arm_mode()
251
+
252
+ def set_auto_swing_arm_mode(self) -> bool:
253
+ """Swing the robot arm.
254
+
255
+ Returns:
256
+ bool: True if the arm is swinging successfully, False otherwise.
257
+ """
258
+ return self._robot_arm.set_auto_swing_arm_mode()
259
+
260
+ def set_external_control_arm_mode(self) -> bool:
261
+ """External control the robot arm.
262
+
263
+ Returns:
264
+ bool: True if the arm is external controlled successfully, False otherwise.
265
+ """
266
+ return self._robot_arm.set_external_control_arm_mode()
267
+
268
+ """ Arm Forward kinematics && Arm Inverse kinematics """
269
+ def arm_ik(self,
270
+ left_pose: KuavoPose,
271
+ right_pose: KuavoPose,
272
+ left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
273
+ right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
274
+ arm_q0: list = None,
275
+ params: KuavoIKParams=None) -> list:
276
+ """Inverse kinematics for the robot arm.
277
+
278
+ Args:
279
+ left_pose (KuavoPose): Pose of the robot left arm, xyz and quat.
280
+ right_pose (KuavoPose): Pose of the robot right arm, xyz and quat.
281
+ left_elbow_pos_xyz (list): Position of the robot left elbow. If [0.0, 0.0, 0.0], will be ignored.
282
+ right_elbow_pos_xyz (list): Position of the robot right elbow. If [0.0, 0.0, 0.0], will be ignored.
283
+ arm_q0 (list, optional): Initial joint positions in radians. If None, will be ignored.
284
+ params (KuavoIKParams, optional): Parameters for the inverse kinematics. If None, will be ignored.
285
+ Contains:
286
+ - major_optimality_tol: Major optimality tolerance
287
+ - major_feasibility_tol: Major feasibility tolerance
288
+ - minor_feasibility_tol: Minor feasibility tolerance
289
+ - major_iterations_limit: Major iterations limit
290
+ - oritation_constraint_tol: Orientation constraint tolerance
291
+ - pos_constraint_tol: Position constraint tolerance, works when pos_cost_weight==0.0
292
+ - pos_cost_weight: Position cost weight. Set to 0.0 for high accuracy
293
+
294
+ Returns:
295
+ list: List of joint positions in radians, or None if inverse kinematics failed.
296
+ """
297
+ return self._robot_arm.arm_ik(left_pose, right_pose, left_elbow_pos_xyz, right_elbow_pos_xyz, arm_q0, params)
298
+
299
+ def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
300
+ """Forward kinematics for the robot arm.
301
+
302
+ Args:
303
+ q (list): List of joint positions in radians.
304
+
305
+ Returns:
306
+ Tuple[KuavoPose, KuavoPose]: Tuple of poses for the robot left arm and right arm,
307
+ or (None, None) if forward kinematics failed.
308
+ """
309
+ return self._robot_arm.arm_fk(q)
@@ -0,0 +1,140 @@
1
+ #!/usr/bin/env python3
2
+ # coding: utf-8
3
+
4
+ import math
5
+ from typing import Tuple
6
+ from kuavo_humanoid_sdk.interfaces.data_types import KuavoArmCtrlMode, KuavoIKParams, KuavoPose
7
+ from kuavo_humanoid_sdk.kuavo.core.core import KuavoRobotCore
8
+ from kuavo_humanoid_sdk.kuavo.robot_info import KuavoRobotInfo
9
+
10
+ class KuavoRobotArm:
11
+ def __init__(self):
12
+ self._kuavo_core = KuavoRobotCore()
13
+ self._robot_info = KuavoRobotInfo(robot_type="kuavo")
14
+
15
+ def arm_reset(self)-> bool:
16
+ return self._kuavo_core.robot_arm_reset()
17
+
18
+ def control_arm_position(self, joint_position:list)->bool:
19
+ """
20
+ Control the position of the robot arm joint.
21
+ Args:
22
+ joint_position (list): List of joint positions in radians
23
+ Raises:
24
+ ValueError: If the joint position list is not of the correct length.
25
+ ValueError: If the joint position is outside the range of [-π, π].
26
+ RuntimeError: If the robot is not in stance state when trying to control the arm.
27
+ Returns:
28
+ True if the control was successful, False otherwise.
29
+ """
30
+ if len(joint_position) != self._robot_info.arm_joint_dof:
31
+ raise ValueError("Invalid position length. Expected {}, got {}".format(self._robot_info.arm_joint_dof, len(joint_position)))
32
+
33
+ # Check if joint positions are within ±180 degrees (±π radians)
34
+ for pos in joint_position:
35
+ if abs(pos) > math.pi:
36
+ raise ValueError(f"Joint position {pos} rad exceeds ±π rad (±180 deg) limit")
37
+
38
+ return self._kuavo_core.control_robot_arm_traj(joint_data=joint_position)
39
+
40
+ def control_arm_target_poses(self, times:list, q_frames:list)->bool:
41
+ """
42
+ Control the target poses of the robot arm.
43
+ Args:
44
+ times (list): List of time intervals in seconds
45
+ joint_q (list): List of joint positions in radians
46
+ Raises:
47
+ ValueError: If the times list is not of the correct length.
48
+ ValueError: If the joint position list is not of the correct length.
49
+ ValueError: If the joint position is outside the range of [-π, π].
50
+ RuntimeError: If the robot is not in stance state when trying to control the arm.
51
+ Returns:
52
+ bool: True if the control was successful, False otherwise.
53
+ """
54
+ if len(times) != len(q_frames):
55
+ raise ValueError("Invalid input. times and joint_q must have thesame length.")
56
+
57
+ # Check if joint positions are within ±180 degrees (±π radians)
58
+ q_degs = []
59
+ for q in q_frames:
60
+ if any(abs(pos) > math.pi for pos in q):
61
+ raise ValueError("Joint positions must be within ±π rad (±180 deg)")
62
+ if len(q) != self._robot_info.arm_joint_dof:
63
+ raise ValueError("Invalid position length. Expected {}, got {}".format(self._robot_info.arm_joint_dof, len(q)))
64
+ # Convert joint positions from radians to degrees
65
+ q_degs.append([(p * 180.0 / math.pi) for p in q])
66
+
67
+ return self._kuavo_core.control_robot_arm_target_poses(times=times, joint_q=q_degs)
68
+
69
+ def set_fixed_arm_mode(self) -> bool:
70
+ """
71
+ Freezes the robot arm.
72
+ Returns:
73
+ bool: True if the arm is frozen successfully, False otherwise.
74
+ """
75
+ return self._kuavo_core.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ArmFixed)
76
+
77
+ def set_auto_swing_arm_mode(self) -> bool:
78
+ """
79
+ Swing the robot arm.
80
+ Returns:
81
+ bool: True if the arm is swinging successfully, False otherwise.
82
+ """
83
+ return self._kuavo_core.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.AutoSwing)
84
+
85
+ def set_external_control_arm_mode(self) -> bool:
86
+ """
87
+ External control the robot arm.
88
+ Returns:
89
+ bool: True if the arm is external controlled successfully, False otherwise.
90
+ """
91
+ return self._kuavo_core.change_robot_arm_ctrl_mode(KuavoArmCtrlMode.ExternalControl)
92
+
93
+ """ Arm Forward kinematics && Arm Inverse kinematics """
94
+ def arm_ik(self,
95
+ left_pose: KuavoPose,
96
+ right_pose: KuavoPose,
97
+ left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
98
+ right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
99
+ arm_q0: list = None,
100
+ params: KuavoIKParams=None) -> list:
101
+ """Inverse kinematics for the robot arm.
102
+
103
+ Args:
104
+ left_pose (KuavoPose): Pose of the robot left arm, xyz and quat.
105
+ right_pose (KuavoPose): Pose of the robot right arm, xyz and quat.
106
+ left_elbow_pos_xyz (list): Position of the robot left elbow. If [0.0, 0.0, 0.0], will be ignored.
107
+ right_elbow_pos_xyz (list): Position of the robot right elbow. If [0.0, 0.0, 0.0], will be ignored.
108
+ arm_q0 (list, optional): Initial joint positions in radians. If None, will be ignored.
109
+ params (KuavoIKParams, optional): Parameters for the inverse kinematics. If None, will be ignored.
110
+ Contains:
111
+ - major_optimality_tol: Major optimality tolerance
112
+ - major_feasibility_tol: Major feasibility tolerance
113
+ - minor_feasibility_tol: Minor feasibility tolerance
114
+ - major_iterations_limit: Major iterations limit
115
+ - oritation_constraint_tol: Orientation constraint tolerance
116
+ - pos_constraint_tol: Position constraint tolerance, works when pos_cost_weight==0.0
117
+ - pos_cost_weight: Position cost weight. Set to 0.0 for high accuracy
118
+
119
+ Returns:
120
+ list: List of joint positions in radians, or None if inverse kinematics failed.
121
+ """
122
+ return self._kuavo_core.arm_ik(left_pose, right_pose, left_elbow_pos_xyz, right_elbow_pos_xyz, arm_q0, params)
123
+
124
+ def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
125
+ """Forward kinematics for the robot arm.
126
+
127
+ Args:
128
+ q (list): List of joint positions in radians.
129
+
130
+ Returns:
131
+ Tuple[KuavoPose, KuavoPose]: Tuple of poses for the robot left arm and right arm,
132
+ or (None, None) if forward kinematics failed.
133
+ """
134
+ if len(q) != self._robot_info.arm_joint_dof:
135
+ raise ValueError("Invalid position length. Expected {}, got {}".format(self._robot_info.arm_joint_dof, len(q)))
136
+
137
+ result = self._kuavo_core.arm_fk(q)
138
+ if result is None:
139
+ return None, None
140
+ return result
@@ -0,0 +1,29 @@
1
+ #!/usr/bin/env python3
2
+ # coding: utf-8
3
+ import math
4
+ from kuavo_humanoid_sdk.kuavo.core.core import KuavoRobotCore
5
+ from kuavo_humanoid_sdk.common.logger import SDKLogger
6
+
7
+ class KuavoRobotHead:
8
+ def __init__(self):
9
+ self._kuavo_core = KuavoRobotCore()
10
+
11
+ def control_head(self, yaw: float, pitch: float)->bool:
12
+ """
13
+ Control the head of the robot.
14
+ Args:
15
+ yaw (float): The yaw angle of the head in radians, range [-1.396, 1.396] (-80 to 80 degrees).
16
+ pitch (float): The pitch angle of the head in radians, range [-0.436, 0.436] (-25 to 25 degrees).
17
+ Returns:
18
+ bool: True if the head is controlled successfully, False otherwise.
19
+ """
20
+ # Check yaw limits (-80 to 80 degrees)
21
+ if yaw < -math.pi*4/9 or yaw > math.pi*4/9: # -80 to 80 degrees in radians
22
+ SDKLogger.warn(f"[Robot] yaw {yaw} exceeds limit [-{math.pi*4/9:.3f}, {math.pi*4/9:.3f}] radians (-80 to 80 degrees), will be limited")
23
+ limited_yaw = min(math.pi*4/9, max(-math.pi*4/9, yaw))
24
+
25
+ # Check pitch limits (-25 to 25 degrees)
26
+ if pitch < -math.pi/7.2 or pitch > math.pi/7.2: # -25 to 25 degrees in radians
27
+ SDKLogger.warn(f"[Robot] pitch {pitch} exceeds limit [-{math.pi/7.2:.3f}, {math.pi/7.2:.3f}] radians (-25 to 25 degrees), will be limited")
28
+ limited_pitch = min(math.pi/7.2, max(-math.pi/7.2, pitch))
29
+ return self._kuavo_core.control_robot_head(yaw=limited_yaw, pitch=limited_pitch)
@@ -0,0 +1,112 @@
1
+ #!/usr/bin/env python3
2
+ # coding: utf-8
3
+ from typing import Tuple
4
+ from kuavo_humanoid_sdk.interfaces.robot_info import RobotInfoBase
5
+ from kuavo_humanoid_sdk.kuavo.core.ros.param import RosParameter, make_robot_param
6
+
7
+ class KuavoRobotInfo(RobotInfoBase):
8
+ def __init__(self, robot_type: str = "kuavo"):
9
+ super().__init__(robot_type=robot_type)
10
+
11
+ # Load robot parameters from ROS parameter server
12
+ kuavo_ros_param = make_robot_param()
13
+ self._ros_param = RosParameter()
14
+ self._robot_version = kuavo_ros_param['robot_version']
15
+ self._end_effector_type = kuavo_ros_param['end_effector_type']
16
+ self._arm_joint_dof = kuavo_ros_param['arm_dof']
17
+ self._joint_dof = kuavo_ros_param['arm_dof'] + kuavo_ros_param['leg_dof'] + kuavo_ros_param['head_dof']
18
+ self._joint_names = kuavo_ros_param['joint_names']
19
+ self._end_frames_names = kuavo_ros_param['end_frames_names']
20
+ self._head_joint_dof = kuavo_ros_param['head_dof']
21
+ self._head_joint_names = self._joint_names[-2:]
22
+ self._arm_joint_names = self._joint_names[12:self._arm_joint_dof + 12]
23
+ @property
24
+ def robot_version(self) -> str:
25
+ """Return the version of the robot.
26
+
27
+ Returns:
28
+ str: The robot version, e.g. "42", "43"...
29
+ """
30
+ return self._robot_version
31
+
32
+ @property
33
+ def end_effector_type(self) -> str:
34
+ """Return the type of the end effector.
35
+
36
+ Returns:
37
+ str: The end effector type, where:
38
+ - "qiangnao" means "dexteroushand"
39
+ - "lejuclaw" means "lejuclaw"
40
+ - ...
41
+ """
42
+ return self._end_effector_type
43
+
44
+ @property
45
+ def joint_names(self) -> list:
46
+ """Return the names of all joints in the robot.
47
+
48
+ Returns:
49
+ list: A list containing the names of all robot joints.
50
+ """
51
+ return self._joint_names
52
+
53
+ @property
54
+ def joint_dof(self) -> int:
55
+ """Return the total number of joints in the robot.
56
+
57
+ Returns:
58
+ int: Total number of joints, e.g. 28
59
+ """
60
+ return self._joint_dof
61
+
62
+ @property
63
+ def arm_joint_dof(self) -> int:
64
+ """Return the number of joints in the double-arm.
65
+
66
+ Returns:
67
+ int: Number of joints in double-arm, e.g. 14
68
+ """
69
+ return self._arm_joint_dof
70
+
71
+ @property
72
+ def arm_joint_names(self) -> list:
73
+ """Return the names of joints in the double-arm.
74
+
75
+ Returns:
76
+ list: A list containing the names of joints in the double-arm.
77
+ """
78
+ return self._arm_joint_names
79
+
80
+ @property
81
+ def head_joint_dof(self) -> int:
82
+ """Return the number of joints in the head.
83
+
84
+ Returns:
85
+ int: Number of joints in head, e.g. 2
86
+ """
87
+ return self._head_joint_dof
88
+
89
+ @property
90
+ def head_joint_names(self) -> list:
91
+ """Return the names of joints in the head.
92
+
93
+ Returns:
94
+ list: A list containing the names of joints in the head.
95
+ """
96
+ return self._head_joint_names
97
+
98
+ @property
99
+ def eef_frame_names(self) -> Tuple[str, str]:
100
+ """Returns the names of the end effector frames.
101
+
102
+ Returns:
103
+ Tuple[str, str]:
104
+ A tuple containing the end effector frame names, where:
105
+ - First element is the left hand frame name
106
+ - Second element is the right hand frame name
107
+ e.g. ("zarm_l7_link", "zarm_r7_link")
108
+ """
109
+ return self._end_frames_names[1], self._end_frames_names[2]
110
+
111
+ def __str__(self) -> str:
112
+ return f"KuavoRobotInfo(robot_type={self.robot_type}, robot_version={self.robot_version}, end_effector_type={self.end_effector_type}, joint_names={self.joint_names}, joint_dof={self.joint_dof}, arm_joint_dof={self.arm_joint_dof})"