|
| 1 | + |
| 2 | +--- |
| 3 | + |
| 4 | +# Linker Hand Python API Documentation |
| 5 | + |
| 6 | +## API Overview |
| 7 | + |
| 8 | +This document provides a detailed overview of the Python API for the Linker Hand, including functions for controlling the hand's movements, retrieving sensor data, and setting operational parameters. |
| 9 | + |
| 10 | +## Public API |
| 11 | + |
| 12 | +### 设置速度 |
| 13 | +```python |
| 14 | +def set_speed(self,speed=[100]*5) |
| 15 | +``` |
| 16 | +**Description**: |
| 17 | +设置手部的运动速度。 |
| 18 | +**Parameters**: |
| 19 | +- `speed`: 一个包含速度数据的 list,长度为5个元素对应每个关节的速度值,如何是L7则为7个元素,对应每个电机速度。 |
| 20 | + |
| 21 | +--- |
| 22 | + |
| 23 | +### 设置五根手指的转矩限制 - 力度 |
| 24 | +```python |
| 25 | +def set_torque(self, torque=[180] * 5) |
| 26 | +``` |
| 27 | +**Description**: |
| 28 | +设置手指的转矩限制或力度,用于控制抓取力度。 |
| 29 | +**Parameters**: |
| 30 | +- `torque`: 一个包含力度数据的 list,长度为5个元素对应每个手指的力度值,如何是L7则为7个元素,对应每个电机力度值。 |
| 31 | + |
| 32 | +--- |
| 33 | + |
| 34 | +### 设置关节位置 |
| 35 | +```python |
| 36 | +def finger_move(self,pose=[]) |
| 37 | +``` |
| 38 | +**Description**: |
| 39 | +设置关节的目标位置,用于控制手指的运动。 |
| 40 | +**Parameters**: |
| 41 | +- `pose`: 一个包含目标位置数据的 float类型的list,L7长度为7个元素,L10长度为10个元素,L20长度为20个元素,L25长度为25个元素。 |
| 42 | + |
| 43 | +--- |
| 44 | + |
| 45 | +### 设置电机电流值 |
| 46 | +```python |
| 47 | +def set_current(self, current=[]) |
| 48 | +``` |
| 49 | +**Description**: |
| 50 | +设置电机的电流值。 |
| 51 | +**Parameters**: |
| 52 | +- `current`: 一个包含目标电流数据的 int类型list,长度为5个元素,当前只支持L20版本。 |
| 53 | + |
| 54 | +--- |
| 55 | + |
| 56 | +### 获取速度 |
| 57 | +```python |
| 58 | +def get_speed(self) |
| 59 | +return [180, 200, 200, 200, 200] |
| 60 | +``` |
| 61 | +**Description**: |
| 62 | +获取当前设置的速度值。提示:需设置关节位置后才能获取到速度值。 |
| 63 | + |
| 64 | +**Returns**: |
| 65 | +- 返回一个 list,包含当前的手指速度设置值。 |
| 66 | + |
| 67 | +--- |
| 68 | + |
| 69 | +### 获取当前关节状态 |
| 70 | +```python |
| 71 | +def get_state(self) |
| 72 | +return [81, 79, 79, 79, 79, 79, 83, 76, 80, 78] |
| 73 | +``` |
| 74 | +**Description**: |
| 75 | +获取当前关节的状态float类型的list信息。提示:需要设置关节位置后才能获取到状态信息,L7长度为7个元素,L10长度为10个元素,L20长度为20个元素,L25长度为25个元素。 |
| 76 | + |
| 77 | +**Returns**: |
| 78 | +- 返回一个 float类型的list,包含当前关节的状态数据。 |
| 79 | + |
| 80 | +--- |
| 81 | + |
| 82 | +### 获取法向压力、切向压力、切向方向、接近感应 |
| 83 | +```python |
| 84 | +def get_force(self) |
| 85 | +return [[255.0, 0.0, 0.0, 77.0, 192.0], [82.0, 0.0, 0.0, 230.0, 223.0], [107.0, 255.0, 255.0, 31.0, 110.0], [255.0, 0.0, 20.0, 255.0, 255.0]] |
| 86 | +``` |
| 87 | +**Description**: |
| 88 | +获取手部传感器的综合数据,包括法向压力、切向压力、切向方向和接近感应。 |
| 89 | +**Returns**: |
| 90 | +- 返回一个二维list,其中每个子list包含不同类别的list压力数据[[法向压力],[切向压力],[切向压力方向],[接近感应]]。类别每一个元素对应拇指、食指、中指、无名指、小拇指 |
| 91 | + |
| 92 | +--- |
| 93 | + |
| 94 | +### 获取版本号 |
| 95 | +```python |
| 96 | +def get_version(self) |
| 97 | +return [10, 6, 22, 82, 20, 17, 0] |
| 98 | +``` |
| 99 | +**Description**: |
| 100 | +获取当前软件或硬件的版本号。 |
| 101 | +**Returns**: |
| 102 | +- 返回一个字符串,表示当前的版本号。list元素依次表示:自由度\版本号\序号\左手76右手82\内部序列号 |
| 103 | + |
| 104 | +--- |
| 105 | +-------------------------------------------------------------- |
| 106 | +### 获取扭矩 |
| 107 | +```python |
| 108 | +def get_torque(self) |
| 109 | +return [200, 200, 200, 200, 200] |
| 110 | +``` |
| 111 | +**Description**: |
| 112 | +获取当前手指扭矩list信息。表示每根手指当前电机扭矩,支持L20、L25。 |
| 113 | + |
| 114 | +**Returns**: |
| 115 | +- 返回一个 float类型的list。 |
| 116 | + |
| 117 | +--- |
| 118 | + |
| 119 | +### 获取电机温度 |
| 120 | +```python |
| 121 | +def get_temperature(self) |
| 122 | +return [41, 71, 45, 40, 50, 47, 58, 50, 63, 70] |
| 123 | +``` |
| 124 | +**Description**: |
| 125 | +获取当前关节的电机温度。 |
| 126 | + |
| 127 | +**Returns**: |
| 128 | +- 返回一个 list数据,包含当前关节的电机温度。 |
| 129 | + |
| 130 | +--- |
| 131 | + |
| 132 | +### 获取电机故障码 |
| 133 | +```python |
| 134 | +def get_fault(self) |
| 135 | +return [0, 4, 0, 0, 0, 0, 0, 0, 0, 0] |
| 136 | +``` |
| 137 | +**Description**: |
| 138 | +获取当前关节电机故障,0表示正常 数字1电流过载 数字2温度过高 数字3编码错误 数字4过压/欠压。 |
| 139 | + |
| 140 | +**Returns**: |
| 141 | +- 返回一个 float类型的list,包含当前关节电机故障。 |
| 142 | + |
| 143 | +--- |
| 144 | + |
| 145 | +### 清除电机故障码 |
| 146 | +```python |
| 147 | +def clear_faults(self) |
| 148 | +``` |
| 149 | +**Description**: |
| 150 | +尝试清除电机故障,无返回值。只支持L20 |
| 151 | +**Returns**: |
| 152 | + |
| 153 | +--- |
| 154 | + |
| 155 | +## Example Usage |
| 156 | + |
| 157 | +以下是一个完整的示例代码,展示如何使用上述 API: |
| 158 | + |
| 159 | +```python |
| 160 | + |
| 161 | +from LinkerHand.linker_hand_api import LinkerHandApi |
| 162 | +def main(): |
| 163 | + # 初始化API hand_type:left or right hand_joint:L7 or L10 or L20 or L25 |
| 164 | + linker_hand = LinkerHandApi(hand_type="left", hand_joint="L10") |
| 165 | + # 设置手指速度 |
| 166 | + linker_hand.set_speed(speed=[120,200,200,200,200]) |
| 167 | + # 设置手扭矩 |
| 168 | + linker_hand.set_torque(torque=[200,200,200,200,200]) |
| 169 | + # 获取手当前状态 |
| 170 | + hand_state = linker_hand.get_state() |
| 171 | + # 打印状态值 |
| 172 | + print(hand_state) |
| 173 | + |
| 174 | +``` |
| 175 | + |
| 176 | +--- |
| 177 | + |
| 178 | +## Notes |
| 179 | +- 在使用 API 之前,请确保手部设备已正确连接并初始化。 |
| 180 | +- 参数值(如速度、力度等)的具体范围和含义请参考设备的技术手册。 |
| 181 | + |
| 182 | +--- |
| 183 | + |
| 184 | +## Contact |
| 185 | +- 如果有任何问题或需要进一步支持,请联系 [[email protected]](mailto:[email protected])。 |
| 186 | + |
| 187 | +--- |
0 commit comments