kuavo-humanoid-sdk 0.1.0__py3-none-any.whl
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
Potentially problematic release.
This version of kuavo-humanoid-sdk might be problematic. Click here for more details.
- kuavo_humanoid_sdk/__init__.py +3 -0
- kuavo_humanoid_sdk/common/logger.py +42 -0
- kuavo_humanoid_sdk/interfaces/__init__.py +4 -0
- kuavo_humanoid_sdk/interfaces/data_types.py +122 -0
- kuavo_humanoid_sdk/interfaces/end_effector.py +43 -0
- kuavo_humanoid_sdk/interfaces/robot.py +22 -0
- kuavo_humanoid_sdk/interfaces/robot_info.py +56 -0
- kuavo_humanoid_sdk/kuavo/__init__.py +7 -0
- kuavo_humanoid_sdk/kuavo/core/core.py +388 -0
- kuavo_humanoid_sdk/kuavo/core/dex_hand_control.py +85 -0
- kuavo_humanoid_sdk/kuavo/core/leju_claw_control.py +67 -0
- kuavo_humanoid_sdk/kuavo/core/ros/control.py +758 -0
- kuavo_humanoid_sdk/kuavo/core/ros/param.py +171 -0
- kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
- kuavo_humanoid_sdk/kuavo/core/ros/state.py +325 -0
- kuavo_humanoid_sdk/kuavo/core/ros_env.py +196 -0
- kuavo_humanoid_sdk/kuavo/dexterous_hand.py +183 -0
- kuavo_humanoid_sdk/kuavo/leju_claw.py +225 -0
- kuavo_humanoid_sdk/kuavo/robot.py +309 -0
- kuavo_humanoid_sdk/kuavo/robot_arm.py +140 -0
- kuavo_humanoid_sdk/kuavo/robot_head.py +29 -0
- kuavo_humanoid_sdk/kuavo/robot_info.py +112 -0
- kuavo_humanoid_sdk/kuavo/robot_state.py +258 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/METADATA +217 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/RECORD +27 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/WHEEL +5 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/top_level.txt +1 -0
|
@@ -0,0 +1,42 @@
|
|
|
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
|
+
Path(log_dir).mkdir(parents=True, exist_ok=True)
|
|
12
|
+
except Exception as e:
|
|
13
|
+
# If creation in /var fails, create in current directory
|
|
14
|
+
log_dir = f'./{log_suffix}'
|
|
15
|
+
Path(log_dir).mkdir(parents=True, exist_ok=True)
|
|
16
|
+
log_file = f'{log_dir}/kuavo_humanoid_sdk.log'
|
|
17
|
+
|
|
18
|
+
print(f'kuavo-humanoid-sdk log_file: {log_file}')
|
|
19
|
+
|
|
20
|
+
fh = RotatingFileHandler(log_file, maxBytes=2*1024*1024, backupCount=5) # 每个日志文件最大 2 MB,保留 5 个备份文件
|
|
21
|
+
fh.setLevel(logging.DEBUG)
|
|
22
|
+
|
|
23
|
+
ch = logging.StreamHandler()
|
|
24
|
+
ch.setLevel(logging.DEBUG)
|
|
25
|
+
|
|
26
|
+
formatter = logging.Formatter('%(asctime)s - %(levelname)s - %(message)s')
|
|
27
|
+
fh.setFormatter(formatter)
|
|
28
|
+
ch.setFormatter(formatter)
|
|
29
|
+
|
|
30
|
+
logger.addHandler(fh)
|
|
31
|
+
logger.addHandler(ch)
|
|
32
|
+
return logger
|
|
33
|
+
|
|
34
|
+
def disable_sdk_logging():
|
|
35
|
+
"""
|
|
36
|
+
Disable SDK logging.
|
|
37
|
+
"""
|
|
38
|
+
logging.disable()
|
|
39
|
+
|
|
40
|
+
|
|
41
|
+
""" Logger """
|
|
42
|
+
SDKLogger = setup_logger()
|
|
@@ -0,0 +1,122 @@
|
|
|
1
|
+
from typing import Tuple
|
|
2
|
+
from enum import Enum
|
|
3
|
+
from dataclasses import dataclass
|
|
4
|
+
|
|
5
|
+
@dataclass
|
|
6
|
+
class KuavoJointData:
|
|
7
|
+
"""Data class representing joint states of the robot.
|
|
8
|
+
|
|
9
|
+
Args:
|
|
10
|
+
position (list): List of joint positions (angles) in radians
|
|
11
|
+
velocity (list): List of joint velocities in radians/second
|
|
12
|
+
torque (list): List of joint torques/efforts in Newton-meters or Amperes
|
|
13
|
+
acceleration (list): List of joint accelerations in radians/second^2
|
|
14
|
+
"""
|
|
15
|
+
position: list
|
|
16
|
+
velocity: list
|
|
17
|
+
torque: list
|
|
18
|
+
acceleration:list
|
|
19
|
+
|
|
20
|
+
@dataclass
|
|
21
|
+
class KuavoImuData:
|
|
22
|
+
"""Data class representing IMU (Inertial Measurement Unit) data from the robot.
|
|
23
|
+
|
|
24
|
+
Args:
|
|
25
|
+
gyro (Tuple[float, float, float]): Angular velocity around x, y, z axes in rad/s
|
|
26
|
+
acc (Tuple[float, float, float]): Linear acceleration in x, y, z axes in m/s^2
|
|
27
|
+
free_acc (Tuple[float, float, float]): Free acceleration (gravity compensated) in x, y, z axes in m/s^2
|
|
28
|
+
quat (Tuple[float, float, float, float]): Orientation quaternion (x, y, z, w)
|
|
29
|
+
"""
|
|
30
|
+
gyro : Tuple[float, float, float]
|
|
31
|
+
acc : Tuple[float, float, float]
|
|
32
|
+
free_acc: Tuple[float, float, float]
|
|
33
|
+
quat: Tuple[float, float, float, float]
|
|
34
|
+
|
|
35
|
+
@dataclass
|
|
36
|
+
class KuavoOdometry:
|
|
37
|
+
"""Data class representing odometry data from the robot.
|
|
38
|
+
|
|
39
|
+
Args:
|
|
40
|
+
position (Tuple[float, float, float]): Robot position (x, y, z) in world coordinates in meters
|
|
41
|
+
orientation (Tuple[float, float, float, float]): Robot orientation as quaternion (x, y, z, w)
|
|
42
|
+
linear (Tuple[float, float, float]): Linear velocity (x, y, z) in world coordinates in m/s
|
|
43
|
+
angular (Tuple[float, float, float]): Angular velocity (x, y, z) in world coordinates in rad/s
|
|
44
|
+
"""
|
|
45
|
+
position: Tuple[float, float, float]
|
|
46
|
+
orientation: Tuple[float, float, float, float]
|
|
47
|
+
linear: Tuple[float, float, float]
|
|
48
|
+
angular: Tuple[float, float, float]
|
|
49
|
+
|
|
50
|
+
class KuavoArmCtrlMode(Enum):
|
|
51
|
+
"""Enum class representing the control modes for the Kuavo robot arm.
|
|
52
|
+
|
|
53
|
+
Attributes:
|
|
54
|
+
ArmFixed: The robot arm is fixed in position (value: 0)
|
|
55
|
+
AutoSwing: The robot arm is in automatic swinging mode (value: 1)
|
|
56
|
+
ExternalControl: The robot arm is controlled by external commands (value: 2)
|
|
57
|
+
"""
|
|
58
|
+
ArmFixed = 0
|
|
59
|
+
AutoSwing = 1
|
|
60
|
+
ExternalControl = 2
|
|
61
|
+
|
|
62
|
+
|
|
63
|
+
@dataclass
|
|
64
|
+
class EndEffectorState:
|
|
65
|
+
"""Data class representing the state of the end effector.
|
|
66
|
+
|
|
67
|
+
Args:
|
|
68
|
+
position (float): Position of the end effector, [0, 100]
|
|
69
|
+
velocity (float): ...
|
|
70
|
+
effort (float): ...
|
|
71
|
+
"""
|
|
72
|
+
position: float
|
|
73
|
+
velocity: float
|
|
74
|
+
effort: float
|
|
75
|
+
class GraspingState(Enum):
|
|
76
|
+
"""Enum class representing the grasping states of the end effector.
|
|
77
|
+
|
|
78
|
+
Attributes:
|
|
79
|
+
ERROR: Error state (value: -1)
|
|
80
|
+
UNKNOWN: Unknown state (value: 0)
|
|
81
|
+
REACHED: Target position reached (value: 1)
|
|
82
|
+
MOVING: Moving to target position (value: 2)
|
|
83
|
+
GRABBED: Object successfully grasped (value: 3)
|
|
84
|
+
"""
|
|
85
|
+
ERROR = -1
|
|
86
|
+
UNKNOWN = 0
|
|
87
|
+
MOVING = 1
|
|
88
|
+
REACHED = 2
|
|
89
|
+
GRABBED = 3
|
|
90
|
+
|
|
91
|
+
state: GraspingState # gripper grasping states
|
|
92
|
+
|
|
93
|
+
class EndEffectorSide(Enum):
|
|
94
|
+
"""Enum class representing the sides of the end effector.
|
|
95
|
+
|
|
96
|
+
Attributes:
|
|
97
|
+
LEFT: The left side of the end effector (value: 'left')
|
|
98
|
+
RIGHT: The right side of the end effector (value: 'right')
|
|
99
|
+
BOTH: Both sides of the end effector (value: 'both')
|
|
100
|
+
"""
|
|
101
|
+
LEFT = 'left'
|
|
102
|
+
RIGHT = 'right'
|
|
103
|
+
BOTH = 'both'
|
|
104
|
+
|
|
105
|
+
@dataclass
|
|
106
|
+
class KuavoPose:
|
|
107
|
+
"""Data class representing the pose of the robot."""
|
|
108
|
+
position: Tuple[float, float, float] # x, y, z
|
|
109
|
+
orientation: Tuple[float, float, float, float] # x, y, z, w
|
|
110
|
+
|
|
111
|
+
@dataclass
|
|
112
|
+
class KuavoIKParams:
|
|
113
|
+
"""Data class representing the parameters for the IK node."""
|
|
114
|
+
# snopt params
|
|
115
|
+
major_optimality_tol: float = 1e-3
|
|
116
|
+
major_feasibility_tol: float = 1e-3
|
|
117
|
+
minor_feasibility_tol: float = 1e-3
|
|
118
|
+
major_iterations_limit: float = 100
|
|
119
|
+
# constraint and cost params
|
|
120
|
+
oritation_constraint_tol: float = 1e-3
|
|
121
|
+
pos_constraint_tol: float = 1e-3 # 0.001m, work when pos_cost_weight==0.0
|
|
122
|
+
pos_cost_weight: float = 0.0 # If U need high accuracy, set this to 0.0 !!!
|
|
@@ -0,0 +1,43 @@
|
|
|
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
|
+
@abstractmethod
|
|
10
|
+
def control(self, target_positions:list, target_velocities:list, target_torques:list)->bool:
|
|
11
|
+
pass
|
|
12
|
+
|
|
13
|
+
@abstractmethod
|
|
14
|
+
def control_right(self, target_positions:list, target_velocities:list, target_torques:list)->bool:
|
|
15
|
+
pass
|
|
16
|
+
|
|
17
|
+
@abstractmethod
|
|
18
|
+
def control_left(self, target_positions:list, target_velocities:list, target_torques:list)->bool:
|
|
19
|
+
pass
|
|
20
|
+
|
|
21
|
+
@abstractmethod
|
|
22
|
+
def open(self, side:EndEffectorSide)->bool:
|
|
23
|
+
pass
|
|
24
|
+
|
|
25
|
+
@abstractmethod
|
|
26
|
+
def get_state(self)->Tuple[EndEffectorState, EndEffectorState]:
|
|
27
|
+
pass
|
|
28
|
+
|
|
29
|
+
@abstractmethod
|
|
30
|
+
def get_position(self)->Tuple[float, float]:
|
|
31
|
+
pass
|
|
32
|
+
|
|
33
|
+
@abstractmethod
|
|
34
|
+
def get_velocity(self)->Tuple[float, float]:
|
|
35
|
+
pass
|
|
36
|
+
|
|
37
|
+
@abstractmethod
|
|
38
|
+
def get_effort(self)->Tuple[float, float]:
|
|
39
|
+
pass
|
|
40
|
+
|
|
41
|
+
@abstractmethod
|
|
42
|
+
def get_grasping_state(self)->Tuple[EndEffectorState.GraspingState, EndEffectorState.GraspingState]:
|
|
43
|
+
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
|
+
|
|
@@ -0,0 +1,7 @@
|
|
|
1
|
+
from .robot import KuavoSDK, KuavoRobot
|
|
2
|
+
from .robot_info import KuavoRobotInfo
|
|
3
|
+
from .robot_state import KuavoRobotState
|
|
4
|
+
from .robot_arm import KuavoRobotArm
|
|
5
|
+
from .robot_head import KuavoRobotHead
|
|
6
|
+
from .dexterous_hand import DexterousHand
|
|
7
|
+
from .leju_claw import LejuClaw
|