xarm-python-sdk 1.15.2__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.
- xarm/__init__.py +2 -0
- xarm/build_backend.py +17 -0
- xarm/core/__init__.py +2 -0
- xarm/core/comm/__init__.py +5 -0
- xarm/core/comm/base.py +303 -0
- xarm/core/comm/serial_port.py +44 -0
- xarm/core/comm/socket_port.py +150 -0
- xarm/core/comm/uxbus_cmd_protocol.py +100 -0
- xarm/core/config/__init__.py +0 -0
- xarm/core/config/x_code.py +1427 -0
- xarm/core/config/x_config.py +553 -0
- xarm/core/utils/__init__.py +3 -0
- xarm/core/utils/convert.py +124 -0
- xarm/core/utils/crc16.py +76 -0
- xarm/core/utils/debug_print.py +21 -0
- xarm/core/utils/log.py +98 -0
- xarm/core/version.py +1 -0
- xarm/core/wrapper/__init__.py +11 -0
- xarm/core/wrapper/uxbus_cmd.py +1457 -0
- xarm/core/wrapper/uxbus_cmd_ser.py +94 -0
- xarm/core/wrapper/uxbus_cmd_tcp.py +305 -0
- xarm/tools/__init__.py +0 -0
- xarm/tools/blockly/__init__.py +1 -0
- xarm/tools/blockly/_blockly_base.py +416 -0
- xarm/tools/blockly/_blockly_handler.py +1338 -0
- xarm/tools/blockly/_blockly_highlight.py +94 -0
- xarm/tools/blockly/_blockly_node.py +61 -0
- xarm/tools/blockly/_blockly_tool.py +480 -0
- xarm/tools/blockly_tool.py +1864 -0
- xarm/tools/gcode.py +90 -0
- xarm/tools/list_ports.py +39 -0
- xarm/tools/modbus_tcp.py +205 -0
- xarm/tools/threads.py +30 -0
- xarm/tools/utils.py +36 -0
- xarm/version.py +1 -0
- xarm/wrapper/__init__.py +1 -0
- xarm/wrapper/studio_api.py +34 -0
- xarm/wrapper/xarm_api.py +4416 -0
- xarm/x3/__init__.py +2 -0
- xarm/x3/base.py +2638 -0
- xarm/x3/base_board.py +198 -0
- xarm/x3/code.py +62 -0
- xarm/x3/decorator.py +104 -0
- xarm/x3/events.py +166 -0
- xarm/x3/ft_sensor.py +264 -0
- xarm/x3/gpio.py +457 -0
- xarm/x3/grammar_async.py +21 -0
- xarm/x3/grammar_coroutine.py +24 -0
- xarm/x3/gripper.py +830 -0
- xarm/x3/modbus_tcp.py +84 -0
- xarm/x3/parse.py +110 -0
- xarm/x3/record.py +216 -0
- xarm/x3/report.py +204 -0
- xarm/x3/robotiq.py +220 -0
- xarm/x3/servo.py +485 -0
- xarm/x3/studio.py +138 -0
- xarm/x3/track.py +424 -0
- xarm/x3/utils.py +43 -0
- xarm/x3/xarm.py +1928 -0
- xarm_python_sdk-1.15.2.dist-info/METADATA +103 -0
- xarm_python_sdk-1.15.2.dist-info/RECORD +63 -0
- xarm_python_sdk-1.15.2.dist-info/WHEEL +4 -0
- xarm_python_sdk-1.15.2.dist-info/licenses/LICENSE +27 -0
xarm/wrapper/xarm_api.py
ADDED
|
@@ -0,0 +1,4416 @@
|
|
|
1
|
+
#!/usr/bin/env python3
|
|
2
|
+
# Software License Agreement (BSD License)
|
|
3
|
+
#
|
|
4
|
+
# Copyright (c) 2018, UFACTORY, Inc.
|
|
5
|
+
# All rights reserved.
|
|
6
|
+
#
|
|
7
|
+
# Author: Vinman <vinman.wen@ufactory.cc> <vinman.cub@gmail.com>
|
|
8
|
+
|
|
9
|
+
import math
|
|
10
|
+
from ..x3 import XArm, Studio
|
|
11
|
+
|
|
12
|
+
|
|
13
|
+
class XArmAPI(object):
|
|
14
|
+
def __init__(self, port=None, is_radian=False, do_not_open=False, **kwargs):
|
|
15
|
+
"""
|
|
16
|
+
The API wrapper of xArm
|
|
17
|
+
Note: Orientation of attitude angle
|
|
18
|
+
roll: rotate around the X axis
|
|
19
|
+
pitch: rotate around the Y axis
|
|
20
|
+
yaw: rotate around the Z axis
|
|
21
|
+
|
|
22
|
+
:param port: ip-address(such as '192.168.1.185')
|
|
23
|
+
Note: this parameter is required if parameter do_not_open is False
|
|
24
|
+
:param is_radian: set the default unit is radians or not, default is False
|
|
25
|
+
Note: (aim of design)
|
|
26
|
+
1. Default value for unified interface parameters
|
|
27
|
+
2: Unification of the external unit system
|
|
28
|
+
3. For compatibility with previous interfaces
|
|
29
|
+
Note: the conversion of degree (°) and radians (rad)
|
|
30
|
+
* 1 rad == 57.29577951308232 °
|
|
31
|
+
* 1 ° == 0.017453292519943295 rad
|
|
32
|
+
* 1 rad/s == 57.29577951308232 °/s
|
|
33
|
+
* 1 °/s == 0.017453292519943295 rad/s
|
|
34
|
+
* 1 rad/s^2 == 57.29577951308232 °/s^2
|
|
35
|
+
* 1 °/s^2 == 0.017453292519943295 rad/s^2
|
|
36
|
+
* 1 rad/s^3 == 57.29577951308232 °/s^3
|
|
37
|
+
* 1 °/s^3 == 0.017453292519943295 rad/s^3
|
|
38
|
+
Note: This parameter determines the value of the property self.default_is_radian
|
|
39
|
+
Note: This parameter determines the default value of the interface with the is_radian/input_is_radian/return_is_radian parameter
|
|
40
|
+
The list of affected interfaces is as follows:
|
|
41
|
+
1. method: get_position
|
|
42
|
+
2. method: set_position
|
|
43
|
+
3. method: get_servo_angle
|
|
44
|
+
4. method: set_servo_angle
|
|
45
|
+
5. method: set_servo_angle_j
|
|
46
|
+
6. method: move_gohome
|
|
47
|
+
7. method: reset
|
|
48
|
+
8. method: set_tcp_offset
|
|
49
|
+
9. method: set_joint_jerk
|
|
50
|
+
10. method: set_joint_maxacc
|
|
51
|
+
11. method: get_inverse_kinematics
|
|
52
|
+
12. method: get_forward_kinematics
|
|
53
|
+
13. method: is_tcp_limit
|
|
54
|
+
14. method: is_joint_limit
|
|
55
|
+
15. method: get_params
|
|
56
|
+
16: method: move_arc_lines
|
|
57
|
+
17: method: move_circle
|
|
58
|
+
18: method: set_servo_cartesian
|
|
59
|
+
Note: This parameter determines the default return type for some interfaces (such as the position, velocity, and acceleration associated with the return angle arc).
|
|
60
|
+
The affected attributes are as follows:
|
|
61
|
+
1. property: position
|
|
62
|
+
2. property: last_used_position
|
|
63
|
+
3. property: angles
|
|
64
|
+
4. property: last_used_angles
|
|
65
|
+
5. property: last_used_joint_speed
|
|
66
|
+
6. property: last_used_joint_acc
|
|
67
|
+
7. property: tcp_offset
|
|
68
|
+
:param do_not_open: do not open, default is False, if true, you need to manually call the connect interface.
|
|
69
|
+
:param kwargs: keyword parameters, generally do not need to set
|
|
70
|
+
axis: number of axes, required only when using a serial port connection, default is 7
|
|
71
|
+
baudrate: serial baudrate, invalid, reserved.
|
|
72
|
+
timeout: serial timeout, invalid, reserved.
|
|
73
|
+
filters: serial port filters, invalid, reserved.
|
|
74
|
+
check_tcp_limit: check the tcp param value out of limit or not, default is False
|
|
75
|
+
Note: only check the param roll/pitch/yaw of the interface `set_position`/`move_arc_lines`
|
|
76
|
+
check_joint_limit: check the joint param value out of limit or not, default is True
|
|
77
|
+
Note: only check the param angle of the interface `set_servo_angle` and the param angles of the interface `set_servo_angle_j`
|
|
78
|
+
check_cmdnum_limit: check the cmdnum out of limit or not, default is True
|
|
79
|
+
max_cmdnum: max cmdnum, default is 512
|
|
80
|
+
Note: only available in the param `check_cmdnum_limit` is True
|
|
81
|
+
check_is_ready: check if the arm is ready to move or not, default is True
|
|
82
|
+
Note: only available if firmware_version < 1.5.20
|
|
83
|
+
"""
|
|
84
|
+
self._is_radian = is_radian
|
|
85
|
+
self._arm = XArm(port=port,
|
|
86
|
+
is_radian=is_radian,
|
|
87
|
+
do_not_open=do_not_open,
|
|
88
|
+
instance=self,
|
|
89
|
+
**kwargs)
|
|
90
|
+
self._studio = Studio(port, True)
|
|
91
|
+
self.__attr_alias_map = {
|
|
92
|
+
'get_ik': self.get_inverse_kinematics,
|
|
93
|
+
'get_fk': self.get_forward_kinematics,
|
|
94
|
+
'set_sleep_time': self.set_pause_time,
|
|
95
|
+
'register_maable_mtbrake_changed_callback': self.register_mtable_mtbrake_changed_callback,
|
|
96
|
+
'release_maable_mtbrake_changed_callback': self.release_mtable_mtbrake_changed_callback,
|
|
97
|
+
'position_offset': self.tcp_offset,
|
|
98
|
+
'get_gpio_digital': self.get_tgpio_digital,
|
|
99
|
+
'set_gpio_digital': self.set_tgpio_digital,
|
|
100
|
+
'get_gpio_analog': self.get_tgpio_analog,
|
|
101
|
+
'set_fense_mode': self.set_fence_mode,
|
|
102
|
+
'get_suction_cup': self.get_vacuum_gripper,
|
|
103
|
+
'set_suction_cup': self.set_vacuum_gripper,
|
|
104
|
+
'get_ft_senfor_config': self.get_ft_sensor_config,
|
|
105
|
+
'shutdown_system': self.system_control,
|
|
106
|
+
}
|
|
107
|
+
|
|
108
|
+
def __getattr__(self, item):
|
|
109
|
+
if item in self.__attr_alias_map.keys():
|
|
110
|
+
return self.__attr_alias_map[item]
|
|
111
|
+
raise AttributeError('\'{}\' has not attribute \'{}\''.format(self.__class__.__name__, item))
|
|
112
|
+
|
|
113
|
+
@property
|
|
114
|
+
def arm(self):
|
|
115
|
+
"""
|
|
116
|
+
XArm interface implementation class instance, do not use (compatibility is not guaranteed)
|
|
117
|
+
"""
|
|
118
|
+
return self._arm
|
|
119
|
+
|
|
120
|
+
@property
|
|
121
|
+
def core(self):
|
|
122
|
+
"""
|
|
123
|
+
Core layer API, set only for advanced developers, please do not use
|
|
124
|
+
Ex:
|
|
125
|
+
self.core.move_line(...)
|
|
126
|
+
self.core.move_lineb(...)
|
|
127
|
+
self.core.move_joint(...)
|
|
128
|
+
...
|
|
129
|
+
"""
|
|
130
|
+
return self._arm.arm_cmd
|
|
131
|
+
|
|
132
|
+
@property
|
|
133
|
+
def count(self):
|
|
134
|
+
"""
|
|
135
|
+
Counter val
|
|
136
|
+
"""
|
|
137
|
+
return self._arm.count
|
|
138
|
+
|
|
139
|
+
@property
|
|
140
|
+
def only_check_result(self):
|
|
141
|
+
return self._arm.only_check_result
|
|
142
|
+
|
|
143
|
+
@property
|
|
144
|
+
def realtime_tcp_speed(self):
|
|
145
|
+
"""
|
|
146
|
+
The real time speed of tcp motion, only available if version > 1.2.11
|
|
147
|
+
|
|
148
|
+
:return: real time speed (mm/s)
|
|
149
|
+
"""
|
|
150
|
+
return self._arm.realtime_tcp_speed
|
|
151
|
+
|
|
152
|
+
@property
|
|
153
|
+
def realtime_joint_speeds(self):
|
|
154
|
+
"""
|
|
155
|
+
The real time speed of joint motion, only available if version > 1.2.11
|
|
156
|
+
|
|
157
|
+
:return: [joint-1-speed(°/s or rad/s), ...., joint-7-speed(°/s or rad/s)]
|
|
158
|
+
"""
|
|
159
|
+
return self._arm.realtime_joint_speeds
|
|
160
|
+
|
|
161
|
+
@property
|
|
162
|
+
def gpio_reset_config(self):
|
|
163
|
+
"""
|
|
164
|
+
The gpio reset enable config
|
|
165
|
+
:return: [cgpio_reset_enable, tgpio_reset_enable]
|
|
166
|
+
"""
|
|
167
|
+
return self._arm.gpio_reset_config
|
|
168
|
+
|
|
169
|
+
@property
|
|
170
|
+
def version_number(self):
|
|
171
|
+
"""
|
|
172
|
+
Frimware version number
|
|
173
|
+
|
|
174
|
+
:return: (major_version_number, minor_version_number, revision_version_number)
|
|
175
|
+
"""
|
|
176
|
+
return self._arm.version_number
|
|
177
|
+
|
|
178
|
+
@property
|
|
179
|
+
def connected(self):
|
|
180
|
+
"""
|
|
181
|
+
Connection status
|
|
182
|
+
"""
|
|
183
|
+
return self._arm.connected
|
|
184
|
+
|
|
185
|
+
@property
|
|
186
|
+
def default_is_radian(self):
|
|
187
|
+
"""
|
|
188
|
+
The default unit is radians or not
|
|
189
|
+
"""
|
|
190
|
+
return self._arm.default_is_radian
|
|
191
|
+
|
|
192
|
+
@property
|
|
193
|
+
def version(self):
|
|
194
|
+
"""
|
|
195
|
+
xArm version
|
|
196
|
+
"""
|
|
197
|
+
return self._arm.version
|
|
198
|
+
|
|
199
|
+
@property
|
|
200
|
+
def sn(self):
|
|
201
|
+
"""
|
|
202
|
+
xArm sn
|
|
203
|
+
"""
|
|
204
|
+
return self._arm.sn
|
|
205
|
+
|
|
206
|
+
@property
|
|
207
|
+
def control_box_sn(self):
|
|
208
|
+
"""
|
|
209
|
+
Control box sn
|
|
210
|
+
"""
|
|
211
|
+
return self._arm.control_box_sn
|
|
212
|
+
|
|
213
|
+
@property
|
|
214
|
+
def position(self):
|
|
215
|
+
"""
|
|
216
|
+
Cartesion position
|
|
217
|
+
Note:
|
|
218
|
+
1. If self.default_is_radian is True, the returned value (only roll/pitch/yaw) is in radians
|
|
219
|
+
|
|
220
|
+
return: [x(mm), y(mm), z(mm), roll(° or rad), pitch(° or rad), yaw(° or rad)]
|
|
221
|
+
"""
|
|
222
|
+
return self._arm.position
|
|
223
|
+
|
|
224
|
+
@property
|
|
225
|
+
def position_aa(self):
|
|
226
|
+
"""
|
|
227
|
+
The pose represented by the axis angle pose
|
|
228
|
+
Note:
|
|
229
|
+
1. If self.default_is_radian is True, the returned value (only roll/pitch/yaw) is in radians
|
|
230
|
+
|
|
231
|
+
:return: [x(mm), y(mm), z(mm), rx(° or rad), ry(° or rad), rz(° or rad)]
|
|
232
|
+
"""
|
|
233
|
+
return self._arm.position_aa
|
|
234
|
+
|
|
235
|
+
@property
|
|
236
|
+
def last_used_position(self):
|
|
237
|
+
"""
|
|
238
|
+
The last used cartesion position, default value of parameter x/y/z/roll/pitch/yaw of interface set_position
|
|
239
|
+
Note:
|
|
240
|
+
1. If self.default_is_radian is True, the returned value (only roll/pitch/yaw) is in radians
|
|
241
|
+
2. self.set_position(x=300) < == > self.set_position(x=300, *last_used_position[1:])
|
|
242
|
+
2. self.set_position(roll=-180) < == > self.set_position(x=self.last_used_position[:3], roll=-180, *self.last_used_position[4:])
|
|
243
|
+
|
|
244
|
+
:return: [x(mm), y(mm), z(mm), roll(° or rad), pitch(° or rad), yaw(° or rad)]
|
|
245
|
+
"""
|
|
246
|
+
return self._arm.last_used_position
|
|
247
|
+
|
|
248
|
+
@property
|
|
249
|
+
def tcp_jerk(self):
|
|
250
|
+
"""
|
|
251
|
+
Tcp jerk
|
|
252
|
+
|
|
253
|
+
:return: jerk (mm/s^3)
|
|
254
|
+
"""
|
|
255
|
+
return self._arm.tcp_jerk
|
|
256
|
+
|
|
257
|
+
@property
|
|
258
|
+
def tcp_speed_limit(self):
|
|
259
|
+
"""
|
|
260
|
+
Tcp speed limit, only available in socket way and enable_report is True and report_type is 'rich'
|
|
261
|
+
|
|
262
|
+
:return: [min_tcp_speed(mm/s), max_tcp_speed(mm/s)]
|
|
263
|
+
"""
|
|
264
|
+
return self._arm.tcp_speed_limit
|
|
265
|
+
|
|
266
|
+
@property
|
|
267
|
+
def tcp_acc_limit(self):
|
|
268
|
+
"""
|
|
269
|
+
Tcp acceleration limit, only available in socket way and enable_report is True and report_type is 'rich'
|
|
270
|
+
|
|
271
|
+
:return: [min_tcp_acc(mm/s^2), max_tcp_acc(mm/s^2)]
|
|
272
|
+
"""
|
|
273
|
+
return self._arm.tcp_acc_limit
|
|
274
|
+
|
|
275
|
+
@property
|
|
276
|
+
def last_used_tcp_speed(self):
|
|
277
|
+
"""
|
|
278
|
+
The last used cartesion speed, default value of parameter speed of interface set_position/move_circle
|
|
279
|
+
|
|
280
|
+
:return: speed (mm/s)
|
|
281
|
+
"""
|
|
282
|
+
return self._arm.last_used_tcp_speed
|
|
283
|
+
|
|
284
|
+
@property
|
|
285
|
+
def last_used_tcp_acc(self):
|
|
286
|
+
"""
|
|
287
|
+
The last used cartesion acceleration, default value of parameter mvacc of interface set_position/move_circle
|
|
288
|
+
|
|
289
|
+
:return: acceleration (mm/s^2)
|
|
290
|
+
"""
|
|
291
|
+
return self._arm.last_used_tcp_acc
|
|
292
|
+
|
|
293
|
+
@property
|
|
294
|
+
def angles(self):
|
|
295
|
+
"""
|
|
296
|
+
Servo angles
|
|
297
|
+
Note:
|
|
298
|
+
1. If self.default_is_radian is True, the returned value is in radians
|
|
299
|
+
|
|
300
|
+
:return: [angle1(° or rad), angle2(° or rad), ..., anglen7(° or rad)]
|
|
301
|
+
"""
|
|
302
|
+
return self._arm.angles
|
|
303
|
+
|
|
304
|
+
@property
|
|
305
|
+
def joint_jerk(self):
|
|
306
|
+
"""
|
|
307
|
+
Joint jerk
|
|
308
|
+
Note:
|
|
309
|
+
1. If self.default_is_radian is True, the returned value is in radians
|
|
310
|
+
|
|
311
|
+
:return: jerk (°/s^3 or rad/s^3)
|
|
312
|
+
"""
|
|
313
|
+
return self._arm.joint_jerk
|
|
314
|
+
|
|
315
|
+
@property
|
|
316
|
+
def joint_speed_limit(self):
|
|
317
|
+
"""
|
|
318
|
+
Joint speed limit, only available in socket way and enable_report is True and report_type is 'rich'
|
|
319
|
+
Note:
|
|
320
|
+
1. If self.default_is_radian is True, the returned value is in radians
|
|
321
|
+
|
|
322
|
+
:return: [min_joint_speed(°/s or rad/s), max_joint_speed(°/s or rad/s)]
|
|
323
|
+
"""
|
|
324
|
+
return self._arm.joint_speed_limit
|
|
325
|
+
|
|
326
|
+
@property
|
|
327
|
+
def joint_acc_limit(self):
|
|
328
|
+
"""
|
|
329
|
+
Joint acceleration limit, only available in socket way and enable_report is True and report_type is 'rich'
|
|
330
|
+
Note:
|
|
331
|
+
1. If self.default_is_radian is True, the returned value is in radians
|
|
332
|
+
|
|
333
|
+
:return: [min_joint_acc(°/s^2 or rad/s^2), max_joint_acc(°/s^2 or rad/s^2)]
|
|
334
|
+
"""
|
|
335
|
+
return self._arm.joint_acc_limit
|
|
336
|
+
|
|
337
|
+
@property
|
|
338
|
+
def last_used_angles(self):
|
|
339
|
+
"""
|
|
340
|
+
The last used servo angles, default value of parameter angle of interface set_servo_angle
|
|
341
|
+
Note:
|
|
342
|
+
1. If self.default_is_radian is True, the returned value is in radians
|
|
343
|
+
2. self.set_servo_angle(servo_id=1, angle=75) < == > self.set_servo_angle(angle=[75] + self.last_used_angles[1:])
|
|
344
|
+
3. self.set_servo_angle(servo_id=5, angle=30) < == > self.set_servo_angle(angle=self.last_used_angles[:4] + [30] + self.last_used_angles[5:])
|
|
345
|
+
|
|
346
|
+
:return: [angle1(° or rad), angle2(° or rad), ..., angle7(° or rad)]
|
|
347
|
+
"""
|
|
348
|
+
return self._arm.last_used_angles
|
|
349
|
+
|
|
350
|
+
@property
|
|
351
|
+
def last_used_joint_speed(self):
|
|
352
|
+
"""
|
|
353
|
+
The last used joint speed, default value of parameter speed of interface set_servo_angle
|
|
354
|
+
Note:
|
|
355
|
+
1. If self.default_is_radian is True, the returned value is in radians
|
|
356
|
+
|
|
357
|
+
:return: speed (°/s or rad/s)
|
|
358
|
+
"""
|
|
359
|
+
return self._arm.last_used_joint_speed
|
|
360
|
+
|
|
361
|
+
@property
|
|
362
|
+
def last_used_joint_acc(self):
|
|
363
|
+
"""
|
|
364
|
+
The last used joint acceleration, default value of parameter mvacc of interface set_servo_angle
|
|
365
|
+
Note:
|
|
366
|
+
1. If self.default_is_radian is True, the returned value is in radians
|
|
367
|
+
|
|
368
|
+
:return: acceleration (°/s^2 or rad/s^2)
|
|
369
|
+
"""
|
|
370
|
+
return self._arm.last_used_joint_acc
|
|
371
|
+
|
|
372
|
+
@property
|
|
373
|
+
def tcp_offset(self):
|
|
374
|
+
"""
|
|
375
|
+
Cartesion position offset, only available in socket way and enable_report is True
|
|
376
|
+
Note:
|
|
377
|
+
1. If self.default_is_radian is True, the returned value(roll_offset/pitch_offset/yaw_offset) is in radians
|
|
378
|
+
|
|
379
|
+
:return: [x_offset(mm), y_offset(mm), z_offset(mm), roll_offset(° or rad), pitch_offset(° or rad), yaw_offset(° or rad)]
|
|
380
|
+
"""
|
|
381
|
+
return self._arm.position_offset
|
|
382
|
+
|
|
383
|
+
@property
|
|
384
|
+
def world_offset(self):
|
|
385
|
+
"""
|
|
386
|
+
Base coordinate offset, only available if version > 1.2.11
|
|
387
|
+
|
|
388
|
+
Note:
|
|
389
|
+
1. If self.default_is_radian is True, the returned value(roll_offset/pitch_offset/yaw_offset) is in radians
|
|
390
|
+
|
|
391
|
+
:return: [x_offset(mm), y_offset(mm), z_offset(mm), roll_offset(° or rad), pitch_offset(° or rad), yaw_offset(° or rad)]
|
|
392
|
+
"""
|
|
393
|
+
return self._arm.world_offset
|
|
394
|
+
|
|
395
|
+
@property
|
|
396
|
+
def state(self):
|
|
397
|
+
"""
|
|
398
|
+
xArm state
|
|
399
|
+
|
|
400
|
+
:return:
|
|
401
|
+
1: in motion
|
|
402
|
+
2: sleeping
|
|
403
|
+
3: suspended
|
|
404
|
+
4: stopping
|
|
405
|
+
"""
|
|
406
|
+
return self._arm.state
|
|
407
|
+
|
|
408
|
+
@property
|
|
409
|
+
def mode(self):
|
|
410
|
+
"""
|
|
411
|
+
xArm mode, only available in socket way and enable_report is True
|
|
412
|
+
|
|
413
|
+
:return:
|
|
414
|
+
0: position control mode
|
|
415
|
+
1: servo motion mode
|
|
416
|
+
2: joint teaching mode
|
|
417
|
+
3: cartesian teaching mode (invalid)
|
|
418
|
+
4: joint velocity control mode
|
|
419
|
+
5: cartesian velocity control mode
|
|
420
|
+
6: joint online trajectory planning mode
|
|
421
|
+
7: cartesian online trajectory planning mode
|
|
422
|
+
"""
|
|
423
|
+
return self._arm.mode
|
|
424
|
+
|
|
425
|
+
@property
|
|
426
|
+
def is_simulation_robot(self):
|
|
427
|
+
"""
|
|
428
|
+
Is simulation robot not not
|
|
429
|
+
"""
|
|
430
|
+
return self._arm.is_simulation_robot
|
|
431
|
+
|
|
432
|
+
@property
|
|
433
|
+
def joints_torque(self):
|
|
434
|
+
"""
|
|
435
|
+
Joints torque, only available in socket way and enable_report is True and report_type is 'rich'
|
|
436
|
+
|
|
437
|
+
:return: [joint-1, ....]
|
|
438
|
+
"""
|
|
439
|
+
return self._arm.joints_torque
|
|
440
|
+
|
|
441
|
+
@property
|
|
442
|
+
def tcp_load(self):
|
|
443
|
+
"""
|
|
444
|
+
xArm tcp load, only available in socket way and enable_report is True and report_type is 'rich'
|
|
445
|
+
|
|
446
|
+
:return: [weight, center of gravity]
|
|
447
|
+
such as: [weight(kg), [x(mm), y(mm), z(mm)]]
|
|
448
|
+
"""
|
|
449
|
+
return self._arm.tcp_load
|
|
450
|
+
|
|
451
|
+
@property
|
|
452
|
+
def collision_sensitivity(self):
|
|
453
|
+
"""
|
|
454
|
+
The sensitivity value of collision, only available in socket way and enable_report is True and report_type is 'rich'
|
|
455
|
+
|
|
456
|
+
:return: 0~5
|
|
457
|
+
"""
|
|
458
|
+
return self._arm.collision_sensitivity
|
|
459
|
+
|
|
460
|
+
@property
|
|
461
|
+
def teach_sensitivity(self):
|
|
462
|
+
"""
|
|
463
|
+
The sensitivity value of drag and teach, only available in socket way and enable_report is True and report_type is 'rich'
|
|
464
|
+
|
|
465
|
+
:return: 1~5
|
|
466
|
+
"""
|
|
467
|
+
return self._arm.teach_sensitivity
|
|
468
|
+
|
|
469
|
+
@property
|
|
470
|
+
def motor_brake_states(self):
|
|
471
|
+
"""
|
|
472
|
+
Motor brake state list, only available in socket way and enable_report is True and report_type is 'rich'
|
|
473
|
+
Note:
|
|
474
|
+
For a robot with a number of axes n, only the first n states are valid, and the latter are reserved.
|
|
475
|
+
|
|
476
|
+
:return: [motor-1-brake-state, ..., motor-7-brake-state, reserved]
|
|
477
|
+
motor-{i}-brake-state:
|
|
478
|
+
0: enable
|
|
479
|
+
1: disable
|
|
480
|
+
"""
|
|
481
|
+
return self._arm.motor_brake_states
|
|
482
|
+
|
|
483
|
+
@property
|
|
484
|
+
def motor_enable_states(self):
|
|
485
|
+
"""
|
|
486
|
+
Motor enable state list, only available in socket way and enable_report is True and report_type is 'rich'
|
|
487
|
+
Note:
|
|
488
|
+
For a robot with a number of axes n, only the first n states are valid, and the latter are reserved.
|
|
489
|
+
|
|
490
|
+
:return: [motor-1-enable-state, ..., motor-7-enable-state, reserved]
|
|
491
|
+
motor-{i}-enable-state:
|
|
492
|
+
0: disable
|
|
493
|
+
1: enable
|
|
494
|
+
"""
|
|
495
|
+
return self._arm.motor_enable_states
|
|
496
|
+
|
|
497
|
+
@property
|
|
498
|
+
def temperatures(self):
|
|
499
|
+
"""
|
|
500
|
+
Motor temperature, only available if version > 1.2.11
|
|
501
|
+
|
|
502
|
+
:return: [motor-1-temperature, ..., motor-7-temperature]
|
|
503
|
+
"""
|
|
504
|
+
return self._arm.temperatures
|
|
505
|
+
|
|
506
|
+
@property
|
|
507
|
+
def has_err_warn(self):
|
|
508
|
+
"""
|
|
509
|
+
Contorller have an error or warning or not
|
|
510
|
+
|
|
511
|
+
:return: True/False
|
|
512
|
+
"""
|
|
513
|
+
return self._arm.has_err_warn
|
|
514
|
+
|
|
515
|
+
@property
|
|
516
|
+
def has_error(self):
|
|
517
|
+
"""
|
|
518
|
+
Controller have an error or not
|
|
519
|
+
"""
|
|
520
|
+
return self._arm.has_error
|
|
521
|
+
|
|
522
|
+
@property
|
|
523
|
+
def has_warn(self):
|
|
524
|
+
"""
|
|
525
|
+
Controller have an warnning or not
|
|
526
|
+
"""
|
|
527
|
+
return self._arm.has_warn
|
|
528
|
+
|
|
529
|
+
@property
|
|
530
|
+
def error_code(self):
|
|
531
|
+
"""
|
|
532
|
+
Controller error code. See the [Controller Error Code Documentation](./xarm_api_code.md#controller-error-code) for details.
|
|
533
|
+
"""
|
|
534
|
+
return self._arm.error_code
|
|
535
|
+
|
|
536
|
+
@property
|
|
537
|
+
def warn_code(self):
|
|
538
|
+
"""
|
|
539
|
+
Controller warn code. See the [Controller Warn Code Documentation](./xarm_api_code.md#controller-warn-code) for details.
|
|
540
|
+
"""
|
|
541
|
+
return self._arm.warn_code
|
|
542
|
+
|
|
543
|
+
@property
|
|
544
|
+
def cmd_num(self):
|
|
545
|
+
"""
|
|
546
|
+
Number of command caches in the controller
|
|
547
|
+
"""
|
|
548
|
+
return self._arm.cmd_num
|
|
549
|
+
|
|
550
|
+
@property
|
|
551
|
+
def device_type(self):
|
|
552
|
+
"""
|
|
553
|
+
Device type, only available in socket way and enable_report is True and report_type is 'rich'
|
|
554
|
+
"""
|
|
555
|
+
return self._arm.device_type
|
|
556
|
+
|
|
557
|
+
@property
|
|
558
|
+
def axis(self):
|
|
559
|
+
"""
|
|
560
|
+
Axis number, only available in socket way and enable_report is True and report_type is 'rich'
|
|
561
|
+
"""
|
|
562
|
+
return self._arm.axis
|
|
563
|
+
|
|
564
|
+
@property
|
|
565
|
+
def master_id(self):
|
|
566
|
+
"""
|
|
567
|
+
Master id, only available in socket way and enable_report is True and report_type is 'rich'
|
|
568
|
+
"""
|
|
569
|
+
return self._arm.master_id
|
|
570
|
+
|
|
571
|
+
@property
|
|
572
|
+
def slave_id(self):
|
|
573
|
+
"""
|
|
574
|
+
Slave id, only available in socket way and enable_report is True and report_type is 'rich'
|
|
575
|
+
"""
|
|
576
|
+
return self._arm.slave_id
|
|
577
|
+
|
|
578
|
+
@property
|
|
579
|
+
def gravity_direction(self):
|
|
580
|
+
"""
|
|
581
|
+
gravity direction, only available in socket way and enable_report is True and report_type is 'rich'
|
|
582
|
+
:return:
|
|
583
|
+
"""
|
|
584
|
+
return self._arm.gravity_direction
|
|
585
|
+
|
|
586
|
+
@property
|
|
587
|
+
def servo_codes(self):
|
|
588
|
+
"""
|
|
589
|
+
Servos status and error_code
|
|
590
|
+
:return: [
|
|
591
|
+
[servo-1-status, servo-1-code],
|
|
592
|
+
...,
|
|
593
|
+
[servo-7-status, servo-7-code],
|
|
594
|
+
[tool-gpio-status, tool-gpio-code]
|
|
595
|
+
]
|
|
596
|
+
"""
|
|
597
|
+
return self._arm.servo_codes
|
|
598
|
+
|
|
599
|
+
@property
|
|
600
|
+
def voltages(self):
|
|
601
|
+
"""
|
|
602
|
+
Servos voltage
|
|
603
|
+
|
|
604
|
+
:return: [servo-1-voltage, ..., servo-7-voltage]
|
|
605
|
+
"""
|
|
606
|
+
return self._arm.voltages
|
|
607
|
+
|
|
608
|
+
@property
|
|
609
|
+
def currents(self):
|
|
610
|
+
"""
|
|
611
|
+
Servos electric current
|
|
612
|
+
|
|
613
|
+
:return: [servo-1-current, ..., servo-7-current]
|
|
614
|
+
"""
|
|
615
|
+
return self._arm.currents
|
|
616
|
+
|
|
617
|
+
@property
|
|
618
|
+
def cgpio_states(self):
|
|
619
|
+
"""
|
|
620
|
+
Controller gpio state
|
|
621
|
+
|
|
622
|
+
:return: states
|
|
623
|
+
states[0]: contorller gpio module state
|
|
624
|
+
states[0] == 0: normal
|
|
625
|
+
states[0] == 1: wrong
|
|
626
|
+
states[0] == 6: communication failure
|
|
627
|
+
states[1]: controller gpio module error code
|
|
628
|
+
states[1] == 0: normal
|
|
629
|
+
states[1] != 0: error code
|
|
630
|
+
states[2]: digital input functional gpio state
|
|
631
|
+
Note: digital-i-input functional gpio state = states[2] >> i & 0x01
|
|
632
|
+
states[3]: digital input configuring gpio state
|
|
633
|
+
Note: digital-i-input configuring gpio state = states[3] >> i & 0x01
|
|
634
|
+
states[4]: digital output functional gpio state
|
|
635
|
+
Note: digital-i-output functional gpio state = states[4] >> i & 0x01
|
|
636
|
+
states[5]: digital output configuring gpio state
|
|
637
|
+
Note: digital-i-output configuring gpio state = states[5] >> i & 0x01
|
|
638
|
+
states[6]: analog-0 input value
|
|
639
|
+
states[7]: analog-1 input value
|
|
640
|
+
states[8]: analog-0 output value
|
|
641
|
+
states[9]: analog-1 output value
|
|
642
|
+
states[10]: digital input functional info, [digital-0-input-functional-mode, ... digital-7-input-functional-mode]
|
|
643
|
+
states[11]: digital output functional info, [digital-0-output-functional-mode, ... digital-7-output-functional-mode]
|
|
644
|
+
"""
|
|
645
|
+
return self._arm.cgpio_states
|
|
646
|
+
|
|
647
|
+
@property
|
|
648
|
+
def self_collision_params(self):
|
|
649
|
+
"""
|
|
650
|
+
Self collision params
|
|
651
|
+
|
|
652
|
+
:return: params
|
|
653
|
+
params[0]: self collision detection or not
|
|
654
|
+
params[1]: self collision tool type
|
|
655
|
+
params[2]: self collision model params
|
|
656
|
+
"""
|
|
657
|
+
return self._arm.self_collision_params
|
|
658
|
+
|
|
659
|
+
@property
|
|
660
|
+
def ft_ext_force(self):
|
|
661
|
+
"""
|
|
662
|
+
The external force detection value of the Six-axis Force Torque Sensor after filtering, load and offset compensation
|
|
663
|
+
"""
|
|
664
|
+
return self._arm.ft_ext_force
|
|
665
|
+
|
|
666
|
+
@property
|
|
667
|
+
def ft_raw_force(self):
|
|
668
|
+
"""
|
|
669
|
+
The direct reading of the Six-axis Force Torque Sensor at the end, without any processing
|
|
670
|
+
"""
|
|
671
|
+
return self._arm.ft_raw_force
|
|
672
|
+
|
|
673
|
+
def connect(self, port=None, baudrate=None, timeout=None, axis=None, **kwargs):
|
|
674
|
+
"""
|
|
675
|
+
Connect to xArm
|
|
676
|
+
|
|
677
|
+
:param port: port name or the ip address, default is the value when initializing an instance
|
|
678
|
+
:param baudrate: baudrate, only available in serial way, default is the value when initializing an instance
|
|
679
|
+
:param timeout: timeout, only available in serial way, default is the value when initializing an instance
|
|
680
|
+
:param axis: number of axes, required only when using a serial port connection, default is 7
|
|
681
|
+
"""
|
|
682
|
+
self._arm.connect(port=port, baudrate=baudrate, timeout=timeout, axis=axis, **kwargs)
|
|
683
|
+
|
|
684
|
+
def disconnect(self):
|
|
685
|
+
"""
|
|
686
|
+
Disconnect
|
|
687
|
+
"""
|
|
688
|
+
self._arm.disconnect()
|
|
689
|
+
|
|
690
|
+
def send_cmd_sync(self, command=None):
|
|
691
|
+
"""
|
|
692
|
+
Send cmd and wait (only waiting the cmd response, not waiting for the movement)
|
|
693
|
+
Note:
|
|
694
|
+
1. Some command depends on self.default_is_radian
|
|
695
|
+
|
|
696
|
+
:param command:
|
|
697
|
+
'G1': 'set_position(MoveLine): G1 X{x} Y{y} Z{z} A{roll} B{pitch} C{yaw} F{speed} Q{acc} T{mvtime}'
|
|
698
|
+
'G2': 'move_circle: G2 X{x1} Y{y1} Z{z1} A{roll1} B{pitch1} C{yaw1} I{x2} J{y2} K{z2} L{roll2} M{pitch2} N{yaw2} F{speed} Q{acc} T{mvtime}'
|
|
699
|
+
'G4': 'set_pause_time: G4 T{second}'
|
|
700
|
+
'G7': 'set_servo_angle: G7 I{servo_1} J{servo_2} K{servo_3} L{servo_4} M{servo_5} N{servo_6} O{servo_7} F{speed} Q{acc} T{mvtime}'
|
|
701
|
+
'G8': 'move_gohome: G8 F{speed} Q{acc} T{mvtime}'
|
|
702
|
+
'G9': 'set_position(MoveArcLine): G9 X{x} Y{y} Z{z} A{roll} B{pitch} C{yaw} R{radius} F{speed} Q{acc} T{mvtime}'
|
|
703
|
+
'G11': 'set_servo_angle_j: G11 I{servo_1} J{servo_2} K{servo_3} L{servo_4} M{servo_5} N{servo_6} O{servo_7} F{speed} Q{acc} T{mvtime}'
|
|
704
|
+
'H1': 'get_version: H1'
|
|
705
|
+
'H11': 'motion_enable: H11 I{servo_id} V{enable}'
|
|
706
|
+
'H12': 'set_state: H12 V{state}'
|
|
707
|
+
'H13': 'get_state: H13'
|
|
708
|
+
'H14': 'get_cmdnum: H14'
|
|
709
|
+
'H15': 'get_err_warn_code: H15'
|
|
710
|
+
'H16': 'clean_error: H16'
|
|
711
|
+
'H17': 'clean_warn: H17'
|
|
712
|
+
'H18': 'set_servo_attach/set_servo_detach: H18 I{servo_id} V{1: enable(detach), 0: disable(attach)}'
|
|
713
|
+
'H19': 'set_mode: H19 V{mode}'
|
|
714
|
+
'H31': 'set_tcp_jerk: H31 V{jerk(mm/s^3)}'
|
|
715
|
+
'H32': 'set_tcp_maxacc: H32 V{maxacc(mm/s^2)}'
|
|
716
|
+
'H33': 'set_joint_jerk: H33 V{jerk(°/s^3 or rad/s^3)}'
|
|
717
|
+
'H34': 'set_joint_maxacc: H34 {maxacc(°/s^2 or rad/s^2)}'
|
|
718
|
+
'H35': 'set_tcp_offset: H35 X{x} Y{y} Z{z} A{roll} B{pitch} C{yaw}'
|
|
719
|
+
'H36': 'set_tcp_load: H36 I{weight} J{center_x} K{center_y} L{center_z}'
|
|
720
|
+
'H37': 'set_collision_sensitivity: H37 V{sensitivity}'
|
|
721
|
+
'H38': 'set_teach_sensitivity: H38 V{sensitivity}'
|
|
722
|
+
'H39': 'clean_conf: H39'
|
|
723
|
+
'H40': 'save_conf: H40'
|
|
724
|
+
'H41': 'get_position: H41'
|
|
725
|
+
'H42': 'get_servo_angle: H42'
|
|
726
|
+
'H43': 'get_inverse_kinematics: H43 X{x} Y{y} Z{z} A{roll} B{pitch} C{yaw}'
|
|
727
|
+
'H44': 'get_forward_kinematics: H44 I{servo_1} J{servo_2} K{servo_3} L{servo_4} M{servo_5} N{servo_6} O{servo_7}'
|
|
728
|
+
'H45': 'is_joint_limit: H45 I{servo_1} J{servo_2} K{servo_3} L{servo_4} M{servo_5} N{servo_6} O{servo_7}'
|
|
729
|
+
'H46': 'is_tcp_limit: H46 X{x} Y{y} Z{z} A{roll} B{pitch} C{yaw}'
|
|
730
|
+
'H51': 'set_gravity_direction: H51 X{x} Y{y} Z{z}'
|
|
731
|
+
'H106': 'get_servo_debug_msg: H106'
|
|
732
|
+
'M116': 'set_gripper_enable: M116 V{enable}'
|
|
733
|
+
'M117': 'set_gripper_mode: M117 V{mode}'
|
|
734
|
+
'M119': 'get_gripper_position: M119'
|
|
735
|
+
'M120': 'set_gripper_position: M120 V{pos}'
|
|
736
|
+
'M121': 'set_gripper_speed: M116 V{speed}'
|
|
737
|
+
'M125': 'get_gripper_err_code: M125'
|
|
738
|
+
'M126': 'clean_gripper_error: M126'
|
|
739
|
+
'M131': 'get_tgpio_digital: M131'
|
|
740
|
+
'M132': 'set_tgpio_digital: M132 I{ionum} V{value}'
|
|
741
|
+
'M133': 'get_tgpio_analog, default ionum=0: M133 I{ionum=0}'
|
|
742
|
+
'M134': 'get_tgpio_analog, default ionum=1: M134 I{ionum=1}'
|
|
743
|
+
'C131': 'get_cgpio_digital: C131'
|
|
744
|
+
'C132': 'get_cgpio_analog, default ionum=0: C132 I{ionum=0}'
|
|
745
|
+
'C133': 'get_cgpio_analog, default ionum=1: C133 I{ionum=1}'
|
|
746
|
+
'C134': 'set_cgpio_digital: C134 I{ionum} V{value}'
|
|
747
|
+
'C135': 'set_cgpio_analog, default ionum=0: C135 I{ionum=0} V{value}'
|
|
748
|
+
'C136': 'set_cgpio_analog, default ionum=1: C136 I{ionum=1} V{value}'
|
|
749
|
+
'C137': 'set_cgpio_digital_input_function: C137 I{ionum} V{fun}'
|
|
750
|
+
'C138': 'set_cgpio_digital_output_function: C138 I{ionum} V{fun}'
|
|
751
|
+
'C139': 'get_cgpio_state: C139'
|
|
752
|
+
:return: code or tuple((code, ...))
|
|
753
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
754
|
+
"""
|
|
755
|
+
return self._arm.send_cmd_sync(command=command)
|
|
756
|
+
|
|
757
|
+
def get_position(self, is_radian=None):
|
|
758
|
+
"""
|
|
759
|
+
Get the cartesian position
|
|
760
|
+
Note:
|
|
761
|
+
1. If the value(roll/pitch/yaw) you want to return is an radian unit, please set the parameter is_radian to True
|
|
762
|
+
ex: code, pos = arm.get_position(is_radian=True)
|
|
763
|
+
|
|
764
|
+
:param is_radian: the returned value (only roll/pitch/yaw) is in radians or not, default is self.default_is_radian
|
|
765
|
+
:return: tuple((code, [x, y, z, roll, pitch, yaw])), only when code is 0, the returned result is correct.
|
|
766
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
767
|
+
"""
|
|
768
|
+
return self._arm.get_position(is_radian=is_radian)
|
|
769
|
+
|
|
770
|
+
def set_position(self, x=None, y=None, z=None, roll=None, pitch=None, yaw=None, radius=None,
|
|
771
|
+
speed=None, mvacc=None, mvtime=None, relative=False, is_radian=None,
|
|
772
|
+
wait=False, timeout=None, **kwargs):
|
|
773
|
+
"""
|
|
774
|
+
Set the cartesian position, the API will modify self.last_used_position value
|
|
775
|
+
Note:
|
|
776
|
+
1. If it is xArm5, ensure that the current robotic arm has a roll value of 180° or π rad and has a roll value of 0 before calling this interface.
|
|
777
|
+
2. If it is xArm5, roll must be set to 180° or π rad, pitch must be set to 0
|
|
778
|
+
3. If the parameter(roll/pitch/yaw) you are passing is an radian unit, be sure to set the parameter is_radian to True.
|
|
779
|
+
ex: code = arm.set_position(x=300, y=0, z=200, roll=-3.14, pitch=0, yaw=0, is_radian=True)
|
|
780
|
+
4. If you want to wait for the robot to complete this action and then return, please set the parameter wait to True.
|
|
781
|
+
ex: code = arm.set_position(x=300, y=0, z=200, roll=180, pitch=0, yaw=0, is_radian=False, wait=True)
|
|
782
|
+
5. This interface is only used in the base coordinate system.
|
|
783
|
+
|
|
784
|
+
:param x: cartesian position x, (unit: mm), default is self.last_used_position[0]
|
|
785
|
+
:param y: cartesian position y, (unit: mm), default is self.last_used_position[1]
|
|
786
|
+
:param z: cartesian position z, (unit: mm), default is self.last_used_position[2]
|
|
787
|
+
:param roll: rotate around the X axis, (unit: rad if is_radian is True else °), default is self.last_used_position[3]
|
|
788
|
+
:param pitch: rotate around the Y axis, (unit: rad if is_radian is True else °), default is self.last_used_position[4]
|
|
789
|
+
:param yaw: rotate around the Z axis, (unit: rad if is_radian is True else °), default is self.last_used_position[5]
|
|
790
|
+
:param radius: move radius, if radius is None or radius less than 0, will MoveLine, else MoveArcLine
|
|
791
|
+
MoveLine: Linear motion
|
|
792
|
+
ex: code = arm.set_position(..., radius=None)
|
|
793
|
+
MoveArcLine: Linear arc motion with interpolation
|
|
794
|
+
ex: code = arm.set_position(..., radius=0)
|
|
795
|
+
Note: Need to set radius>=0
|
|
796
|
+
:param speed: move speed (mm/s, rad/s), default is self.last_used_tcp_speed
|
|
797
|
+
:param mvacc: move acceleration (mm/s^2, rad/s^2), default is self.last_used_tcp_acc
|
|
798
|
+
:param mvtime: 0, reserved
|
|
799
|
+
:param relative: relative move or not
|
|
800
|
+
:param is_radian: the roll/pitch/yaw in radians or not, default is self.default_is_radian
|
|
801
|
+
:param wait: whether to wait for the arm to complete, default is False
|
|
802
|
+
:param timeout: maximum waiting time(unit: second), default is None(no timeout), only valid if wait is True
|
|
803
|
+
:param kwargs: extra parameters
|
|
804
|
+
:param motion_type: motion planning type, default is 0
|
|
805
|
+
motion_type == 0: default, linear planning
|
|
806
|
+
motion_type == 1: prioritize linear planning, and turn to IK for joint planning when linear planning is not possible
|
|
807
|
+
motion_type == 2: direct transfer to IK using joint planning
|
|
808
|
+
Note:
|
|
809
|
+
1. only available if firmware_version >= 1.11.100
|
|
810
|
+
2. when motion_type is 1 or 2, linear motion cannot be guaranteed
|
|
811
|
+
3. once IK is transferred to joint planning, the given Cartesian velocity and acceleration are converted into joint velocity and acceleration according to the percentage
|
|
812
|
+
speed = speed / max_tcp_speed * max_joint_speed
|
|
813
|
+
mvacc = mvacc / max_tcp_acc * max_joint_acc
|
|
814
|
+
4. if there is no suitable IK, a C40 error will be triggered
|
|
815
|
+
:return: code
|
|
816
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
817
|
+
code < 0: the last_used_position/last_used_tcp_speed/last_used_tcp_acc will not be modified
|
|
818
|
+
code >= 0: the last_used_position/last_used_tcp_speed/last_used_tcp_acc will be modified
|
|
819
|
+
"""
|
|
820
|
+
return self._arm.set_position(x=x, y=y, z=z, roll=roll, pitch=pitch, yaw=yaw, radius=radius,
|
|
821
|
+
speed=speed, mvacc=mvacc, mvtime=mvtime, relative=relative,
|
|
822
|
+
is_radian=is_radian, wait=wait, timeout=timeout, **kwargs)
|
|
823
|
+
|
|
824
|
+
def set_tool_position(self, x=0, y=0, z=0, roll=0, pitch=0, yaw=0,
|
|
825
|
+
speed=None, mvacc=None, mvtime=None, is_radian=None,
|
|
826
|
+
wait=False, timeout=None, radius=None, **kwargs):
|
|
827
|
+
"""
|
|
828
|
+
Movement relative to the tool coordinate system
|
|
829
|
+
Note:
|
|
830
|
+
1. This interface is moving relative to the current tool coordinate system
|
|
831
|
+
2. The tool coordinate system is not fixed and varies with position.
|
|
832
|
+
3. This interface is only used in the tool coordinate system.
|
|
833
|
+
|
|
834
|
+
|
|
835
|
+
:param x: the x coordinate relative to the current tool coordinate system, (unit: mm), default is 0
|
|
836
|
+
:param y: the y coordinate relative to the current tool coordinate system, (unit: mm), default is 0
|
|
837
|
+
:param z: the z coordinate relative to the current tool coordinate system, (unit: mm), default is 0
|
|
838
|
+
:param roll: the rotate around the X axis relative to the current tool coordinate system, (unit: rad if is_radian is True else °), default is 0
|
|
839
|
+
:param pitch: the rotate around the Y axis relative to the current tool coordinate system, (unit: rad if is_radian is True else °), default is 0
|
|
840
|
+
:param yaw: the rotate around the Z axis relative to the current tool coordinate system, (unit: rad if is_radian is True else °), default is 0
|
|
841
|
+
:param speed: move speed (mm/s, rad/s), default is self.last_used_tcp_speed
|
|
842
|
+
:param mvacc: move acceleration (mm/s^2, rad/s^2), default is self.last_used_tcp_acc
|
|
843
|
+
:param mvtime: 0, reserved
|
|
844
|
+
:param is_radian: the roll/pitch/yaw in radians or not, default is self.default_is_radian
|
|
845
|
+
:param wait: whether to wait for the arm to complete, default is False
|
|
846
|
+
:param timeout: maximum waiting time(unit: second), default is None(no timeout), only valid if wait is True
|
|
847
|
+
:param radius: move radius, if radius is None or radius less than 0, will MoveToolLine, else MoveToolArcLine
|
|
848
|
+
only available if firmware_version >= 1.11.100
|
|
849
|
+
MoveToolLine: Linear motion
|
|
850
|
+
ex: code = arm.set_tool_position(..., radius=None)
|
|
851
|
+
MoveToolArcLine: Linear arc motion with interpolation
|
|
852
|
+
ex: code = arm.set_tool_position(..., radius=0)
|
|
853
|
+
Note: Need to set radius>=0
|
|
854
|
+
:param kwargs: extra parameters
|
|
855
|
+
:param motion_type: motion planning type, default is 0
|
|
856
|
+
motion_type == 0: default, linear planning
|
|
857
|
+
motion_type == 1: prioritize linear planning, and turn to IK for joint planning when linear planning is not possible
|
|
858
|
+
motion_type == 2: direct transfer to IK using joint planning
|
|
859
|
+
Note:
|
|
860
|
+
1. only available if firmware_version >= 1.11.100
|
|
861
|
+
2. when motion_type is 1 or 2, linear motion cannot be guaranteed
|
|
862
|
+
3. once IK is transferred to joint planning, the given Cartesian velocity and acceleration are converted into joint velocity and acceleration according to the percentage
|
|
863
|
+
speed = speed / max_tcp_speed * max_joint_speed
|
|
864
|
+
mvacc = mvacc / max_tcp_acc * max_joint_acc
|
|
865
|
+
4. if there is no suitable IK, a C40 error will be triggered
|
|
866
|
+
:return: code
|
|
867
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
868
|
+
code < 0: the last_used_tcp_speed/last_used_tcp_acc will not be modified
|
|
869
|
+
code >= 0: the last_used_tcp_speed/last_used_tcp_acc will be modified
|
|
870
|
+
"""
|
|
871
|
+
return self._arm.set_tool_position(x=x, y=y, z=z, roll=roll, pitch=pitch, yaw=yaw,
|
|
872
|
+
speed=speed, mvacc=mvacc, mvtime=mvtime,
|
|
873
|
+
is_radian=is_radian, wait=wait, timeout=timeout, radius=radius, **kwargs)
|
|
874
|
+
|
|
875
|
+
def get_servo_angle(self, servo_id=None, is_radian=None, is_real=False):
|
|
876
|
+
"""
|
|
877
|
+
Get the servo angle
|
|
878
|
+
Note:
|
|
879
|
+
1. If the value you want to return is an radian unit, please set the parameter is_radian to True
|
|
880
|
+
ex: code, angles = arm.get_servo_angle(is_radian=True)
|
|
881
|
+
2. If you want to return only the angle of a single joint, please set the parameter servo_id
|
|
882
|
+
ex: code, angle = arm.get_servo_angle(servo_id=2)
|
|
883
|
+
3. This interface is only used in the base coordinate system.
|
|
884
|
+
|
|
885
|
+
:param servo_id: 1-(Number of axes), None(8), default is None
|
|
886
|
+
:param is_radian: the returned value is in radians or not, default is self.default_is_radian
|
|
887
|
+
:return: tuple((code, angle list if servo_id is None or 8 else angle)), only when code is 0, the returned result is correct.
|
|
888
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
889
|
+
"""
|
|
890
|
+
return self._arm.get_servo_angle(servo_id=servo_id, is_radian=is_radian, is_real=is_real)
|
|
891
|
+
|
|
892
|
+
def set_servo_angle(self, servo_id=None, angle=None, speed=None, mvacc=None, mvtime=None,
|
|
893
|
+
relative=False, is_radian=None, wait=False, timeout=None, radius=None, **kwargs):
|
|
894
|
+
"""
|
|
895
|
+
Set the servo angle, the API will modify self.last_used_angles value
|
|
896
|
+
Note:
|
|
897
|
+
1. If the parameter angle you are passing is an radian unit, be sure to set the parameter is_radian to True.
|
|
898
|
+
ex: code = arm.set_servo_angle(servo_id=1, angle=1.57, is_radian=True)
|
|
899
|
+
2. If you want to wait for the robot to complete this action and then return, please set the parameter wait to True.
|
|
900
|
+
ex: code = arm.set_servo_angle(servo_id=1, angle=45, is_radian=False,wait=True)
|
|
901
|
+
3. This interface is only used in the base coordinate system.
|
|
902
|
+
|
|
903
|
+
:param servo_id: 1-(Number of axes), None(8)
|
|
904
|
+
1. 1-(Number of axes) indicates the corresponding joint, the parameter angle should be a numeric value
|
|
905
|
+
ex: code = arm.set_servo_angle(servo_id=1, angle=45, is_radian=False)
|
|
906
|
+
2. None(8) means all joints, default is None, the parameter angle should be a list of values whose length is the number of joints
|
|
907
|
+
ex: code = arm.set_servo_angle(angle=[30, -45, 0, 0, 0, 0, 0], is_radian=False)
|
|
908
|
+
:param angle: angle or angle list, (unit: rad if is_radian is True else °)
|
|
909
|
+
1. If servo_id is 1-(Number of axes), angle should be a numeric value
|
|
910
|
+
ex: code = arm.set_servo_angle(servo_id=1, angle=45, is_radian=False)
|
|
911
|
+
2. If servo_id is None or 8, angle should be a list of values whose length is the number of joints
|
|
912
|
+
like [axis-1, axis-2, axis-3, axis-3, axis-4, axis-5, axis-6, axis-7]
|
|
913
|
+
ex: code = arm.set_servo_angle(angle=[30, -45, 0, 0, 0, 0, 0], is_radian=False)
|
|
914
|
+
:param speed: move speed (unit: rad/s if is_radian is True else °/s), default is self.last_used_joint_speed
|
|
915
|
+
:param mvacc: move acceleration (unit: rad/s^2 if is_radian is True else °/s^2), default is self.last_used_joint_acc
|
|
916
|
+
:param mvtime: 0, reserved
|
|
917
|
+
:param relative: relative move or not
|
|
918
|
+
:param is_radian: the angle in radians or not, default is self.default_is_radian
|
|
919
|
+
:param wait: whether to wait for the arm to complete, default is False
|
|
920
|
+
:param timeout: maximum waiting time(unit: second), default is None(no timeout), only valid if wait is True
|
|
921
|
+
:param radius: move radius, if radius is None or radius less than 0, will MoveJoint, else MoveArcJoint
|
|
922
|
+
Note: Only available if version > 1.5.20
|
|
923
|
+
Note: The blending radius cannot be greater than the track length.
|
|
924
|
+
MoveJoint: joint motion
|
|
925
|
+
ex: code = arm.set_servo_angle(..., radius=None)
|
|
926
|
+
MoveArcJoint: joint fusion motion with interpolation
|
|
927
|
+
ex: code = arm.set_servo_angle(..., radius=0)
|
|
928
|
+
Note: Need to set radius>=0
|
|
929
|
+
:param kwargs: reserved
|
|
930
|
+
:return: code
|
|
931
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
932
|
+
code < 0: the last_used_angles/last_used_joint_speed/last_used_joint_acc will not be modified
|
|
933
|
+
code >= 0: the last_used_angles/last_used_joint_speed/last_used_joint_acc will be modified
|
|
934
|
+
"""
|
|
935
|
+
return self._arm.set_servo_angle(servo_id=servo_id, angle=angle, speed=speed, mvacc=mvacc, mvtime=mvtime,
|
|
936
|
+
relative=relative, is_radian=is_radian, wait=wait, timeout=timeout, radius=radius, **kwargs)
|
|
937
|
+
|
|
938
|
+
def set_servo_angle_j(self, angles, speed=None, mvacc=None, mvtime=None, is_radian=None, **kwargs):
|
|
939
|
+
"""
|
|
940
|
+
Set the servo angle, execute only the last instruction, need to be set to servo motion mode(self.set_mode(1))
|
|
941
|
+
Note:
|
|
942
|
+
1. This interface does not modify the value of last_used_angles/last_used_joint_speed/last_used_joint_acc
|
|
943
|
+
2. This interface is only used in the base coordinate system.
|
|
944
|
+
|
|
945
|
+
:param angles: angle list, (unit: rad if is_radian is True else °)
|
|
946
|
+
:param speed: speed, reserved
|
|
947
|
+
:param mvacc: acceleration, reserved
|
|
948
|
+
:param mvtime: 0, reserved
|
|
949
|
+
:param is_radian: the angles in radians or not, default is self.default_is_radian
|
|
950
|
+
:param kwargs: reserved
|
|
951
|
+
:return: code
|
|
952
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
953
|
+
"""
|
|
954
|
+
return self._arm.set_servo_angle_j(angles, speed=speed, mvacc=mvacc, mvtime=mvtime, is_radian=is_radian, **kwargs)
|
|
955
|
+
|
|
956
|
+
def set_servo_cartesian(self, mvpose, speed=None, mvacc=None, mvtime=0, is_radian=None, is_tool_coord=False, **kwargs):
|
|
957
|
+
"""
|
|
958
|
+
Set the servo cartesian, execute only the last instruction, need to be set to servo motion mode(self.set_mode(1))
|
|
959
|
+
|
|
960
|
+
:param mvpose: cartesian position, [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
|
|
961
|
+
:param speed: move speed (mm/s), reserved
|
|
962
|
+
:param mvacc: move acceleration (mm/s^2), reserved
|
|
963
|
+
:param mvtime: 0, reserved
|
|
964
|
+
:param is_radian: the roll/pitch/yaw of mvpose in radians or not, default is self.default_is_radian
|
|
965
|
+
:param is_tool_coord: is tool coordinate or not
|
|
966
|
+
:param kwargs: reserved
|
|
967
|
+
:return: code
|
|
968
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
969
|
+
"""
|
|
970
|
+
return self._arm.set_servo_cartesian(mvpose, speed=speed, mvacc=mvacc, mvtime=mvtime, is_radian=is_radian,
|
|
971
|
+
is_tool_coord=is_tool_coord, **kwargs)
|
|
972
|
+
|
|
973
|
+
def move_circle(self, pose1, pose2, percent, speed=None, mvacc=None, mvtime=None, is_radian=None,
|
|
974
|
+
wait=False, timeout=None, is_tool_coord=False, is_axis_angle=False, **kwargs):
|
|
975
|
+
"""
|
|
976
|
+
The motion calculates the trajectory of the space circle according to the three-point coordinates.
|
|
977
|
+
The three-point coordinates are (current starting point, pose1, pose2).
|
|
978
|
+
|
|
979
|
+
:param pose1: cartesian position, [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
|
|
980
|
+
:param pose2: cartesian position, [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
|
|
981
|
+
:param percent: the percentage of arc length and circumference of the movement
|
|
982
|
+
:param speed: move speed (mm/s, rad/s), default is self.last_used_tcp_speed
|
|
983
|
+
:param mvacc: move acceleration (mm/s^2, rad/s^2), default is self.last_used_tcp_acc
|
|
984
|
+
:param mvtime: 0, reserved
|
|
985
|
+
:param is_radian: roll/pitch/yaw value is radians or not, default is self.default_is_radian
|
|
986
|
+
:param wait: whether to wait for the arm to complete, default is False
|
|
987
|
+
:param timeout: maximum waiting time(unit: second), default is None(no timeout), only valid if wait is True
|
|
988
|
+
:param is_tool_coord: is tool coord or not, default is False, only available if firmware_version >= 1.11.100
|
|
989
|
+
:param is_axis_angle: is axis angle or not, default is False, only available if firmware_version >= 1.11.100
|
|
990
|
+
:param kwargs: reserved
|
|
991
|
+
:return: code
|
|
992
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
993
|
+
code < 0: the last_used_tcp_speed/last_used_tcp_acc will not be modified
|
|
994
|
+
code >= 0: the last_used_tcp_speed/last_used_tcp_acc will be modified
|
|
995
|
+
"""
|
|
996
|
+
return self._arm.move_circle(pose1, pose2, percent, speed=speed, mvacc=mvacc, mvtime=mvtime,
|
|
997
|
+
is_radian=is_radian, wait=wait, timeout=timeout,
|
|
998
|
+
is_tool_coord=is_tool_coord, is_axis_angle=is_axis_angle, **kwargs)
|
|
999
|
+
|
|
1000
|
+
def move_gohome(self, speed=None, mvacc=None, mvtime=None, is_radian=None, wait=False, timeout=None, **kwargs):
|
|
1001
|
+
"""
|
|
1002
|
+
Move to go home (Back to zero), the API will modify self.last_used_position and self.last_used_angles value
|
|
1003
|
+
Warnning: without limit detection
|
|
1004
|
+
Note:
|
|
1005
|
+
1. The API will change self.last_used_position value into [201.5, 0, 140.5, -180, 0, 0]
|
|
1006
|
+
2. The API will change self.last_used_angles value into [0, 0, 0, 0, 0, 0, 0]
|
|
1007
|
+
3. If you want to wait for the robot to complete this action and then return, please set the parameter wait to True.
|
|
1008
|
+
ex: code = arm.move_gohome(wait=True)
|
|
1009
|
+
4. This interface does not modify the value of last_used_angles/last_used_joint_speed/last_used_joint_acc
|
|
1010
|
+
|
|
1011
|
+
:param speed: gohome speed (unit: rad/s if is_radian is True else °/s), default is 50 °/s
|
|
1012
|
+
:param mvacc: gohome acceleration (unit: rad/s^2 if is_radian is True else °/s^2), default is 5000 °/s^2
|
|
1013
|
+
:param mvtime: reserved
|
|
1014
|
+
:param is_radian: the speed and acceleration are in radians or not, default is self.default_is_radian
|
|
1015
|
+
:param wait: whether to wait for the arm to complete, default is False
|
|
1016
|
+
:param timeout: maximum waiting time(unit: second), default is None(no timeout), only valid if wait is True
|
|
1017
|
+
:return: code
|
|
1018
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1019
|
+
"""
|
|
1020
|
+
return self._arm.move_gohome(speed=speed, mvacc=mvacc, mvtime=mvtime, is_radian=is_radian, wait=wait, timeout=timeout, **kwargs)
|
|
1021
|
+
|
|
1022
|
+
def move_arc_lines(self, paths, is_radian=None, times=1, first_pause_time=0.1, repeat_pause_time=0,
|
|
1023
|
+
automatic_calibration=True, speed=None, mvacc=None, mvtime=None, wait=False):
|
|
1024
|
+
"""
|
|
1025
|
+
Continuous linear motion with interpolation.
|
|
1026
|
+
Note:
|
|
1027
|
+
1. If an error occurs, it will return early.
|
|
1028
|
+
2. If the emergency_stop interface is called actively, it will return early.
|
|
1029
|
+
3. The last_used_position/last_used_tcp_speed/last_used_tcp_acc will be modified.
|
|
1030
|
+
4. The last_used_angles/last_used_joint_speed/last_used_joint_acc will not be modified.
|
|
1031
|
+
|
|
1032
|
+
:param paths: cartesian path list
|
|
1033
|
+
1. Specify arc radius: [[x, y, z, roll, pitch, yaw, radius], ....]
|
|
1034
|
+
2. Do not specify arc radius (radius=0): [[x, y, z, roll, pitch, yaw], ....]
|
|
1035
|
+
3. If you want to plan the continuous motion,set radius>0.
|
|
1036
|
+
|
|
1037
|
+
:param is_radian: roll/pitch/yaw of paths are in radians or not, default is self.default_is_radian
|
|
1038
|
+
:param times: repeat times, 0 is infinite loop, default is 1
|
|
1039
|
+
:param first_pause_time: sleep time at first, purpose is to cache the commands and plan continuous motion, default is 0.1s
|
|
1040
|
+
:param repeat_pause_time: interval between repeated movements, unit: (s)second
|
|
1041
|
+
:param automatic_calibration: automatic calibration or not, default is True
|
|
1042
|
+
:param speed: move speed (mm/s, rad/s), default is self.last_used_tcp_speed
|
|
1043
|
+
:param mvacc: move acceleration (mm/s^2, rad/s^2), default is self.last_used_tcp_acc
|
|
1044
|
+
:param mvtime: 0, reserved
|
|
1045
|
+
:param wait: whether to wait for the arm to complete, default is False
|
|
1046
|
+
"""
|
|
1047
|
+
return self._arm.move_arc_lines(paths, is_radian=is_radian, times=times, first_pause_time=first_pause_time,
|
|
1048
|
+
repeat_pause_time=repeat_pause_time, automatic_calibration=automatic_calibration,
|
|
1049
|
+
speed=speed, mvacc=mvacc, mvtime=mvtime, wait=wait)
|
|
1050
|
+
|
|
1051
|
+
def set_servo_attach(self, servo_id=None):
|
|
1052
|
+
"""
|
|
1053
|
+
Attach the servo
|
|
1054
|
+
|
|
1055
|
+
:param servo_id: 1-(Number of axes), 8, if servo_id is 8, will attach all servo
|
|
1056
|
+
1. 1-(Number of axes): attach only one joint
|
|
1057
|
+
ex: arm.set_servo_attach(servo_id=1)
|
|
1058
|
+
2: 8: attach all joints
|
|
1059
|
+
ex: arm.set_servo_attach(servo_id=8)
|
|
1060
|
+
:return: code
|
|
1061
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1062
|
+
"""
|
|
1063
|
+
return self._arm.set_servo_attach(servo_id=servo_id)
|
|
1064
|
+
|
|
1065
|
+
def set_servo_detach(self, servo_id=None):
|
|
1066
|
+
"""
|
|
1067
|
+
Detach the servo, be sure to do protective work before unlocking to avoid injury or damage.
|
|
1068
|
+
|
|
1069
|
+
:param servo_id: 1-(Number of axes), 8, if servo_id is 8, will detach all servo
|
|
1070
|
+
1. 1-(Number of axes): detach only one joint
|
|
1071
|
+
ex: arm.set_servo_detach(servo_id=1)
|
|
1072
|
+
2: 8: detach all joints, please
|
|
1073
|
+
ex: arm.set_servo_detach(servo_id=8)
|
|
1074
|
+
:return: code
|
|
1075
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1076
|
+
"""
|
|
1077
|
+
return self._arm.set_servo_detach(servo_id=servo_id)
|
|
1078
|
+
|
|
1079
|
+
def get_version(self):
|
|
1080
|
+
"""
|
|
1081
|
+
Get the xArm firmware version
|
|
1082
|
+
|
|
1083
|
+
:return: tuple((code, version)), only when code is 0, the returned result is correct.
|
|
1084
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1085
|
+
"""
|
|
1086
|
+
return self._arm.get_version()
|
|
1087
|
+
|
|
1088
|
+
def get_robot_sn(self):
|
|
1089
|
+
"""
|
|
1090
|
+
Get the xArm sn
|
|
1091
|
+
|
|
1092
|
+
:return: tuple((code, sn)), only when code is 0, the returned result is correct.
|
|
1093
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1094
|
+
"""
|
|
1095
|
+
return self._arm.get_robot_sn()
|
|
1096
|
+
|
|
1097
|
+
def check_verification(self):
|
|
1098
|
+
"""
|
|
1099
|
+
check verification
|
|
1100
|
+
|
|
1101
|
+
:return: tuple((code, status)), only when code is 0, the returned result is correct.
|
|
1102
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1103
|
+
status:
|
|
1104
|
+
0: verified
|
|
1105
|
+
other: not verified
|
|
1106
|
+
"""
|
|
1107
|
+
return self._arm.check_verification()
|
|
1108
|
+
|
|
1109
|
+
def system_control(self, value=1):
|
|
1110
|
+
"""
|
|
1111
|
+
Control the xArm controller system
|
|
1112
|
+
|
|
1113
|
+
:param value: 1: shutdown, 2: reboot
|
|
1114
|
+
:return: code
|
|
1115
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1116
|
+
"""
|
|
1117
|
+
return self._arm.system_control(value=value)
|
|
1118
|
+
|
|
1119
|
+
def get_trajectories(self):
|
|
1120
|
+
"""
|
|
1121
|
+
get the trajectories
|
|
1122
|
+
|
|
1123
|
+
Note:
|
|
1124
|
+
1. This interface relies on xArmStudio 1.2.0 or above
|
|
1125
|
+
2. This interface relies on Firmware 1.2.0 or above
|
|
1126
|
+
|
|
1127
|
+
:return: tuple((code, trajectories))
|
|
1128
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1129
|
+
trajectories: [{
|
|
1130
|
+
'name': name, # The name of the trajectory
|
|
1131
|
+
'duration': duration, # The duration of the trajectory (seconds)
|
|
1132
|
+
}]
|
|
1133
|
+
"""
|
|
1134
|
+
return self._arm.get_trajectories()
|
|
1135
|
+
|
|
1136
|
+
def start_record_trajectory(self):
|
|
1137
|
+
"""
|
|
1138
|
+
Start trajectory recording, only in teach mode, so you need to set joint teaching mode before.
|
|
1139
|
+
|
|
1140
|
+
Note:
|
|
1141
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1142
|
+
2. set joint teaching mode: set_mode(2);set_state(0)
|
|
1143
|
+
|
|
1144
|
+
:return: code
|
|
1145
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1146
|
+
"""
|
|
1147
|
+
return self._arm.start_record_trajectory()
|
|
1148
|
+
|
|
1149
|
+
def stop_record_trajectory(self, filename=None, **kwargs):
|
|
1150
|
+
"""
|
|
1151
|
+
Stop trajectory recording
|
|
1152
|
+
|
|
1153
|
+
Note:
|
|
1154
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1155
|
+
|
|
1156
|
+
:param filename: The name to save
|
|
1157
|
+
1. Only strings consisting of English or numbers are supported, and the length is no more than 50.
|
|
1158
|
+
2. The trajectory is saved in the controller box.
|
|
1159
|
+
3. If the filename is None, just stop recording, do not save, you need to manually call `save_record_trajectory` save before changing the mode. otherwise it will be lost
|
|
1160
|
+
4. This action will overwrite the trajectory with the same name
|
|
1161
|
+
5. Empty the trajectory in memory after saving
|
|
1162
|
+
:return: code
|
|
1163
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1164
|
+
"""
|
|
1165
|
+
return self._arm.stop_record_trajectory(filename=filename, **kwargs)
|
|
1166
|
+
|
|
1167
|
+
def get_record_seconds(self):
|
|
1168
|
+
"""
|
|
1169
|
+
Get record seconds
|
|
1170
|
+
Note:
|
|
1171
|
+
1. Only available if firmware_version >= 2.4.0
|
|
1172
|
+
2. Only valid during recording or after recording but before saving
|
|
1173
|
+
|
|
1174
|
+
:return: tuple((code, seconds)), only when code is 0, the returned result is correct.
|
|
1175
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1176
|
+
seconds: The actual duration of the recorded track
|
|
1177
|
+
"""
|
|
1178
|
+
ret = self._arm.get_common_info(50, return_val=True)
|
|
1179
|
+
return ret
|
|
1180
|
+
|
|
1181
|
+
def save_record_trajectory(self, filename, wait=True, timeout=5, **kwargs):
|
|
1182
|
+
"""
|
|
1183
|
+
Save the trajectory you just recorded
|
|
1184
|
+
|
|
1185
|
+
Note:
|
|
1186
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1187
|
+
|
|
1188
|
+
:param filename: The name to save
|
|
1189
|
+
1. Only strings consisting of English or numbers are supported, and the length is no more than 50.
|
|
1190
|
+
2. The trajectory is saved in the controller box.
|
|
1191
|
+
3. This action will overwrite the trajectory with the same name
|
|
1192
|
+
4. Empty the trajectory in memory after saving, so repeated calls will cause the recorded trajectory to be covered by an empty trajectory.
|
|
1193
|
+
:param wait: Whether to wait for saving, default is True
|
|
1194
|
+
:param timeout: Timeout waiting for saving to complete
|
|
1195
|
+
:return: code
|
|
1196
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1197
|
+
"""
|
|
1198
|
+
return self._arm.save_record_trajectory(filename, wait=wait, timeout=timeout, **kwargs)
|
|
1199
|
+
|
|
1200
|
+
def load_trajectory(self, filename, wait=True, timeout=None, **kwargs):
|
|
1201
|
+
"""
|
|
1202
|
+
Load the trajectory
|
|
1203
|
+
|
|
1204
|
+
Note:
|
|
1205
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1206
|
+
|
|
1207
|
+
:param filename: The name of the trajectory to load
|
|
1208
|
+
:param wait: Whether to wait for loading, default is True
|
|
1209
|
+
:param timeout: Timeout waiting for loading to complete
|
|
1210
|
+
:return: code
|
|
1211
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1212
|
+
"""
|
|
1213
|
+
return self._arm.load_trajectory(filename, wait=wait, timeout=timeout, **kwargs)
|
|
1214
|
+
|
|
1215
|
+
def playback_trajectory(self, times=1, filename=None, wait=True, double_speed=1, **kwargs):
|
|
1216
|
+
"""
|
|
1217
|
+
Playback trajectory
|
|
1218
|
+
|
|
1219
|
+
Note:
|
|
1220
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1221
|
+
|
|
1222
|
+
:param times: Number of playbacks,
|
|
1223
|
+
1. Only valid when the current position of the arm is the end position of the track, otherwise it will only be played once.
|
|
1224
|
+
:param filename: The name of the trajectory to play back
|
|
1225
|
+
1. If filename is None, you need to manually call the `load_trajectory` to load the trajectory.
|
|
1226
|
+
:param wait: whether to wait for the arm to complete, default is False
|
|
1227
|
+
:param double_speed: double speed, only support 1/2/4, default is 1, only available if version > 1.2.11
|
|
1228
|
+
:return: code
|
|
1229
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1230
|
+
"""
|
|
1231
|
+
return self._arm.playback_trajectory(times=times, filename=filename, wait=wait, double_speed=double_speed, **kwargs)
|
|
1232
|
+
|
|
1233
|
+
def get_trajectory_rw_status(self):
|
|
1234
|
+
"""
|
|
1235
|
+
Get trajectory read/write status
|
|
1236
|
+
|
|
1237
|
+
:return: (code, status)
|
|
1238
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1239
|
+
status:
|
|
1240
|
+
0: no read/write
|
|
1241
|
+
1: loading
|
|
1242
|
+
2: load success
|
|
1243
|
+
3: load failed
|
|
1244
|
+
4: saving
|
|
1245
|
+
5: save success
|
|
1246
|
+
6: save failed
|
|
1247
|
+
"""
|
|
1248
|
+
return self._arm.get_trajectory_rw_status()
|
|
1249
|
+
|
|
1250
|
+
def get_reduced_mode(self):
|
|
1251
|
+
"""
|
|
1252
|
+
Get reduced mode
|
|
1253
|
+
|
|
1254
|
+
Note:
|
|
1255
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1256
|
+
|
|
1257
|
+
:return: tuple((code, mode))
|
|
1258
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1259
|
+
mode: 0 or 1, 1 means that the reduced mode is turned on. 0 means that the reduced mode is not turned on
|
|
1260
|
+
"""
|
|
1261
|
+
return self._arm.get_reduced_mode()
|
|
1262
|
+
|
|
1263
|
+
def get_reduced_states(self, is_radian=None):
|
|
1264
|
+
"""
|
|
1265
|
+
Get states of the reduced mode
|
|
1266
|
+
|
|
1267
|
+
Note:
|
|
1268
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1269
|
+
|
|
1270
|
+
:param is_radian: the max_joint_speed of the states is in radians or not, default is self.default_is_radian
|
|
1271
|
+
:return: tuple((code, states))
|
|
1272
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1273
|
+
states: [....]
|
|
1274
|
+
if version > 1.2.11:
|
|
1275
|
+
states: [
|
|
1276
|
+
reduced_mode_is_on,
|
|
1277
|
+
[reduced_x_max, reduced_x_min, reduced_y_max, reduced_y_min, reduced_z_max, reduced_z_min],
|
|
1278
|
+
reduced_max_tcp_speed,
|
|
1279
|
+
reduced_max_joint_speed,
|
|
1280
|
+
joint_ranges([joint-1-min, joint-1-max, ..., joint-7-min, joint-7-max]),
|
|
1281
|
+
safety_boundary_is_on,
|
|
1282
|
+
collision_rebound_is_on,
|
|
1283
|
+
]
|
|
1284
|
+
if version <= 1.2.11:
|
|
1285
|
+
states: [
|
|
1286
|
+
reduced_mode_is_on,
|
|
1287
|
+
[reduced_x_max, reduced_x_min, reduced_y_max, reduced_y_min, reduced_z_max, reduced_z_min],
|
|
1288
|
+
reduced_max_tcp_speed,
|
|
1289
|
+
reduced_max_joint_speed,
|
|
1290
|
+
]
|
|
1291
|
+
"""
|
|
1292
|
+
return self._arm.get_reduced_states(is_radian=is_radian)
|
|
1293
|
+
|
|
1294
|
+
def set_reduced_mode(self, on):
|
|
1295
|
+
"""
|
|
1296
|
+
Turn on/off reduced mode
|
|
1297
|
+
|
|
1298
|
+
Note:
|
|
1299
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1300
|
+
|
|
1301
|
+
:param on: True/False
|
|
1302
|
+
such as:Turn on the reduced mode : code=arm.set_reduced_mode(True)
|
|
1303
|
+
:return: code
|
|
1304
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1305
|
+
"""
|
|
1306
|
+
return self._arm.set_reduced_mode(on)
|
|
1307
|
+
|
|
1308
|
+
def set_reduced_max_tcp_speed(self, speed):
|
|
1309
|
+
"""
|
|
1310
|
+
Set the maximum tcp speed of the reduced mode
|
|
1311
|
+
|
|
1312
|
+
Note:
|
|
1313
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1314
|
+
2. Only reset the reduced mode to take effect (`set_reduced_mode(True)`)
|
|
1315
|
+
|
|
1316
|
+
:param speed: speed (mm/s)
|
|
1317
|
+
:return: code
|
|
1318
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1319
|
+
"""
|
|
1320
|
+
return self._arm.set_reduced_max_tcp_speed(speed)
|
|
1321
|
+
|
|
1322
|
+
def set_reduced_max_joint_speed(self, speed, is_radian=None):
|
|
1323
|
+
"""
|
|
1324
|
+
Set the maximum joint speed of the reduced mode
|
|
1325
|
+
|
|
1326
|
+
Note:
|
|
1327
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1328
|
+
2. Only reset the reduced mode to take effect (`set_reduced_mode(True)`)
|
|
1329
|
+
|
|
1330
|
+
:param speed: speed (°/s or rad/s)
|
|
1331
|
+
:param is_radian: the speed is in radians or not, default is self.default_is_radian
|
|
1332
|
+
:return: code
|
|
1333
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1334
|
+
"""
|
|
1335
|
+
return self._arm.set_reduced_max_joint_speed(speed, is_radian=is_radian)
|
|
1336
|
+
|
|
1337
|
+
def set_reduced_tcp_boundary(self, boundary):
|
|
1338
|
+
"""
|
|
1339
|
+
Set the boundary of the safety boundary mode
|
|
1340
|
+
|
|
1341
|
+
Note:
|
|
1342
|
+
1. This interface relies on Firmware 1.2.0 or above
|
|
1343
|
+
2. Only reset the reduced mode to take effect (`set_reduced_mode(True)`)
|
|
1344
|
+
|
|
1345
|
+
:param boundary: [x_max, x_min, y_max, y_min, z_max, z_min]
|
|
1346
|
+
:return: code
|
|
1347
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1348
|
+
"""
|
|
1349
|
+
return self._arm.set_reduced_tcp_boundary(boundary)
|
|
1350
|
+
|
|
1351
|
+
def set_reduced_joint_range(self, joint_range, is_radian=None):
|
|
1352
|
+
"""
|
|
1353
|
+
Set the joint range of the reduced mode
|
|
1354
|
+
|
|
1355
|
+
Note:
|
|
1356
|
+
1. This interface relies on Firmware 1.2.11 or above
|
|
1357
|
+
2. Only reset the reduced mode to take effect (`set_reduced_mode(True)`)
|
|
1358
|
+
|
|
1359
|
+
:param joint_range: [joint-1-min, joint-1-max, ..., joint-7-min, joint-7-max]
|
|
1360
|
+
:param is_radian: the param joint_range are in radians or not, default is self.default_is_radian
|
|
1361
|
+
:return:
|
|
1362
|
+
"""
|
|
1363
|
+
return self._arm.set_reduced_joint_range(joint_range, is_radian=is_radian)
|
|
1364
|
+
|
|
1365
|
+
def set_fence_mode(self, on):
|
|
1366
|
+
"""
|
|
1367
|
+
Set the fence mode,turn on/off fense mode
|
|
1368
|
+
|
|
1369
|
+
Note:
|
|
1370
|
+
1. This interface relies on Firmware 1.2.11 or above
|
|
1371
|
+
|
|
1372
|
+
:param on: True/False
|
|
1373
|
+
:return: code
|
|
1374
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1375
|
+
"""
|
|
1376
|
+
return self._arm.set_fense_mode(on)
|
|
1377
|
+
|
|
1378
|
+
def set_collision_rebound(self, on):
|
|
1379
|
+
"""
|
|
1380
|
+
Set the collision rebound,turn on/off collision rebound
|
|
1381
|
+
|
|
1382
|
+
Note:
|
|
1383
|
+
1. This interface relies on Firmware 1.2.11 or above
|
|
1384
|
+
|
|
1385
|
+
:param on: True/False
|
|
1386
|
+
:return: code
|
|
1387
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1388
|
+
"""
|
|
1389
|
+
return self._arm.set_collision_rebound(on)
|
|
1390
|
+
|
|
1391
|
+
def set_world_offset(self, offset, is_radian=None, wait=True):
|
|
1392
|
+
"""
|
|
1393
|
+
Set the base coordinate offset
|
|
1394
|
+
|
|
1395
|
+
Note:
|
|
1396
|
+
1. This interface relies on Firmware 1.2.11 or above
|
|
1397
|
+
|
|
1398
|
+
:param offset: [x, y, z, roll, pitch, yaw]
|
|
1399
|
+
:param is_radian: the roll/pitch/yaw in radians or not, default is self.default_is_radian
|
|
1400
|
+
:param wait: whether to wait for the robotic arm to stop or all previous queue commands to be executed or cleared before setting
|
|
1401
|
+
:return: code
|
|
1402
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1403
|
+
"""
|
|
1404
|
+
return self._arm.set_world_offset(offset, is_radian=is_radian, wait=wait)
|
|
1405
|
+
|
|
1406
|
+
def get_is_moving(self):
|
|
1407
|
+
"""
|
|
1408
|
+
Check xArm is moving or not
|
|
1409
|
+
:return: True/False
|
|
1410
|
+
"""
|
|
1411
|
+
return self._arm.get_is_moving()
|
|
1412
|
+
|
|
1413
|
+
def get_state(self):
|
|
1414
|
+
"""
|
|
1415
|
+
Get state
|
|
1416
|
+
|
|
1417
|
+
:return: tuple((code, state)), only when code is 0, the returned result is correct.
|
|
1418
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1419
|
+
state:
|
|
1420
|
+
1: in motion
|
|
1421
|
+
2: sleeping
|
|
1422
|
+
3: suspended
|
|
1423
|
+
4: stopping
|
|
1424
|
+
"""
|
|
1425
|
+
return self._arm.get_state()
|
|
1426
|
+
|
|
1427
|
+
def set_state(self, state=0):
|
|
1428
|
+
"""
|
|
1429
|
+
Set the xArm state
|
|
1430
|
+
|
|
1431
|
+
:param state: default is 0
|
|
1432
|
+
0: sport state
|
|
1433
|
+
3: pause state
|
|
1434
|
+
4: stop state
|
|
1435
|
+
:return: code
|
|
1436
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1437
|
+
"""
|
|
1438
|
+
return self._arm.set_state(state=state)
|
|
1439
|
+
|
|
1440
|
+
def set_mode(self, mode=0, detection_param=0):
|
|
1441
|
+
"""
|
|
1442
|
+
Set the xArm mode
|
|
1443
|
+
|
|
1444
|
+
:param mode: default is 0
|
|
1445
|
+
0: position control mode
|
|
1446
|
+
1: servo motion mode
|
|
1447
|
+
Note: the use of the set_servo_angle_j interface must first be set to this mode
|
|
1448
|
+
Note: the use of the set_servo_cartesian interface must first be set to this mode
|
|
1449
|
+
2: joint teaching mode
|
|
1450
|
+
Note: use this mode to ensure that the arm has been identified and the control box and arm used for identification are one-to-one.
|
|
1451
|
+
3: cartesian teaching mode (invalid)
|
|
1452
|
+
4: joint velocity control mode
|
|
1453
|
+
5: cartesian velocity control mode
|
|
1454
|
+
6: joint online trajectory planning mode
|
|
1455
|
+
7: cartesian online trajectory planning mode
|
|
1456
|
+
:param detection_param: Teaching detection parameters, default is 0
|
|
1457
|
+
0: Turn on motion detection
|
|
1458
|
+
1: Turn off motion detection
|
|
1459
|
+
Note:
|
|
1460
|
+
1. only available if firmware_version >= 1.10.1
|
|
1461
|
+
2. only available if set_mode(2)
|
|
1462
|
+
:return: code
|
|
1463
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1464
|
+
"""
|
|
1465
|
+
return self._arm.set_mode(mode=mode, detection_param=detection_param)
|
|
1466
|
+
|
|
1467
|
+
def get_cmdnum(self):
|
|
1468
|
+
"""
|
|
1469
|
+
Get the cmd count in cache
|
|
1470
|
+
:return: tuple((code, cmd_num)), only when code is 0, the returned result is correct.
|
|
1471
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1472
|
+
"""
|
|
1473
|
+
return self._arm.get_cmdnum()
|
|
1474
|
+
|
|
1475
|
+
def get_err_warn_code(self, show=False, lang='en'):
|
|
1476
|
+
"""
|
|
1477
|
+
Get the controller error and warn code
|
|
1478
|
+
|
|
1479
|
+
:param show: show the detail info if True
|
|
1480
|
+
:param lang: show language, en/cn, degault is en, only available if show is True
|
|
1481
|
+
:return: tuple((code, [error_code, warn_code])), only when code is 0, the returned result is correct.
|
|
1482
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1483
|
+
error_code: See the [Controller Error Code Documentation](./xarm_api_code.md#controller-error-code) for details.
|
|
1484
|
+
warn_code: See the [Controller Error Code Documentation](./xarm_api_code.md#controller-warn-code) for details.
|
|
1485
|
+
"""
|
|
1486
|
+
return self._arm.get_err_warn_code(show=show, lang=lang)
|
|
1487
|
+
|
|
1488
|
+
def clean_error(self):
|
|
1489
|
+
"""
|
|
1490
|
+
Clean the error, need to be manually enabled motion(arm.motion_enable(True)) and set state(arm.set_state(state=0))after clean error
|
|
1491
|
+
|
|
1492
|
+
:return: code
|
|
1493
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1494
|
+
"""
|
|
1495
|
+
return self._arm.clean_error()
|
|
1496
|
+
|
|
1497
|
+
def clean_warn(self):
|
|
1498
|
+
"""
|
|
1499
|
+
Clean the warn
|
|
1500
|
+
|
|
1501
|
+
:return: code
|
|
1502
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1503
|
+
"""
|
|
1504
|
+
return self._arm.clean_warn()
|
|
1505
|
+
|
|
1506
|
+
def motion_enable(self, enable=True, servo_id=None):
|
|
1507
|
+
"""
|
|
1508
|
+
Motion enable
|
|
1509
|
+
|
|
1510
|
+
:param enable:True/False
|
|
1511
|
+
:param servo_id: 1-(Number of axes), None(8)
|
|
1512
|
+
:return: code
|
|
1513
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1514
|
+
"""
|
|
1515
|
+
return self._arm.motion_enable(servo_id=servo_id, enable=enable)
|
|
1516
|
+
|
|
1517
|
+
def reset(self, speed=None, mvacc=None, mvtime=None, is_radian=None, wait=False, timeout=None):
|
|
1518
|
+
"""
|
|
1519
|
+
Reset the xArm
|
|
1520
|
+
Warnning: without limit detection
|
|
1521
|
+
Note:
|
|
1522
|
+
1. If there are errors or warnings, this interface will clear the warnings and errors.
|
|
1523
|
+
2. If not ready, the api will auto enable motion and set state
|
|
1524
|
+
3. This interface does not modify the value of last_used_angles/last_used_joint_speed/last_used_joint_acc
|
|
1525
|
+
|
|
1526
|
+
:param speed: reset speed (unit: rad/s if is_radian is True else °/s), default is 50 °/s
|
|
1527
|
+
:param mvacc: reset acceleration (unit: rad/s^2 if is_radian is True else °/s^2), default is 5000 °/s^2
|
|
1528
|
+
:param mvtime: reserved
|
|
1529
|
+
:param is_radian: the speed and acceleration are in radians or not, default is self.default_is_radian
|
|
1530
|
+
:param wait: whether to wait for the arm to complete, default is False
|
|
1531
|
+
:param timeout: maximum waiting time(unit: second), default is None(no timeout), only valid if wait is True
|
|
1532
|
+
"""
|
|
1533
|
+
return self._arm.reset(speed=speed, mvacc=mvacc, mvtime=mvtime, is_radian=is_radian, wait=wait, timeout=timeout)
|
|
1534
|
+
|
|
1535
|
+
def set_pause_time(self, sltime, wait=False):
|
|
1536
|
+
"""
|
|
1537
|
+
Set the arm pause time, xArm will pause sltime second
|
|
1538
|
+
|
|
1539
|
+
:param sltime: sleep time,unit:(s)second
|
|
1540
|
+
:param wait: wait or not, default is False
|
|
1541
|
+
:return: code
|
|
1542
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1543
|
+
"""
|
|
1544
|
+
return self._arm.set_pause_time(sltime, wait=wait)
|
|
1545
|
+
|
|
1546
|
+
def set_tcp_offset(self, offset, is_radian=None, wait=True, **kwargs):
|
|
1547
|
+
"""
|
|
1548
|
+
Set the tool coordinate system offset at the end
|
|
1549
|
+
Note:
|
|
1550
|
+
1. Do not use if not required
|
|
1551
|
+
2. If not saved and you want to revert to the last saved value, please reset the offset by set_tcp_offset([0, 0, 0, 0, 0, 0])
|
|
1552
|
+
3. If not saved, it will be lost after reboot
|
|
1553
|
+
4. The save_conf interface can record the current settings and will not be lost after the restart.
|
|
1554
|
+
5. The clean_conf interface can restore system default settings
|
|
1555
|
+
|
|
1556
|
+
:param offset: [x, y, z, roll, pitch, yaw]
|
|
1557
|
+
:param is_radian: the roll/pitch/yaw in radians or not, default is self.default_is_radian
|
|
1558
|
+
:param wait: whether to wait for the robotic arm to stop or all previous queue commands to be executed or cleared before setting
|
|
1559
|
+
:return: code
|
|
1560
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1561
|
+
"""
|
|
1562
|
+
return self._arm.set_tcp_offset(offset, is_radian=is_radian, wait=wait, **kwargs)
|
|
1563
|
+
|
|
1564
|
+
def set_tcp_jerk(self, jerk):
|
|
1565
|
+
"""
|
|
1566
|
+
Set the translational jerk of Cartesian space
|
|
1567
|
+
Note:
|
|
1568
|
+
1. Do not use if not required
|
|
1569
|
+
2. If not saved, it will be lost after reboot
|
|
1570
|
+
3. The save_conf interface can record the current settings and will not be lost after the restart.
|
|
1571
|
+
4. The clean_conf interface can restore system default settings
|
|
1572
|
+
|
|
1573
|
+
:param jerk: jerk (mm/s^3)
|
|
1574
|
+
:return: code
|
|
1575
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1576
|
+
"""
|
|
1577
|
+
return self._arm.set_tcp_jerk(jerk)
|
|
1578
|
+
|
|
1579
|
+
def set_tcp_maxacc(self, acc):
|
|
1580
|
+
"""
|
|
1581
|
+
Set the max translational acceleration of Cartesian space
|
|
1582
|
+
Note:
|
|
1583
|
+
1. Do not use if not required
|
|
1584
|
+
2. If not saved, it will be lost after reboot
|
|
1585
|
+
3. The save_conf interface can record the current settings and will not be lost after the restart.
|
|
1586
|
+
4. The clean_conf interface can restore system default settings
|
|
1587
|
+
|
|
1588
|
+
:param acc: max acceleration (mm/s^2)
|
|
1589
|
+
:return: code
|
|
1590
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1591
|
+
"""
|
|
1592
|
+
return self._arm.set_tcp_maxacc(acc)
|
|
1593
|
+
|
|
1594
|
+
def set_joint_jerk(self, jerk, is_radian=None):
|
|
1595
|
+
"""
|
|
1596
|
+
Set the jerk of Joint space
|
|
1597
|
+
Note:
|
|
1598
|
+
1. Do not use if not required
|
|
1599
|
+
2. If not saved, it will be lost after reboot
|
|
1600
|
+
3. The save_conf interface can record the current settings and will not be lost after the restart.
|
|
1601
|
+
4. The clean_conf interface can restore system default settings
|
|
1602
|
+
|
|
1603
|
+
:param jerk: jerk (°/s^3 or rad/s^3)
|
|
1604
|
+
:param is_radian: the jerk in radians or not, default is self.default_is_radian
|
|
1605
|
+
:return: code
|
|
1606
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1607
|
+
"""
|
|
1608
|
+
return self._arm.set_joint_jerk(jerk, is_radian=is_radian)
|
|
1609
|
+
|
|
1610
|
+
def set_joint_maxacc(self, acc, is_radian=None):
|
|
1611
|
+
"""
|
|
1612
|
+
Set the max acceleration of Joint space
|
|
1613
|
+
|
|
1614
|
+
Note:
|
|
1615
|
+
1. Do not use if not required
|
|
1616
|
+
2. If not saved, it will be lost after reboot
|
|
1617
|
+
3. The save_conf interface can record the current settings and will not be lost after the restart.
|
|
1618
|
+
4. The clean_conf interface can restore system default settings
|
|
1619
|
+
|
|
1620
|
+
:param acc: max acceleration (°/s^2 or rad/s^2)
|
|
1621
|
+
:param is_radian: the jerk in radians or not, default is self.default_is_radian
|
|
1622
|
+
:return: code
|
|
1623
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1624
|
+
"""
|
|
1625
|
+
return self._arm.set_joint_maxacc(acc, is_radian=is_radian)
|
|
1626
|
+
|
|
1627
|
+
def set_tcp_load(self, weight, center_of_gravity, wait=False, **kwargs):
|
|
1628
|
+
"""
|
|
1629
|
+
Set the end load of xArm
|
|
1630
|
+
|
|
1631
|
+
Note:
|
|
1632
|
+
1. Do not use if not required
|
|
1633
|
+
2. If not saved, it will be lost after reboot
|
|
1634
|
+
3. The save_conf interface can record the current settings and will not be lost after the restart.
|
|
1635
|
+
4. The clean_conf interface can restore system default settings
|
|
1636
|
+
|
|
1637
|
+
:param weight: load weight (unit: kg)
|
|
1638
|
+
:param center_of_gravity: load center of gravity, such as [x(mm), y(mm), z(mm)]
|
|
1639
|
+
:param wait: whether to wait for the command to be executed or the the robotic arm to stop
|
|
1640
|
+
:return: code
|
|
1641
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1642
|
+
"""
|
|
1643
|
+
return self._arm.set_tcp_load(weight, center_of_gravity, wait=wait, **kwargs)
|
|
1644
|
+
|
|
1645
|
+
def set_collision_sensitivity(self, value, wait=True):
|
|
1646
|
+
"""
|
|
1647
|
+
Set the sensitivity of collision
|
|
1648
|
+
|
|
1649
|
+
Note:
|
|
1650
|
+
1. Do not use if not required
|
|
1651
|
+
2. If not saved, it will be lost after reboot
|
|
1652
|
+
3. The save_conf interface can record the current settings and will not be lost after the restart.
|
|
1653
|
+
4. The clean_conf interface can restore system default settings
|
|
1654
|
+
|
|
1655
|
+
:param value: sensitivity value, 0~5
|
|
1656
|
+
:param wait: reversed
|
|
1657
|
+
:return: code
|
|
1658
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1659
|
+
"""
|
|
1660
|
+
return self._arm.set_collision_sensitivity(value, wait=wait)
|
|
1661
|
+
|
|
1662
|
+
def set_teach_sensitivity(self, value, wait=True):
|
|
1663
|
+
"""
|
|
1664
|
+
Set the sensitivity of drag and teach
|
|
1665
|
+
|
|
1666
|
+
Note:
|
|
1667
|
+
1. Do not use if not required
|
|
1668
|
+
2. If not saved, it will be lost after reboot
|
|
1669
|
+
3. The save_conf interface can record the current settings and will not be lost after the restart.
|
|
1670
|
+
4. The clean_conf interface can restore system default settings
|
|
1671
|
+
|
|
1672
|
+
:param value: sensitivity value, 1~5
|
|
1673
|
+
:param wait: whether to wait for the robotic arm to stop or all previous queue commands to be executed or cleared before setting
|
|
1674
|
+
:return: code
|
|
1675
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1676
|
+
"""
|
|
1677
|
+
return self._arm.set_teach_sensitivity(value, wait=wait)
|
|
1678
|
+
|
|
1679
|
+
def set_gravity_direction(self, direction, wait=True):
|
|
1680
|
+
"""
|
|
1681
|
+
Set the gravity direction for proper torque compensation and collision detection.
|
|
1682
|
+
|
|
1683
|
+
Note:
|
|
1684
|
+
1. Use only if necessary. Incorrect settings may affect torque compensation.
|
|
1685
|
+
2. Changes are not saved automatically. Call save_conf() to save the settings,
|
|
1686
|
+
otherwise, they will be lost after a reboot.
|
|
1687
|
+
3. Use clean_conf() to restore the system default settings.
|
|
1688
|
+
4. The clean_conf interface can restore system default settings
|
|
1689
|
+
|
|
1690
|
+
:param direction: Gravity direction vector [x, y, z], e.g., [0, 0, -1] for a floor-mounted arm.
|
|
1691
|
+
:param wait: Whether to wait for the robotic arm to stop or clear all previous queued commands before applying the setting.
|
|
1692
|
+
:return: code
|
|
1693
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1694
|
+
"""
|
|
1695
|
+
return self._arm.set_gravity_direction(direction=direction, wait=wait)
|
|
1696
|
+
|
|
1697
|
+
def set_mount_direction(self, base_tilt_deg, rotation_deg, is_radian=None):
|
|
1698
|
+
"""
|
|
1699
|
+
Set the mount direction
|
|
1700
|
+
|
|
1701
|
+
Note:
|
|
1702
|
+
1. Do not use if not required
|
|
1703
|
+
2. If not saved, it will be lost after reboot
|
|
1704
|
+
3. The save_conf interface can record the current settings and will not be lost after the restart.
|
|
1705
|
+
4. The clean_conf interface can restore system default settings
|
|
1706
|
+
|
|
1707
|
+
:param base_tilt_deg: tilt degree
|
|
1708
|
+
:param rotation_deg: rotation degree
|
|
1709
|
+
:param is_radian: the base_tilt_deg/rotation_deg in radians or not, default is self.default_is_radian
|
|
1710
|
+
:return: code
|
|
1711
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1712
|
+
"""
|
|
1713
|
+
return self._arm.set_mount_direction(base_tilt_deg, rotation_deg, is_radian=is_radian)
|
|
1714
|
+
|
|
1715
|
+
def clean_conf(self):
|
|
1716
|
+
"""
|
|
1717
|
+
Clean current config and restore system default settings
|
|
1718
|
+
Note:
|
|
1719
|
+
1. This interface will clear the current settings and restore to the original settings (system default settings)
|
|
1720
|
+
|
|
1721
|
+
:return: code
|
|
1722
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1723
|
+
"""
|
|
1724
|
+
return self._arm.clean_conf()
|
|
1725
|
+
|
|
1726
|
+
def save_conf(self):
|
|
1727
|
+
"""
|
|
1728
|
+
Save config
|
|
1729
|
+
Note:
|
|
1730
|
+
1. This interface can record the current settings and will not be lost after the restart.
|
|
1731
|
+
2. The clean_conf interface can restore system default settings
|
|
1732
|
+
|
|
1733
|
+
:return: code
|
|
1734
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1735
|
+
"""
|
|
1736
|
+
return self._arm.save_conf()
|
|
1737
|
+
|
|
1738
|
+
def get_inverse_kinematics(self, pose, input_is_radian=None, return_is_radian=None):
|
|
1739
|
+
"""
|
|
1740
|
+
Get inverse kinematics
|
|
1741
|
+
|
|
1742
|
+
:param pose: [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
|
|
1743
|
+
Note: the roll/pitch/yaw unit is radian if input_is_radian is True, else °
|
|
1744
|
+
:param input_is_radian: the param pose value(only roll/pitch/yaw) is in radians or not, default is self.default_is_radian
|
|
1745
|
+
:param return_is_radian: the returned value is in radians or not, default is self.default_is_radian
|
|
1746
|
+
:return: tuple((code, angles)), only when code is 0, the returned result is correct.
|
|
1747
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1748
|
+
angles: [angle-1(rad or °), angle-2, ..., angle-(Number of axes)] or []
|
|
1749
|
+
Note: the returned angle value is radians if return_is_radian is True, else °
|
|
1750
|
+
"""
|
|
1751
|
+
return self._arm.get_inverse_kinematics(pose, input_is_radian=input_is_radian, return_is_radian=return_is_radian)
|
|
1752
|
+
|
|
1753
|
+
def get_forward_kinematics(self, angles, input_is_radian=None, return_is_radian=None):
|
|
1754
|
+
"""
|
|
1755
|
+
Get forward kinematics
|
|
1756
|
+
|
|
1757
|
+
:param angles: [angle-1, angle-2, ..., angle-n], n is the number of axes of the arm
|
|
1758
|
+
:param input_is_radian: the param angles value is in radians or not, default is self.default_is_radian
|
|
1759
|
+
:param return_is_radian: the returned value is in radians or not, default is self.default_is_radian
|
|
1760
|
+
:return: tuple((code, pose)), only when code is 0, the returned result is correct.
|
|
1761
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1762
|
+
pose: [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)] or []
|
|
1763
|
+
Note: the roll/pitch/yaw value is radians if return_is_radian is True, else °
|
|
1764
|
+
"""
|
|
1765
|
+
return self._arm.get_forward_kinematics(angles, input_is_radian=input_is_radian, return_is_radian=return_is_radian)
|
|
1766
|
+
|
|
1767
|
+
def is_tcp_limit(self, pose, is_radian=None):
|
|
1768
|
+
"""
|
|
1769
|
+
Check the tcp pose is in limit
|
|
1770
|
+
|
|
1771
|
+
:param pose: [x, y, z, roll, pitch, yaw]
|
|
1772
|
+
:param is_radian: roll/pitch/yaw value is radians or not, default is self.default_is_radian
|
|
1773
|
+
:return: tuple((code, limit)), only when code is 0, the returned result is correct.
|
|
1774
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1775
|
+
limit: True/False/None, limit or not, or failed
|
|
1776
|
+
"""
|
|
1777
|
+
return self._arm.is_tcp_limit(pose, is_radian=is_radian)
|
|
1778
|
+
|
|
1779
|
+
def is_joint_limit(self, joint, is_radian=None):
|
|
1780
|
+
"""
|
|
1781
|
+
Check the joint angle is in limit
|
|
1782
|
+
|
|
1783
|
+
:param joint: [angle-1, angle-2, ..., angle-n], n is the number of axes of the arm
|
|
1784
|
+
:param is_radian: angle value is radians or not, default is self.default_is_radian
|
|
1785
|
+
:return: tuple((code, limit)), only when code is 0, the returned result is correct.
|
|
1786
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1787
|
+
limit: True/False/None, limit or not, or failed
|
|
1788
|
+
"""
|
|
1789
|
+
return self._arm.is_joint_limit(joint, is_radian=is_radian)
|
|
1790
|
+
|
|
1791
|
+
def emergency_stop(self):
|
|
1792
|
+
"""
|
|
1793
|
+
Emergency stop (set_state(4) -> motion_enable(True) -> set_state(0))
|
|
1794
|
+
Note:
|
|
1795
|
+
1. This interface does not automatically clear the error. If there is an error, you need to handle it according to the error code.
|
|
1796
|
+
"""
|
|
1797
|
+
return self._arm.emergency_stop()
|
|
1798
|
+
|
|
1799
|
+
def set_gripper_enable(self, enable, **kwargs):
|
|
1800
|
+
"""
|
|
1801
|
+
Set the gripper enable
|
|
1802
|
+
|
|
1803
|
+
:param enable: enable or not
|
|
1804
|
+
Note: such as code = arm.set_gripper_enable(True) #turn on the Gripper
|
|
1805
|
+
:return: code
|
|
1806
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1807
|
+
"""
|
|
1808
|
+
return self._arm.set_gripper_enable(enable, **kwargs)
|
|
1809
|
+
|
|
1810
|
+
def set_gripper_mode(self, mode, **kwargs):
|
|
1811
|
+
"""
|
|
1812
|
+
Set the gripper mode
|
|
1813
|
+
|
|
1814
|
+
:param mode: 0: location mode
|
|
1815
|
+
Note: such as code = arm.set_gripper_mode(0)
|
|
1816
|
+
:return: code
|
|
1817
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1818
|
+
"""
|
|
1819
|
+
return self._arm.set_gripper_mode(mode, **kwargs)
|
|
1820
|
+
|
|
1821
|
+
def get_gripper_position(self, **kwargs):
|
|
1822
|
+
"""
|
|
1823
|
+
Get the gripper position
|
|
1824
|
+
|
|
1825
|
+
:return: tuple((code, pos)), only when code is 0, the returned result is correct.
|
|
1826
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1827
|
+
"""
|
|
1828
|
+
return self._arm.get_gripper_position(**kwargs)
|
|
1829
|
+
|
|
1830
|
+
def set_gripper_position(self, pos, wait=False, speed=None, auto_enable=False, timeout=None, **kwargs):
|
|
1831
|
+
"""
|
|
1832
|
+
Set the gripper position
|
|
1833
|
+
|
|
1834
|
+
:param pos: pos
|
|
1835
|
+
:param wait: wait or not, default is False
|
|
1836
|
+
:param speed: speed,unit:r/min
|
|
1837
|
+
:param auto_enable: auto enable or not, default is False
|
|
1838
|
+
:param timeout: wait time, unit:second, default is 10s
|
|
1839
|
+
:return: code
|
|
1840
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1841
|
+
"""
|
|
1842
|
+
return self._arm.set_gripper_position(pos, wait=wait, speed=speed, auto_enable=auto_enable, timeout=timeout, **kwargs)
|
|
1843
|
+
|
|
1844
|
+
def set_gripper_speed(self, speed, **kwargs):
|
|
1845
|
+
"""
|
|
1846
|
+
Set the gripper speed
|
|
1847
|
+
|
|
1848
|
+
:param speed:
|
|
1849
|
+
:return: code
|
|
1850
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1851
|
+
"""
|
|
1852
|
+
return self._arm.set_gripper_speed(speed, **kwargs)
|
|
1853
|
+
|
|
1854
|
+
def get_gripper_err_code(self, **kwargs):
|
|
1855
|
+
"""
|
|
1856
|
+
Get the gripper error code
|
|
1857
|
+
|
|
1858
|
+
:return: tuple((code, err_code)), only when code is 0, the returned result is correct.
|
|
1859
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1860
|
+
err_code: See the [Gripper Error Code Documentation](./xarm_api_code.md#gripper-error-code) for details.
|
|
1861
|
+
"""
|
|
1862
|
+
return self._arm.get_gripper_err_code(**kwargs)
|
|
1863
|
+
|
|
1864
|
+
def clean_gripper_error(self, **kwargs):
|
|
1865
|
+
"""
|
|
1866
|
+
Clean the gripper error
|
|
1867
|
+
|
|
1868
|
+
:return: code
|
|
1869
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1870
|
+
"""
|
|
1871
|
+
return self._arm.clean_gripper_error(**kwargs)
|
|
1872
|
+
|
|
1873
|
+
def get_tgpio_output_digital(self, ionum=None):
|
|
1874
|
+
"""
|
|
1875
|
+
Get the digital value of the specified Tool GPIO output
|
|
1876
|
+
|
|
1877
|
+
:param ionum: 0 or 1 or 2 or 3 or 4 or None(both 0 and 1 and 2 and 3 and 4), default is None
|
|
1878
|
+
:return: tuple((code, value or value list)), only when code is 0, the returned result is correct.
|
|
1879
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1880
|
+
"""
|
|
1881
|
+
return self._arm.get_tgpio_output_digital(ionum)
|
|
1882
|
+
|
|
1883
|
+
def get_tgpio_digital(self, ionum=None):
|
|
1884
|
+
"""
|
|
1885
|
+
Get the digital value of the specified Tool GPIO
|
|
1886
|
+
|
|
1887
|
+
:param ionum: 0 or 1 or None(both 0 and 1), default is None
|
|
1888
|
+
:return: tuple((code, value or value list)), only when code is 0, the returned result is correct.
|
|
1889
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1890
|
+
"""
|
|
1891
|
+
return self._arm.get_tgpio_digital(ionum)
|
|
1892
|
+
|
|
1893
|
+
def get_tool_digital_input(self, ionum=None):
|
|
1894
|
+
"""
|
|
1895
|
+
Get the digital value of the specified Tool GPIO,Compared with the "get_tgpio_digital" interface,
|
|
1896
|
+
the value of TI2 is obtained when the ionum is not transmitted.
|
|
1897
|
+
|
|
1898
|
+
:param ionum: 0 or 1 or or 2 or 3 or 4 (both 0 and 4), default is None
|
|
1899
|
+
:return: tuple((code, value or value list)), only when code is 0, the returned result is correct.
|
|
1900
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1901
|
+
"""
|
|
1902
|
+
return self._arm.get_tool_digital_input(ionum)
|
|
1903
|
+
|
|
1904
|
+
def set_tgpio_digital(self, ionum, value, delay_sec=None, sync=True):
|
|
1905
|
+
"""
|
|
1906
|
+
Set the digital value of the specified Tool GPIO
|
|
1907
|
+
|
|
1908
|
+
:param ionum: 0 or 1
|
|
1909
|
+
:param value: value
|
|
1910
|
+
:param delay_sec: delay effective time from the current start, in seconds, default is None(effective immediately)
|
|
1911
|
+
:param sync: whether to execute in the motion queue, set to False to execute immediately(default is True)
|
|
1912
|
+
1. only available if firmware_version >= 2.4.101
|
|
1913
|
+
2. only available if delay_sec <= 0
|
|
1914
|
+
:return: code
|
|
1915
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1916
|
+
"""
|
|
1917
|
+
return self._arm.set_tgpio_digital(ionum=ionum, value=value, delay_sec=delay_sec, sync=sync)
|
|
1918
|
+
|
|
1919
|
+
def get_tgpio_analog(self, ionum=None):
|
|
1920
|
+
"""
|
|
1921
|
+
Get the analog value of the specified Tool GPIO
|
|
1922
|
+
:param ionum: 0 or 1 or None(both 0 and 1), default is None
|
|
1923
|
+
:return: tuple((code, value or value list)), only when code is 0, the returned result is correct.
|
|
1924
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1925
|
+
"""
|
|
1926
|
+
return self._arm.get_tgpio_analog(ionum)
|
|
1927
|
+
|
|
1928
|
+
def get_vacuum_gripper(self, hardware_version=1):
|
|
1929
|
+
"""
|
|
1930
|
+
Get vacuum gripper state
|
|
1931
|
+
|
|
1932
|
+
:param hardware_version: hardware version
|
|
1933
|
+
1: Plug-in Connection, default
|
|
1934
|
+
2: Contact Connection
|
|
1935
|
+
:return: tuple((code, state)), only when code is 0, the returned result is correct.
|
|
1936
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1937
|
+
state: vacuum gripper state
|
|
1938
|
+
0: vacuum gripper is off
|
|
1939
|
+
1: vacuum gripper is on
|
|
1940
|
+
"""
|
|
1941
|
+
return self._arm.get_suction_cup(hardware_version=hardware_version)
|
|
1942
|
+
|
|
1943
|
+
def set_vacuum_gripper(self, on, wait=False, timeout=3, delay_sec=None, sync=True, hardware_version=1):
|
|
1944
|
+
"""
|
|
1945
|
+
Set vacuum gripper state
|
|
1946
|
+
|
|
1947
|
+
:param on: open or not
|
|
1948
|
+
on=True: equivalent to calling `set_tgpio_digital(0, 1)` and `set_tgpio_digital(1, 0)`
|
|
1949
|
+
on=False: equivalent to calling `set_tgpio_digital(0, 0)` and `set_tgpio_digital(1, 1)`
|
|
1950
|
+
:param wait: wait or not, default is False
|
|
1951
|
+
:param timeout: wait time, unit:second, default is 3s
|
|
1952
|
+
:param delay_sec: delay effective time from the current start, in seconds, default is None(effective immediately)
|
|
1953
|
+
:param sync: whether to execute in the motion queue, set to False to execute immediately(default is True)
|
|
1954
|
+
1. only available if firmware_version >= 2.4.101
|
|
1955
|
+
2. only available if delay_sec <= 0
|
|
1956
|
+
:param hardware_version: hardware version
|
|
1957
|
+
1: Plug-in Connection, default
|
|
1958
|
+
2: Contact Connection
|
|
1959
|
+
:return: code
|
|
1960
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1961
|
+
"""
|
|
1962
|
+
return self._arm.set_suction_cup(on, wait=wait, timeout=timeout, delay_sec=delay_sec, sync=sync, hardware_version=hardware_version)
|
|
1963
|
+
|
|
1964
|
+
def get_cgpio_digital(self, ionum=None):
|
|
1965
|
+
"""
|
|
1966
|
+
Get the digital value of the specified Controller GPIO
|
|
1967
|
+
|
|
1968
|
+
:param ionum: 0~7(CI0~CI7), 8~15(DI0~DI7) or None(both 0~15), default is None
|
|
1969
|
+
:return: tuple((code, value or value list)), only when code is 0, the returned result is correct.
|
|
1970
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1971
|
+
"""
|
|
1972
|
+
return self._arm.get_cgpio_digital(ionum=ionum)
|
|
1973
|
+
|
|
1974
|
+
def get_cgpio_analog(self, ionum=None):
|
|
1975
|
+
"""
|
|
1976
|
+
Get the analog value of the specified Controller GPIO
|
|
1977
|
+
:param ionum: 0 or 1 or None(both 0 and 1), default is None
|
|
1978
|
+
:return: tuple((code, value or value list)), only when code is 0, the returned result is correct.
|
|
1979
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1980
|
+
"""
|
|
1981
|
+
return self._arm.get_cgpio_analog(ionum=ionum)
|
|
1982
|
+
|
|
1983
|
+
def set_cgpio_digital(self, ionum, value, delay_sec=None, sync=True):
|
|
1984
|
+
"""
|
|
1985
|
+
Set the digital value of the specified Controller GPIO
|
|
1986
|
+
|
|
1987
|
+
:param ionum: 0~7(CO0~CO7), 8~15(DO0~DO7)
|
|
1988
|
+
:param value: value
|
|
1989
|
+
:param delay_sec: delay effective time from the current start, in seconds, default is None(effective immediately)
|
|
1990
|
+
:param sync: whether to execute in the motion queue, set to False to execute immediately(default is True)
|
|
1991
|
+
1. only available if firmware_version >= 2.4.101
|
|
1992
|
+
2. only available if delay_sec <= 0
|
|
1993
|
+
:return: code
|
|
1994
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
1995
|
+
"""
|
|
1996
|
+
return self._arm.set_cgpio_digital(ionum=ionum, value=value, delay_sec=delay_sec, sync=sync)
|
|
1997
|
+
|
|
1998
|
+
def set_cgpio_analog(self, ionum, value, sync=True):
|
|
1999
|
+
"""
|
|
2000
|
+
Set the analog value of the specified Controller GPIO
|
|
2001
|
+
|
|
2002
|
+
:param ionum: 0 or 1
|
|
2003
|
+
:param value: value
|
|
2004
|
+
:param sync: whether to execute in the motion queue, set to False to execute immediately(default is True)
|
|
2005
|
+
1. only available if firmware_version >= 2.4.101
|
|
2006
|
+
:return: code
|
|
2007
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2008
|
+
"""
|
|
2009
|
+
return self._arm.set_cgpio_analog(ionum=ionum, value=value, sync=sync)
|
|
2010
|
+
|
|
2011
|
+
def set_cgpio_digital_input_function(self, ionum, fun):
|
|
2012
|
+
"""
|
|
2013
|
+
Set the digital input functional mode of the Controller GPIO
|
|
2014
|
+
:param ionum: 0~7(CI0~CI7), 8~15(DI0~DI7)
|
|
2015
|
+
:param fun: functional mode
|
|
2016
|
+
0: general input
|
|
2017
|
+
1: external emergency stop
|
|
2018
|
+
2: protection reset
|
|
2019
|
+
11: offline task
|
|
2020
|
+
12: teaching mode
|
|
2021
|
+
13: reduced mode
|
|
2022
|
+
14: enable arm
|
|
2023
|
+
:return: code
|
|
2024
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2025
|
+
"""
|
|
2026
|
+
return self._arm.set_cgpio_digital_input_function(ionum=ionum, fun=fun)
|
|
2027
|
+
|
|
2028
|
+
def set_cgpio_digital_output_function(self, ionum, fun):
|
|
2029
|
+
"""
|
|
2030
|
+
Set the digital output functional mode of the specified Controller GPIO
|
|
2031
|
+
:param ionum: 0~7(CO0~CO7), 8~15(DO0~DO7)
|
|
2032
|
+
:param fun: functionnal mode
|
|
2033
|
+
0: general output
|
|
2034
|
+
1: emergency stop
|
|
2035
|
+
2: in motion
|
|
2036
|
+
11: has error
|
|
2037
|
+
12: has warn
|
|
2038
|
+
13: in collision
|
|
2039
|
+
14: in teaching
|
|
2040
|
+
15: in offline task
|
|
2041
|
+
16: in reduced mode
|
|
2042
|
+
17: is enabled
|
|
2043
|
+
18: emergency stop is pressed
|
|
2044
|
+
:return: code
|
|
2045
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2046
|
+
"""
|
|
2047
|
+
return self._arm.set_cgpio_digital_output_function(ionum=ionum, fun=fun)
|
|
2048
|
+
|
|
2049
|
+
def get_cgpio_state(self):
|
|
2050
|
+
"""
|
|
2051
|
+
Get the state of the Controller GPIO
|
|
2052
|
+
:return: code, states
|
|
2053
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2054
|
+
states: [...]
|
|
2055
|
+
states[0]: contorller gpio module state
|
|
2056
|
+
states[0] == 0: normal
|
|
2057
|
+
states[0] == 1: wrong
|
|
2058
|
+
states[0] == 6: communication failure
|
|
2059
|
+
states[1]: controller gpio module error code
|
|
2060
|
+
states[1] == 0: normal
|
|
2061
|
+
states[1] != 0: error code
|
|
2062
|
+
states[2]: digital input functional gpio state
|
|
2063
|
+
Note: digital-i-input functional gpio state = states[2] >> i & 0x0001
|
|
2064
|
+
states[3]: digital input configuring gpio state
|
|
2065
|
+
Note: digital-i-input configuring gpio state = states[3] >> i & 0x0001
|
|
2066
|
+
states[4]: digital output functional gpio state
|
|
2067
|
+
Note: digital-i-output functional gpio state = states[4] >> i & 0x0001
|
|
2068
|
+
states[5]: digital output configuring gpio state
|
|
2069
|
+
Note: digital-i-output configuring gpio state = states[5] >> i & 0x0001
|
|
2070
|
+
states[6]: analog-0 input value
|
|
2071
|
+
states[7]: analog-1 input value
|
|
2072
|
+
states[8]: analog-0 output value
|
|
2073
|
+
states[9]: analog-1 output value
|
|
2074
|
+
states[10]: digital input functional info, [digital-0-input-functional-mode, ... digital-15-input-functional-mode]
|
|
2075
|
+
states[11]: digital output functional info, [digital-0-output-functional-mode, ... digital-15-output-functional-mode]
|
|
2076
|
+
"""
|
|
2077
|
+
return self._arm.get_cgpio_state()
|
|
2078
|
+
|
|
2079
|
+
def register_report_callback(self, callback=None, report_cartesian=True, report_joints=True,
|
|
2080
|
+
report_state=True, report_error_code=True, report_warn_code=True,
|
|
2081
|
+
report_mtable=True, report_mtbrake=True, report_cmd_num=True):
|
|
2082
|
+
"""
|
|
2083
|
+
Register the report callback, only available if enable_report is True
|
|
2084
|
+
|
|
2085
|
+
:param callback:
|
|
2086
|
+
callback data:
|
|
2087
|
+
{
|
|
2088
|
+
'cartesian': [], # if report_cartesian is True
|
|
2089
|
+
'joints': [], # if report_joints is True
|
|
2090
|
+
'error_code': 0, # if report_error_code is True
|
|
2091
|
+
'warn_code': 0, # if report_warn_code is True
|
|
2092
|
+
'state': state, # if report_state is True
|
|
2093
|
+
'mtbrake': mtbrake, # if report_mtbrake is True, and available if enable_report is True and the connect way is socket
|
|
2094
|
+
'mtable': mtable, # if report_mtable is True, and available if enable_report is True and the connect way is socket
|
|
2095
|
+
'cmdnum': cmdnum, # if report_cmd_num is True
|
|
2096
|
+
}
|
|
2097
|
+
:param report_cartesian: report cartesian or not, default is True
|
|
2098
|
+
:param report_joints: report joints or not, default is True
|
|
2099
|
+
:param report_state: report state or not, default is True
|
|
2100
|
+
:param report_error_code: report error or not, default is True
|
|
2101
|
+
:param report_warn_code: report warn or not, default is True
|
|
2102
|
+
:param report_mtable: report motor enable states or not, default is True
|
|
2103
|
+
:param report_mtbrake: report motor brake states or not, default is True
|
|
2104
|
+
:param report_cmd_num: report cmdnum or not, default is True
|
|
2105
|
+
:return: True/False
|
|
2106
|
+
"""
|
|
2107
|
+
return self._arm.register_report_callback(callback=callback,
|
|
2108
|
+
report_cartesian=report_cartesian,
|
|
2109
|
+
report_joints=report_joints,
|
|
2110
|
+
report_state=report_state,
|
|
2111
|
+
report_error_code=report_error_code,
|
|
2112
|
+
report_warn_code=report_warn_code,
|
|
2113
|
+
report_mtable=report_mtable,
|
|
2114
|
+
report_mtbrake=report_mtbrake,
|
|
2115
|
+
report_cmd_num=report_cmd_num)
|
|
2116
|
+
|
|
2117
|
+
def register_report_location_callback(self, callback=None, report_cartesian=True, report_joints=True):
|
|
2118
|
+
"""
|
|
2119
|
+
Register the report location callback, only available if enable_report is True
|
|
2120
|
+
|
|
2121
|
+
:param callback:
|
|
2122
|
+
callback data:
|
|
2123
|
+
{
|
|
2124
|
+
"cartesian": [x, y, z, roll, pitch, yaw], ## if report_cartesian is True
|
|
2125
|
+
"joints": [angle-1, angle-2, angle-3, angle-4, angle-5, angle-6, angle-7], ## if report_joints is True
|
|
2126
|
+
}
|
|
2127
|
+
:param report_cartesian: report or not, True/False, default is True
|
|
2128
|
+
:param report_joints: report or not, True/False, default is True
|
|
2129
|
+
:return: True/False
|
|
2130
|
+
"""
|
|
2131
|
+
return self._arm.register_report_location_callback(callback=callback,
|
|
2132
|
+
report_cartesian=report_cartesian,
|
|
2133
|
+
report_joints=report_joints)
|
|
2134
|
+
|
|
2135
|
+
def register_connect_changed_callback(self, callback=None):
|
|
2136
|
+
"""
|
|
2137
|
+
Register the connect status changed callback
|
|
2138
|
+
|
|
2139
|
+
:param callback:
|
|
2140
|
+
callback data:
|
|
2141
|
+
{
|
|
2142
|
+
"connected": connected,
|
|
2143
|
+
"reported": reported,
|
|
2144
|
+
}
|
|
2145
|
+
:return: True/False
|
|
2146
|
+
"""
|
|
2147
|
+
return self._arm.register_connect_changed_callback(callback=callback)
|
|
2148
|
+
|
|
2149
|
+
def register_state_changed_callback(self, callback=None):
|
|
2150
|
+
"""
|
|
2151
|
+
Register the state status changed callback, only available if enable_report is True
|
|
2152
|
+
|
|
2153
|
+
:param callback:
|
|
2154
|
+
callback data:
|
|
2155
|
+
{
|
|
2156
|
+
"state": state,
|
|
2157
|
+
}
|
|
2158
|
+
:return: True/False
|
|
2159
|
+
"""
|
|
2160
|
+
return self._arm.register_state_changed_callback(callback=callback)
|
|
2161
|
+
|
|
2162
|
+
def register_mode_changed_callback(self, callback=None):
|
|
2163
|
+
"""
|
|
2164
|
+
Register the mode changed callback, only available if enable_report is True and the connect way is socket
|
|
2165
|
+
|
|
2166
|
+
:param callback:
|
|
2167
|
+
callback data:
|
|
2168
|
+
{
|
|
2169
|
+
"mode": mode,
|
|
2170
|
+
}
|
|
2171
|
+
:return: True/False
|
|
2172
|
+
"""
|
|
2173
|
+
return self._arm.register_mode_changed_callback(callback=callback)
|
|
2174
|
+
|
|
2175
|
+
def register_mtable_mtbrake_changed_callback(self, callback=None):
|
|
2176
|
+
"""
|
|
2177
|
+
Register the motor enable states or motor brake states changed callback, only available if enable_report is True and the connect way is socket
|
|
2178
|
+
|
|
2179
|
+
:param callback:
|
|
2180
|
+
callback data:
|
|
2181
|
+
{
|
|
2182
|
+
"mtable": [motor-1-motion-enable, motor-2-motion-enable, ...],
|
|
2183
|
+
"mtbrake": [motor-1-brake-enable, motor-1-brake-enable,...],
|
|
2184
|
+
}
|
|
2185
|
+
:return: True/False
|
|
2186
|
+
"""
|
|
2187
|
+
return self._arm.register_mtable_mtbrake_changed_callback(callback=callback)
|
|
2188
|
+
|
|
2189
|
+
def register_error_warn_changed_callback(self, callback=None):
|
|
2190
|
+
"""
|
|
2191
|
+
Register the error code or warn code changed callback, only available if enable_report is True
|
|
2192
|
+
|
|
2193
|
+
:param callback:
|
|
2194
|
+
callback data:
|
|
2195
|
+
{
|
|
2196
|
+
"error_code": error_code,
|
|
2197
|
+
"warn_code": warn_code,
|
|
2198
|
+
}
|
|
2199
|
+
:return: True/False
|
|
2200
|
+
"""
|
|
2201
|
+
return self._arm.register_error_warn_changed_callback(callback=callback)
|
|
2202
|
+
|
|
2203
|
+
def register_cmdnum_changed_callback(self, callback=None):
|
|
2204
|
+
"""
|
|
2205
|
+
Register the cmdnum changed callback, only available if enable_report is True
|
|
2206
|
+
|
|
2207
|
+
:param callback:
|
|
2208
|
+
callback data:
|
|
2209
|
+
{
|
|
2210
|
+
"cmdnum": cmdnum
|
|
2211
|
+
}
|
|
2212
|
+
:return: True/False
|
|
2213
|
+
"""
|
|
2214
|
+
return self._arm.register_cmdnum_changed_callback(callback=callback)
|
|
2215
|
+
|
|
2216
|
+
def register_temperature_changed_callback(self, callback=None):
|
|
2217
|
+
"""
|
|
2218
|
+
Register the temperature changed callback, only available if enable_report is True
|
|
2219
|
+
|
|
2220
|
+
:param callback:
|
|
2221
|
+
callback data:
|
|
2222
|
+
{
|
|
2223
|
+
"temperatures": [servo-1-temperature, ...., servo-7-temperature]
|
|
2224
|
+
}
|
|
2225
|
+
:return: True/False
|
|
2226
|
+
"""
|
|
2227
|
+
return self._arm.register_temperature_changed_callback(callback=callback)
|
|
2228
|
+
|
|
2229
|
+
def register_count_changed_callback(self, callback=None):
|
|
2230
|
+
"""
|
|
2231
|
+
Register the counter value changed callback, only available if enable_report is True
|
|
2232
|
+
|
|
2233
|
+
:param callback:
|
|
2234
|
+
callback data:
|
|
2235
|
+
{
|
|
2236
|
+
"count": counter value
|
|
2237
|
+
}
|
|
2238
|
+
:return: True/False
|
|
2239
|
+
"""
|
|
2240
|
+
return self._arm.register_count_changed_callback(callback=callback)
|
|
2241
|
+
|
|
2242
|
+
def register_iden_progress_changed_callback(self, callback=None):
|
|
2243
|
+
"""
|
|
2244
|
+
Register the Identification progress value changed callback, only available if enable_report is True
|
|
2245
|
+
|
|
2246
|
+
:param callback:
|
|
2247
|
+
callback data:
|
|
2248
|
+
{
|
|
2249
|
+
"progress": progress value
|
|
2250
|
+
}
|
|
2251
|
+
:return: True/False
|
|
2252
|
+
"""
|
|
2253
|
+
return self._arm.register_iden_progress_changed_callback(callback=callback)
|
|
2254
|
+
|
|
2255
|
+
def release_report_callback(self, callback=None):
|
|
2256
|
+
"""
|
|
2257
|
+
Release the report callback
|
|
2258
|
+
|
|
2259
|
+
:param callback:
|
|
2260
|
+
:return: True/False
|
|
2261
|
+
"""
|
|
2262
|
+
return self._arm.release_report_callback(callback)
|
|
2263
|
+
|
|
2264
|
+
def release_report_location_callback(self, callback=None):
|
|
2265
|
+
"""
|
|
2266
|
+
Release the location report callback
|
|
2267
|
+
|
|
2268
|
+
:param callback:
|
|
2269
|
+
:return: True/False
|
|
2270
|
+
"""
|
|
2271
|
+
return self._arm.release_report_location_callback(callback)
|
|
2272
|
+
|
|
2273
|
+
def release_connect_changed_callback(self, callback=None):
|
|
2274
|
+
"""
|
|
2275
|
+
Release the connect changed callback
|
|
2276
|
+
|
|
2277
|
+
:param callback:
|
|
2278
|
+
:return: True/False
|
|
2279
|
+
"""
|
|
2280
|
+
return self._arm.release_connect_changed_callback(callback)
|
|
2281
|
+
|
|
2282
|
+
def release_state_changed_callback(self, callback=None):
|
|
2283
|
+
"""
|
|
2284
|
+
Release the state changed callback
|
|
2285
|
+
|
|
2286
|
+
:param callback:
|
|
2287
|
+
:return: True/False
|
|
2288
|
+
"""
|
|
2289
|
+
return self._arm.release_state_changed_callback(callback)
|
|
2290
|
+
|
|
2291
|
+
def release_mode_changed_callback(self, callback=None):
|
|
2292
|
+
"""
|
|
2293
|
+
Release the mode changed callback
|
|
2294
|
+
|
|
2295
|
+
:param callback:
|
|
2296
|
+
:return: True/False
|
|
2297
|
+
"""
|
|
2298
|
+
return self._arm.release_mode_changed_callback(callback)
|
|
2299
|
+
|
|
2300
|
+
def release_mtable_mtbrake_changed_callback(self, callback=None):
|
|
2301
|
+
"""
|
|
2302
|
+
Release the motor enable states or motor brake states changed callback
|
|
2303
|
+
|
|
2304
|
+
:param callback:
|
|
2305
|
+
:return: True/False
|
|
2306
|
+
"""
|
|
2307
|
+
return self._arm.release_mtable_mtbrake_changed_callback(callback)
|
|
2308
|
+
|
|
2309
|
+
def release_error_warn_changed_callback(self, callback=None):
|
|
2310
|
+
"""
|
|
2311
|
+
Release the error warn changed callback
|
|
2312
|
+
|
|
2313
|
+
:param callback:
|
|
2314
|
+
:return: True/False
|
|
2315
|
+
"""
|
|
2316
|
+
return self._arm.release_error_warn_changed_callback(callback)
|
|
2317
|
+
|
|
2318
|
+
def release_cmdnum_changed_callback(self, callback=None):
|
|
2319
|
+
"""
|
|
2320
|
+
Release the cmdnum changed callback
|
|
2321
|
+
|
|
2322
|
+
:param callback:
|
|
2323
|
+
:return: True/False
|
|
2324
|
+
"""
|
|
2325
|
+
return self._arm.release_cmdnum_changed_callback(callback)
|
|
2326
|
+
|
|
2327
|
+
def release_temperature_changed_callback(self, callback=None):
|
|
2328
|
+
"""
|
|
2329
|
+
Release the temperature changed callback
|
|
2330
|
+
|
|
2331
|
+
:param callback:
|
|
2332
|
+
:return: True/False
|
|
2333
|
+
"""
|
|
2334
|
+
return self._arm.release_temperature_changed_callback(callback=callback)
|
|
2335
|
+
|
|
2336
|
+
def release_count_changed_callback(self, callback=None):
|
|
2337
|
+
"""
|
|
2338
|
+
Release the counter value changed callback
|
|
2339
|
+
|
|
2340
|
+
:param callback:
|
|
2341
|
+
:return: True/False
|
|
2342
|
+
"""
|
|
2343
|
+
return self._arm.release_count_changed_callback(callback=callback)
|
|
2344
|
+
|
|
2345
|
+
def release_iden_progress_changed_callback(self, callback=None):
|
|
2346
|
+
"""
|
|
2347
|
+
Release the Identification progress value changed callback
|
|
2348
|
+
|
|
2349
|
+
:param callback:
|
|
2350
|
+
:return: True/False
|
|
2351
|
+
"""
|
|
2352
|
+
return self._arm.release_iden_progress_changed_callback(callback=callback)
|
|
2353
|
+
|
|
2354
|
+
def get_servo_debug_msg(self, show=False, lang='en'):
|
|
2355
|
+
"""
|
|
2356
|
+
Get the servo debug msg, used only for debugging
|
|
2357
|
+
|
|
2358
|
+
:param show: show the detail info if True
|
|
2359
|
+
:param lang: language, en/cn, default is en
|
|
2360
|
+
:return: tuple((code, servo_info_list)), only when code is 0, the returned result is correct.
|
|
2361
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2362
|
+
"""
|
|
2363
|
+
return self._arm.get_servo_debug_msg(show=show, lang=lang)
|
|
2364
|
+
|
|
2365
|
+
def run_blockly_app(self, path, **kwargs):
|
|
2366
|
+
"""
|
|
2367
|
+
Run the app generated by xArmStudio software
|
|
2368
|
+
:param path: app path
|
|
2369
|
+
"""
|
|
2370
|
+
return self._arm.run_blockly_app(path, **kwargs)
|
|
2371
|
+
|
|
2372
|
+
def run_gcode_file(self, path, **kwargs):
|
|
2373
|
+
"""
|
|
2374
|
+
Run the gcode file
|
|
2375
|
+
:param path: gcode file path
|
|
2376
|
+
"""
|
|
2377
|
+
return self._arm.run_gcode_file(path, **kwargs)
|
|
2378
|
+
|
|
2379
|
+
def get_gripper_version(self):
|
|
2380
|
+
"""
|
|
2381
|
+
Get gripper version, only for debug
|
|
2382
|
+
|
|
2383
|
+
:return: (code, version)
|
|
2384
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2385
|
+
"""
|
|
2386
|
+
return self._arm.get_gripper_version()
|
|
2387
|
+
|
|
2388
|
+
def get_servo_version(self, servo_id=1):
|
|
2389
|
+
"""
|
|
2390
|
+
Get servo version, only for debug
|
|
2391
|
+
|
|
2392
|
+
:param servo_id: servo id(1~7)
|
|
2393
|
+
:return: (code, version)
|
|
2394
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2395
|
+
"""
|
|
2396
|
+
return self._arm.get_servo_version(servo_id=servo_id)
|
|
2397
|
+
|
|
2398
|
+
def get_tgpio_version(self):
|
|
2399
|
+
"""
|
|
2400
|
+
Get tool gpio version, only for debug
|
|
2401
|
+
|
|
2402
|
+
:return: (code, version)
|
|
2403
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2404
|
+
"""
|
|
2405
|
+
return self._arm.get_tgpio_version()
|
|
2406
|
+
|
|
2407
|
+
def get_harmonic_type(self, servo_id=1):
|
|
2408
|
+
"""
|
|
2409
|
+
Get harmonic type, only for debug
|
|
2410
|
+
|
|
2411
|
+
:return: (code, type)
|
|
2412
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2413
|
+
"""
|
|
2414
|
+
return self._arm.get_harmonic_type(servo_id=servo_id)
|
|
2415
|
+
|
|
2416
|
+
def get_hd_types(self):
|
|
2417
|
+
"""
|
|
2418
|
+
Get harmonic types, only for debug
|
|
2419
|
+
|
|
2420
|
+
:return: (code, types)
|
|
2421
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2422
|
+
"""
|
|
2423
|
+
return self._arm.get_hd_types()
|
|
2424
|
+
|
|
2425
|
+
def set_counter_reset(self):
|
|
2426
|
+
"""
|
|
2427
|
+
Reset counter value
|
|
2428
|
+
|
|
2429
|
+
:return: code
|
|
2430
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2431
|
+
"""
|
|
2432
|
+
return self._arm.set_counter_reset()
|
|
2433
|
+
|
|
2434
|
+
def set_counter_increase(self, val=1):
|
|
2435
|
+
"""
|
|
2436
|
+
Set counter plus value, only support plus 1
|
|
2437
|
+
|
|
2438
|
+
:param val: reversed
|
|
2439
|
+
:return: code
|
|
2440
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2441
|
+
"""
|
|
2442
|
+
return self._arm.set_counter_increase(val)
|
|
2443
|
+
|
|
2444
|
+
def set_tgpio_digital_with_xyz(self, ionum, value, xyz, fault_tolerance_radius):
|
|
2445
|
+
"""
|
|
2446
|
+
Set the digital value of the specified Tool GPIO when the robot has reached the specified xyz position
|
|
2447
|
+
|
|
2448
|
+
:param ionum: 0 or 1
|
|
2449
|
+
:param value: value
|
|
2450
|
+
:param xyz: position xyz, as [x, y, z]
|
|
2451
|
+
:param fault_tolerance_radius: fault tolerance radius
|
|
2452
|
+
:return: code
|
|
2453
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2454
|
+
"""
|
|
2455
|
+
return self._arm.set_tgpio_digital_with_xyz(ionum, value, xyz, fault_tolerance_radius)
|
|
2456
|
+
|
|
2457
|
+
def set_cgpio_digital_with_xyz(self, ionum, value, xyz, fault_tolerance_radius):
|
|
2458
|
+
"""
|
|
2459
|
+
Set the digital value of the specified Controller GPIO when the robot has reached the specified xyz position
|
|
2460
|
+
|
|
2461
|
+
:param ionum: 0 ~ 15
|
|
2462
|
+
:param value: value
|
|
2463
|
+
:param xyz: position xyz, as [x, y, z]
|
|
2464
|
+
:param fault_tolerance_radius: fault tolerance radius
|
|
2465
|
+
:return: code
|
|
2466
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2467
|
+
"""
|
|
2468
|
+
return self._arm.set_cgpio_digital_with_xyz(ionum, value, xyz, fault_tolerance_radius)
|
|
2469
|
+
|
|
2470
|
+
def set_cgpio_analog_with_xyz(self, ionum, value, xyz, fault_tolerance_radius):
|
|
2471
|
+
"""
|
|
2472
|
+
Set the analog value of the specified Controller GPIO when the robot has reached the specified xyz position
|
|
2473
|
+
|
|
2474
|
+
:param ionum: 0 ~ 1
|
|
2475
|
+
:param value: value
|
|
2476
|
+
:param xyz: position xyz, as [x, y, z]
|
|
2477
|
+
:param fault_tolerance_radius: fault tolerance radius
|
|
2478
|
+
:return: code
|
|
2479
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2480
|
+
"""
|
|
2481
|
+
return self._arm.set_cgpio_analog_with_xyz(ionum, value, xyz, fault_tolerance_radius)
|
|
2482
|
+
|
|
2483
|
+
def config_tgpio_reset_when_stop(self, on_off):
|
|
2484
|
+
"""
|
|
2485
|
+
Config the Tool GPIO reset the digital output when the robot is in stop state
|
|
2486
|
+
|
|
2487
|
+
:param on_off: True/False
|
|
2488
|
+
:return: code
|
|
2489
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2490
|
+
"""
|
|
2491
|
+
return self._arm.config_io_reset_when_stop(1, on_off)
|
|
2492
|
+
|
|
2493
|
+
def config_cgpio_reset_when_stop(self, on_off):
|
|
2494
|
+
"""
|
|
2495
|
+
Config the Controller GPIO reset the digital output when the robot is in stop state
|
|
2496
|
+
|
|
2497
|
+
:param on_off: True/False
|
|
2498
|
+
:return: code
|
|
2499
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2500
|
+
"""
|
|
2501
|
+
return self._arm.config_io_reset_when_stop(0, on_off)
|
|
2502
|
+
|
|
2503
|
+
def set_position_aa(self, axis_angle_pose, speed=None, mvacc=None, mvtime=None,
|
|
2504
|
+
is_radian=None, is_tool_coord=False, relative=False, wait=False, timeout=None, radius=None, **kwargs):
|
|
2505
|
+
"""
|
|
2506
|
+
Set the pose represented by the axis angle pose
|
|
2507
|
+
|
|
2508
|
+
:param axis_angle_pose: the axis angle pose, [x(mm), y(mm), z(mm), rx(rad or °), ry(rad or °), rz(rad or °)]
|
|
2509
|
+
:param speed: move speed (mm/s, rad/s), default is self.last_used_tcp_speed
|
|
2510
|
+
:param mvacc: move acceleration (mm/s^2, rad/s^2), default is self.last_used_tcp_acc
|
|
2511
|
+
:param mvtime: 0, reserved
|
|
2512
|
+
:param is_radian: the rx/ry/rz of axis_angle_pose in radians or not, default is self.default_is_radian
|
|
2513
|
+
:param is_tool_coord: is tool coordinate or not, if it is True, the relative parameter is no longer valid
|
|
2514
|
+
:param relative: relative move or not
|
|
2515
|
+
:param wait: whether to wait for the arm to complete, default is False
|
|
2516
|
+
:param timeout: maximum waiting time(unit: second), default is None(no timeout), only valid if wait is True
|
|
2517
|
+
:param radius: move radius, if radius is None or radius less than 0, will MoveLineAA, else MoveArcLineAA
|
|
2518
|
+
only available if firmware_version >= 1.11.100
|
|
2519
|
+
MoveLineAA: Linear motion
|
|
2520
|
+
ex: code = arm.set_position_aa(..., radius=None)
|
|
2521
|
+
MoveArcLineAA: Linear arc motion with interpolation
|
|
2522
|
+
ex: code = arm.set_position_aa(..., radius=0)
|
|
2523
|
+
Note: Need to set radius>=0
|
|
2524
|
+
:param kwargs: extra parameters
|
|
2525
|
+
:param motion_type: motion planning type, default is 0
|
|
2526
|
+
motion_type == 0: default, linear planning
|
|
2527
|
+
motion_type == 1: prioritize linear planning, and turn to IK for joint planning when linear planning is not possible
|
|
2528
|
+
motion_type == 2: direct transfer to IK using joint planning
|
|
2529
|
+
Note:
|
|
2530
|
+
1. only available if firmware_version >= 1.11.100
|
|
2531
|
+
2. when motion_type is 1 or 2, linear motion cannot be guaranteed
|
|
2532
|
+
3. once IK is transferred to joint planning, the given Cartesian velocity and acceleration are converted into joint velocity and acceleration according to the percentage
|
|
2533
|
+
speed = speed / max_tcp_speed * max_joint_speed
|
|
2534
|
+
mvacc = mvacc / max_tcp_acc * max_joint_acc
|
|
2535
|
+
4. if there is no suitable IK, a C40 error will be triggered
|
|
2536
|
+
:return: code
|
|
2537
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2538
|
+
"""
|
|
2539
|
+
return self._arm.set_position_aa(axis_angle_pose, speed=speed, mvacc=mvacc, mvtime=mvtime,
|
|
2540
|
+
is_radian=is_radian, is_tool_coord=is_tool_coord, relative=relative,
|
|
2541
|
+
wait=wait, timeout=timeout, radius=radius, **kwargs)
|
|
2542
|
+
|
|
2543
|
+
def set_servo_cartesian_aa(self, axis_angle_pose, speed=None, mvacc=None, is_radian=None, is_tool_coord=False, relative=False, **kwargs):
|
|
2544
|
+
"""
|
|
2545
|
+
Set the servo cartesian represented by the axis angle pose, execute only the last instruction, need to be set to servo motion mode(self.set_mode(1))
|
|
2546
|
+
Note:
|
|
2547
|
+
1. only available if firmware_version >= 1.4.7
|
|
2548
|
+
|
|
2549
|
+
:param axis_angle_pose: the axis angle pose, [x(mm), y(mm), z(mm), rx(rad or °), ry(rad or °), rz(rad or °)]
|
|
2550
|
+
:param speed: move speed (mm/s), reserved
|
|
2551
|
+
:param mvacc: move acceleration (mm/s^2), reserved
|
|
2552
|
+
:param is_radian: the rx/ry/rz of axis_angle_pose in radians or not, default is self.default_is_radian
|
|
2553
|
+
:param is_tool_coord: is tool coordinate or not
|
|
2554
|
+
:param relative: relative move or not
|
|
2555
|
+
:return: code
|
|
2556
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2557
|
+
"""
|
|
2558
|
+
|
|
2559
|
+
return self._arm.set_servo_cartesian_aa(axis_angle_pose, speed=speed, mvacc=mvacc, is_radian=is_radian,
|
|
2560
|
+
is_tool_coord=is_tool_coord, relative=relative, **kwargs)
|
|
2561
|
+
|
|
2562
|
+
def get_pose_offset(self, pose1, pose2, orient_type_in=0, orient_type_out=0, is_radian=None):
|
|
2563
|
+
"""
|
|
2564
|
+
Calculate the pose offset of two given points
|
|
2565
|
+
|
|
2566
|
+
:param pose1: [x(mm), y(mm), z(mm), roll/rx(rad or °), pitch/ry(rad or °), yaw/rz(rad or °)]
|
|
2567
|
+
:param pose2: [x(mm), y(mm), z(mm), roll/rx(rad or °), pitch/ry(rad or °), yaw/rz(rad or °)]
|
|
2568
|
+
:param orient_type_in: input attitude notation, 0 is RPY(roll/pitch/yaw) (default), 1 is axis angle(rx/ry/rz)
|
|
2569
|
+
:param orient_type_out: notation of output attitude, 0 is RPY (default), 1 is axis angle
|
|
2570
|
+
:param is_radian: the roll/rx/pitch/ry/yaw/rz of pose1/pose2/return_pose is radian or not
|
|
2571
|
+
:return: tuple((code, pose)), only when code is 0, the returned result is correct.
|
|
2572
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2573
|
+
pose: [x(mm), y(mm), z(mm), roll/rx(rad or °), pitch/ry(rad or °), yaw/rz(rad or °)]
|
|
2574
|
+
"""
|
|
2575
|
+
return self._arm.get_pose_offset(pose1, pose2, orient_type_in=orient_type_in, orient_type_out=orient_type_out,
|
|
2576
|
+
is_radian=is_radian)
|
|
2577
|
+
|
|
2578
|
+
def get_position_aa(self, is_radian=None):
|
|
2579
|
+
"""
|
|
2580
|
+
Get the pose represented by the axis angle pose
|
|
2581
|
+
|
|
2582
|
+
:param is_radian: the returned value (only rx/ry/rz) is in radians or not, default is self.default_is_radian
|
|
2583
|
+
:return: tuple((code, [x, y, z, rx, ry, rz])), only when code is 0, the returned result is correct.
|
|
2584
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2585
|
+
"""
|
|
2586
|
+
return self._arm.get_position_aa(is_radian=is_radian)
|
|
2587
|
+
|
|
2588
|
+
def get_joints_torque(self):
|
|
2589
|
+
"""
|
|
2590
|
+
Get joints torque
|
|
2591
|
+
|
|
2592
|
+
:return: tuple((code, joints_torque))
|
|
2593
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2594
|
+
joints_torque: joints torque
|
|
2595
|
+
"""
|
|
2596
|
+
return self._arm.get_joints_torque()
|
|
2597
|
+
|
|
2598
|
+
# This interface is no longer supported
|
|
2599
|
+
# def set_joints_torque(self, joints_torque):
|
|
2600
|
+
# """
|
|
2601
|
+
# Set joints torque,
|
|
2602
|
+
# Warning: If necessary, please do not set it randomly, it may damage the robot arm
|
|
2603
|
+
|
|
2604
|
+
# :param joints_torque:
|
|
2605
|
+
# :return: code
|
|
2606
|
+
# code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2607
|
+
# """
|
|
2608
|
+
# return self._arm.set_joints_torque(joints_torque)
|
|
2609
|
+
|
|
2610
|
+
def get_safe_level(self):
|
|
2611
|
+
"""
|
|
2612
|
+
Get safe level
|
|
2613
|
+
|
|
2614
|
+
:return: tuple((code, safe_level))
|
|
2615
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2616
|
+
safe_level: safe level
|
|
2617
|
+
"""
|
|
2618
|
+
return self._arm.get_safe_level()
|
|
2619
|
+
|
|
2620
|
+
def set_safe_level(self, level=4):
|
|
2621
|
+
"""
|
|
2622
|
+
Set safe level,
|
|
2623
|
+
|
|
2624
|
+
:param level: safe level, default is 4
|
|
2625
|
+
:return: code
|
|
2626
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2627
|
+
"""
|
|
2628
|
+
return self._arm.set_safe_level(level=level)
|
|
2629
|
+
|
|
2630
|
+
def set_timeout(self, timeout):
|
|
2631
|
+
"""
|
|
2632
|
+
Set the timeout of cmd response
|
|
2633
|
+
|
|
2634
|
+
:param timeout: seconds
|
|
2635
|
+
"""
|
|
2636
|
+
return self._arm.set_timeout(timeout)
|
|
2637
|
+
|
|
2638
|
+
def set_baud_checkset_enable(self, enable):
|
|
2639
|
+
"""
|
|
2640
|
+
Enable auto checkset the baudrate of the end IO board or not
|
|
2641
|
+
Note:
|
|
2642
|
+
only available in the API of gripper/bio/robotiq/linear_track.
|
|
2643
|
+
|
|
2644
|
+
:param enable: True/False
|
|
2645
|
+
:return: code
|
|
2646
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2647
|
+
"""
|
|
2648
|
+
return self._arm.set_baud_checkset_enable(enable)
|
|
2649
|
+
|
|
2650
|
+
def set_checkset_default_baud(self, type_, baud):
|
|
2651
|
+
"""
|
|
2652
|
+
Set the checkset baud value
|
|
2653
|
+
|
|
2654
|
+
:param type_: checkset type
|
|
2655
|
+
1: xarm gripper
|
|
2656
|
+
2: bio gripper
|
|
2657
|
+
3: robotiq gripper
|
|
2658
|
+
4: linear track
|
|
2659
|
+
:param baud: checkset baud value, less than or equal to 0 means disable checkset
|
|
2660
|
+
:return: code
|
|
2661
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2662
|
+
"""
|
|
2663
|
+
return self._arm.set_checkset_default_baud(type_, baud)
|
|
2664
|
+
|
|
2665
|
+
def get_checkset_default_baud(self, type_):
|
|
2666
|
+
"""
|
|
2667
|
+
Get the checkset baud value
|
|
2668
|
+
|
|
2669
|
+
:param type_: checkset type
|
|
2670
|
+
1: xarm gripper
|
|
2671
|
+
2: bio gripper
|
|
2672
|
+
3: robotiq gripper
|
|
2673
|
+
4: linear track
|
|
2674
|
+
:return: tuple((code, baud))
|
|
2675
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2676
|
+
baud: the checkset baud value
|
|
2677
|
+
"""
|
|
2678
|
+
return self._arm.get_checkset_default_baud(type_)
|
|
2679
|
+
|
|
2680
|
+
def robotiq_reset(self):
|
|
2681
|
+
"""
|
|
2682
|
+
Reset the robotiq gripper (clear previous activation if any)
|
|
2683
|
+
|
|
2684
|
+
:return: tuple((code, robotiq_response))
|
|
2685
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2686
|
+
robotiq_response: See the robotiq documentation
|
|
2687
|
+
"""
|
|
2688
|
+
return self._arm.robotiq_reset()
|
|
2689
|
+
|
|
2690
|
+
def robotiq_set_activate(self, wait=True, timeout=3):
|
|
2691
|
+
"""
|
|
2692
|
+
If not already activated. Activate the robotiq gripper
|
|
2693
|
+
|
|
2694
|
+
:param wait: whether to wait for the robotiq activate complete, default is True
|
|
2695
|
+
:param timeout: maximum waiting time(unit: second), default is 3, only available if wait=True
|
|
2696
|
+
|
|
2697
|
+
:return: tuple((code, robotiq_response))
|
|
2698
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2699
|
+
robotiq_response: See the robotiq documentation
|
|
2700
|
+
"""
|
|
2701
|
+
return self._arm.robotiq_set_activate(wait=wait, timeout=timeout)
|
|
2702
|
+
|
|
2703
|
+
def robotiq_set_position(self, pos, speed=0xFF, force=0xFF, wait=True, timeout=5, **kwargs):
|
|
2704
|
+
"""
|
|
2705
|
+
Go to the position with determined speed and force.
|
|
2706
|
+
|
|
2707
|
+
:param pos: position of the gripper. Integer between 0 and 255. 0 being the open position and 255 being the close position.
|
|
2708
|
+
:param speed: gripper speed between 0 and 255
|
|
2709
|
+
:param force: gripper force between 0 and 255
|
|
2710
|
+
:param wait: whether to wait for the robotion motion complete, default is True
|
|
2711
|
+
:param timeout: maximum waiting time(unit: second), default is 5, only available if wait=True
|
|
2712
|
+
|
|
2713
|
+
:return: tuple((code, robotiq_response))
|
|
2714
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2715
|
+
robotiq_response: See the robotiq documentation
|
|
2716
|
+
"""
|
|
2717
|
+
return self._arm.robotiq_set_position(pos, speed=speed, force=force, wait=wait, timeout=timeout, **kwargs)
|
|
2718
|
+
|
|
2719
|
+
def robotiq_open(self, speed=0xFF, force=0xFF, wait=True, timeout=5, **kwargs):
|
|
2720
|
+
"""
|
|
2721
|
+
Open the robotiq gripper
|
|
2722
|
+
|
|
2723
|
+
:param speed: gripper speed between 0 and 255
|
|
2724
|
+
:param force: gripper force between 0 and 255
|
|
2725
|
+
:param wait: whether to wait for the robotiq motion to complete, default is True
|
|
2726
|
+
:param timeout: maximum waiting time(unit: second), default is 5, only available if wait=True
|
|
2727
|
+
|
|
2728
|
+
:return: tuple((code, robotiq_response))
|
|
2729
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2730
|
+
robotiq_response: See the robotiq documentation
|
|
2731
|
+
"""
|
|
2732
|
+
return self._arm.robotiq_open(speed=speed, force=force, wait=wait, timeout=timeout, **kwargs)
|
|
2733
|
+
|
|
2734
|
+
def robotiq_close(self, speed=0xFF, force=0xFF, wait=True, timeout=5, **kwargs):
|
|
2735
|
+
"""
|
|
2736
|
+
Close the robotiq gripper
|
|
2737
|
+
|
|
2738
|
+
:param speed: gripper speed between 0 and 255
|
|
2739
|
+
:param force: gripper force between 0 and 255
|
|
2740
|
+
:param wait: whether to wait for the robotiq motion to complete, default is True
|
|
2741
|
+
:param timeout: maximum waiting time(unit: second), default is 3, only available if wait=True
|
|
2742
|
+
|
|
2743
|
+
:return: tuple((code, robotiq_response))
|
|
2744
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2745
|
+
robotiq_response: See the robotiq documentation
|
|
2746
|
+
"""
|
|
2747
|
+
return self._arm.robotiq_close(speed=speed, force=force, wait=wait, timeout=timeout, **kwargs)
|
|
2748
|
+
|
|
2749
|
+
def robotiq_get_status(self, number_of_registers=3):
|
|
2750
|
+
"""
|
|
2751
|
+
Reading the status of robotiq gripper
|
|
2752
|
+
|
|
2753
|
+
:param number_of_registers: number of registers, 1/2/3, default is 3
|
|
2754
|
+
number_of_registers=1: reading the content of register 0x07D0
|
|
2755
|
+
number_of_registers=2: reading the content of register 0x07D0/0x07D1
|
|
2756
|
+
number_of_registers=3: reading the content of register 0x07D0/0x07D1/0x07D2
|
|
2757
|
+
|
|
2758
|
+
Note:
|
|
2759
|
+
register 0x07D0: Register GRIPPER STATUS
|
|
2760
|
+
register 0x07D1: Register FAULT STATUS and register POSITION REQUEST ECHO
|
|
2761
|
+
register 0x07D2: Register POSITION and register CURRENT
|
|
2762
|
+
:return: tuple((code, robotiq_response))
|
|
2763
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2764
|
+
robotiq_response: See the robotiq documentation
|
|
2765
|
+
"""
|
|
2766
|
+
return self._arm.robotiq_get_status(number_of_registers=number_of_registers)
|
|
2767
|
+
|
|
2768
|
+
@property
|
|
2769
|
+
def robotiq_status(self):
|
|
2770
|
+
"""
|
|
2771
|
+
The last state value obtained
|
|
2772
|
+
|
|
2773
|
+
Note:
|
|
2774
|
+
1. Successfully call the robotiq related interface with wait parameter (when the parameter wait = True is set) will update this value
|
|
2775
|
+
2. Successfully calling interface robotiq_get_status will partially or completely update this value
|
|
2776
|
+
|
|
2777
|
+
:return status dict
|
|
2778
|
+
{
|
|
2779
|
+
'gOBJ': 0, # Object detection status, is a built-in feature that provides information on possible object pick-up
|
|
2780
|
+
'gSTA': 0, # Gripper status, returns the current status & motion of the Gripper fingers
|
|
2781
|
+
'gGTO': 0, # Action status, echo of the rGTO bit(go to bit)
|
|
2782
|
+
'gACT': 0, # Activation status, echo of the rACT bit(activation bit)
|
|
2783
|
+
'kFLT': 0, # Echo of the requested position for the Gripper
|
|
2784
|
+
'gFLT': 0, # Fault status
|
|
2785
|
+
'gPR': 0, # Echo of the requested position for the Gripper
|
|
2786
|
+
'gPO': 0, # Actual position of the Gripper obtained via the encoders
|
|
2787
|
+
'gCU': 0, # The current is read instantaneously from the motor drive
|
|
2788
|
+
}
|
|
2789
|
+
Note: -1 means never updated
|
|
2790
|
+
"""
|
|
2791
|
+
return self._arm.robotiq_status
|
|
2792
|
+
|
|
2793
|
+
def set_bio_gripper_enable(self, enable=True, wait=True, timeout=3):
|
|
2794
|
+
"""
|
|
2795
|
+
If not already enabled. Enable the bio gripper
|
|
2796
|
+
|
|
2797
|
+
:param enable: enable or not
|
|
2798
|
+
:param wait: whether to wait for the bio gripper enable complete, default is True
|
|
2799
|
+
:param timeout: maximum waiting time(unit: second), default is 3, only available if wait=True
|
|
2800
|
+
|
|
2801
|
+
:return: code
|
|
2802
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2803
|
+
"""
|
|
2804
|
+
return self._arm.set_bio_gripper_enable(enable, wait=wait, timeout=timeout)
|
|
2805
|
+
|
|
2806
|
+
def set_bio_gripper_speed(self, speed):
|
|
2807
|
+
"""
|
|
2808
|
+
Set the speed of the bio gripper
|
|
2809
|
+
|
|
2810
|
+
:param speed: speed
|
|
2811
|
+
|
|
2812
|
+
:return: code
|
|
2813
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2814
|
+
"""
|
|
2815
|
+
return self._arm.set_bio_gripper_speed(speed)
|
|
2816
|
+
|
|
2817
|
+
def set_bio_gripper_control_mode(self, mode):
|
|
2818
|
+
"""
|
|
2819
|
+
Set the bio gripper control mode
|
|
2820
|
+
Note:
|
|
2821
|
+
1. Only available in the new version of BIO Gripper
|
|
2822
|
+
|
|
2823
|
+
:param mode: mode
|
|
2824
|
+
0: bio gripper opening and closing mode
|
|
2825
|
+
1: position loop mode
|
|
2826
|
+
|
|
2827
|
+
:return: code
|
|
2828
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2829
|
+
"""
|
|
2830
|
+
|
|
2831
|
+
return self._arm.set_bio_gripper_control_mode(mode)
|
|
2832
|
+
|
|
2833
|
+
def set_bio_gripper_force(self, force):
|
|
2834
|
+
"""
|
|
2835
|
+
Set the bio gripper force
|
|
2836
|
+
Note:
|
|
2837
|
+
1. Only available in the new version of BIO Gripper
|
|
2838
|
+
|
|
2839
|
+
:param force: gripper force between 10 and 100
|
|
2840
|
+
|
|
2841
|
+
:return: code
|
|
2842
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2843
|
+
"""
|
|
2844
|
+
|
|
2845
|
+
return self._arm.set_bio_gripper_force(force)
|
|
2846
|
+
|
|
2847
|
+
def set_bio_gripper_position(self, pos, speed=0, force=100, wait=True, timeout=5, **kwargs):
|
|
2848
|
+
"""
|
|
2849
|
+
Set the bio gripper position
|
|
2850
|
+
|
|
2851
|
+
:param pos: gripper pos between 71 and 150
|
|
2852
|
+
:param speed: gripper speed between 0 and 4500
|
|
2853
|
+
:param force: gripper force between 10 and 100
|
|
2854
|
+
:param wait: whether to wait for the robotiq motion to complete, default is True
|
|
2855
|
+
:param timeout: maximum waiting time(unit: second), default is 5, only available if wait=True
|
|
2856
|
+
|
|
2857
|
+
:return: tuple((code, robotiq_response))
|
|
2858
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2859
|
+
robotiq_response: See the robotiq documentation
|
|
2860
|
+
"""
|
|
2861
|
+
return self._arm.set_bio_gripper_position(pos, speed=speed, force=force, wait=wait, timeout=timeout, **kwargs)
|
|
2862
|
+
|
|
2863
|
+
def open_bio_gripper(self, speed=0, wait=True, timeout=5, **kwargs):
|
|
2864
|
+
"""
|
|
2865
|
+
Open the bio gripper
|
|
2866
|
+
|
|
2867
|
+
:param speed: speed value, default is 0 (not set the speed)
|
|
2868
|
+
:param wait: whether to wait for the bio gripper motion complete, default is True
|
|
2869
|
+
:param timeout: maximum waiting time(unit: second), default is 5, only available if wait=True
|
|
2870
|
+
|
|
2871
|
+
:return: code
|
|
2872
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2873
|
+
"""
|
|
2874
|
+
return self._arm.open_bio_gripper(speed=speed, wait=wait, timeout=timeout, **kwargs)
|
|
2875
|
+
|
|
2876
|
+
def close_bio_gripper(self, speed=0, wait=True, timeout=5, **kwargs):
|
|
2877
|
+
"""
|
|
2878
|
+
Close the bio gripper
|
|
2879
|
+
|
|
2880
|
+
:param speed: speed value, default is 0 (not set the speed)
|
|
2881
|
+
:param wait: whether to wait for the bio gripper motion complete, default is True
|
|
2882
|
+
:param timeout: maximum waiting time(unit: second), default is 5, only available if wait=True
|
|
2883
|
+
|
|
2884
|
+
:return: code
|
|
2885
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2886
|
+
"""
|
|
2887
|
+
return self._arm.close_bio_gripper(speed=speed, wait=wait, timeout=timeout, **kwargs)
|
|
2888
|
+
|
|
2889
|
+
def get_bio_gripper_status(self):
|
|
2890
|
+
"""
|
|
2891
|
+
Get the status of the bio gripper
|
|
2892
|
+
|
|
2893
|
+
:return: tuple((code, status))
|
|
2894
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2895
|
+
status: status
|
|
2896
|
+
status & 0x03 == 0: stop
|
|
2897
|
+
status & 0x03 == 1: motion
|
|
2898
|
+
status & 0x03 == 2: catch
|
|
2899
|
+
status & 0x03 == 3: error
|
|
2900
|
+
(status >> 2) & 0x03 == 0: not enabled
|
|
2901
|
+
(status >> 2) & 0x03 == 1: enabling
|
|
2902
|
+
(status >> 2) & 0x03 == 2: enabled
|
|
2903
|
+
"""
|
|
2904
|
+
return self._arm.get_bio_gripper_status()
|
|
2905
|
+
|
|
2906
|
+
def get_bio_gripper_error(self):
|
|
2907
|
+
"""
|
|
2908
|
+
Get the error code of the bio gripper
|
|
2909
|
+
|
|
2910
|
+
:return: tuple((code, error_code))
|
|
2911
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2912
|
+
error_code: See the [Bio Gripper Error Code Documentation](./xarm_api_code.md#bio-gripper-error-code) for details.
|
|
2913
|
+
"""
|
|
2914
|
+
return self._arm.get_bio_gripper_error()
|
|
2915
|
+
|
|
2916
|
+
def clean_bio_gripper_error(self):
|
|
2917
|
+
"""
|
|
2918
|
+
Clean the error code of the bio gripper
|
|
2919
|
+
|
|
2920
|
+
:return: code
|
|
2921
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2922
|
+
"""
|
|
2923
|
+
return self._arm.clean_bio_gripper_error()
|
|
2924
|
+
|
|
2925
|
+
def set_tgpio_modbus_timeout(self, timeout, is_transparent_transmission=False, **kwargs):
|
|
2926
|
+
"""
|
|
2927
|
+
Set the modbus timeout of the tool gpio
|
|
2928
|
+
|
|
2929
|
+
:param timeout: timeout, milliseconds
|
|
2930
|
+
:param is_transparent_transmission: whether the set timeout is the timeout of transparent transmission
|
|
2931
|
+
Note: only available if firmware_version >= 1.11.0
|
|
2932
|
+
|
|
2933
|
+
:return: code
|
|
2934
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2935
|
+
"""
|
|
2936
|
+
return self._arm.set_tgpio_modbus_timeout(timeout, is_transparent_transmission=is_transparent_transmission, **kwargs)
|
|
2937
|
+
|
|
2938
|
+
def set_tgpio_modbus_baudrate(self, baud):
|
|
2939
|
+
"""
|
|
2940
|
+
Set the modbus baudrate of the tool gpio
|
|
2941
|
+
|
|
2942
|
+
:param baud: 4800/9600/19200/38400/57600/115200/230400/460800/921600/1000000/1500000/2000000/2500000
|
|
2943
|
+
|
|
2944
|
+
:return: code
|
|
2945
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2946
|
+
"""
|
|
2947
|
+
return self._arm.set_tgpio_modbus_baudrate(baud)
|
|
2948
|
+
|
|
2949
|
+
def get_tgpio_modbus_baudrate(self):
|
|
2950
|
+
"""
|
|
2951
|
+
Get the modbus baudrate of the tool gpio
|
|
2952
|
+
|
|
2953
|
+
:return: tuple((code, baudrate)), only when code is 0, the returned result is correct.
|
|
2954
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2955
|
+
baudrate: the modbus baudrate of the tool gpio
|
|
2956
|
+
"""
|
|
2957
|
+
return self._arm.get_tgpio_modbus_baudrate()
|
|
2958
|
+
|
|
2959
|
+
def set_control_modbus_baudrate(self, baud):
|
|
2960
|
+
"""
|
|
2961
|
+
Set the modbus baudrate of the control box
|
|
2962
|
+
|
|
2963
|
+
:param baud: 4800/9600/19200/38400/57600/115200/230400/460800/921600/1000000/1500000/2000000/2500000
|
|
2964
|
+
|
|
2965
|
+
:return: code
|
|
2966
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2967
|
+
"""
|
|
2968
|
+
return self._arm.set_control_modbus_baudrate(baud)
|
|
2969
|
+
|
|
2970
|
+
def getset_tgpio_modbus_data(self, datas, min_res_len=0, host_id=9, is_transparent_transmission=False, use_503_port=False, **kwargs):
|
|
2971
|
+
"""
|
|
2972
|
+
Send the modbus data to the tool gpio
|
|
2973
|
+
|
|
2974
|
+
:param datas: data_list
|
|
2975
|
+
:param min_res_len: the minimum length of modbus response data. Used to check the data length, if not specified, no check
|
|
2976
|
+
:param host_id: host_id, default is 9 (TGPIO_HOST_ID)
|
|
2977
|
+
9: END RS485
|
|
2978
|
+
10: CONTROLLER RS485
|
|
2979
|
+
:param is_transparent_transmission: whether to choose transparent transmission, default is False
|
|
2980
|
+
Note: only available if firmware_version >= 1.11.0
|
|
2981
|
+
:param use_503_port: whether to use port 503 for communication, default is False
|
|
2982
|
+
Note: if it is True, it will connect to 503 port for communication when it is used for the first time, which is generally only useful for transparent transmission.
|
|
2983
|
+
Note: only available if firmware_version >= 1.11.0
|
|
2984
|
+
|
|
2985
|
+
:return: tuple((code, modbus_response))
|
|
2986
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
2987
|
+
modbus_response: modbus response data
|
|
2988
|
+
"""
|
|
2989
|
+
return self._arm.getset_tgpio_modbus_data(datas, min_res_len=min_res_len, host_id=host_id, is_transparent_transmission=is_transparent_transmission, use_503_port=use_503_port, **kwargs)
|
|
2990
|
+
|
|
2991
|
+
def set_report_tau_or_i(self, tau_or_i=0):
|
|
2992
|
+
"""
|
|
2993
|
+
Set the reported torque or electric current
|
|
2994
|
+
|
|
2995
|
+
:param tau_or_i:
|
|
2996
|
+
0: torque
|
|
2997
|
+
1: electric current
|
|
2998
|
+
|
|
2999
|
+
:return: code
|
|
3000
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3001
|
+
"""
|
|
3002
|
+
return self._arm.set_report_tau_or_i(tau_or_i=tau_or_i)
|
|
3003
|
+
|
|
3004
|
+
def get_report_tau_or_i(self):
|
|
3005
|
+
"""
|
|
3006
|
+
Get the reported torque or electric current
|
|
3007
|
+
|
|
3008
|
+
:return: tuple((code, tau_or_i))
|
|
3009
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3010
|
+
tau_or_i:
|
|
3011
|
+
0: torque
|
|
3012
|
+
1: electric current
|
|
3013
|
+
"""
|
|
3014
|
+
return self._arm.get_report_tau_or_i()
|
|
3015
|
+
|
|
3016
|
+
def set_self_collision_detection(self, on_off):
|
|
3017
|
+
"""
|
|
3018
|
+
Set whether to enable self-collision detection
|
|
3019
|
+
|
|
3020
|
+
:param on_off: enable or not
|
|
3021
|
+
|
|
3022
|
+
:return: code
|
|
3023
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3024
|
+
"""
|
|
3025
|
+
return self._arm.set_self_collision_detection(on_off)
|
|
3026
|
+
|
|
3027
|
+
def set_collision_tool_model(self, tool_type, *args, **kwargs):
|
|
3028
|
+
"""
|
|
3029
|
+
Set the geometric model of the end effector for self collision detection
|
|
3030
|
+
|
|
3031
|
+
:param tool_type: the geometric model type
|
|
3032
|
+
0: No end effector, no additional parameters required
|
|
3033
|
+
1: xArm Gripper, no additional parameters required
|
|
3034
|
+
2: xArm Vacuum Gripper, no additional parameters required
|
|
3035
|
+
3: xArm Bio Gripper, no additional parameters required
|
|
3036
|
+
4: Robotiq-2F-85 Gripper, no additional parameters required
|
|
3037
|
+
5: Robotiq-2F-140 Gripper, no additional parameters required
|
|
3038
|
+
21: Cylinder, need additional parameters radius, height
|
|
3039
|
+
self.set_collision_tool_model(21, radius=45, height=137)
|
|
3040
|
+
:param radius: the radius of cylinder, (unit: mm)
|
|
3041
|
+
:param height: the height of cylinder, (unit: mm)
|
|
3042
|
+
22: Cuboid, need additional parameters x, y, z
|
|
3043
|
+
self.set_collision_tool_model(22, x=234, y=323, z=23)
|
|
3044
|
+
:param x: the length of the cuboid in the x coordinate direction, (unit: mm)
|
|
3045
|
+
:param y: the length of the cuboid in the y coordinate direction, (unit: mm)
|
|
3046
|
+
:param z: the length of the cuboid in the z coordinate direction, (unit: mm)
|
|
3047
|
+
:param args: additional parameters
|
|
3048
|
+
:param kwargs: additional parameters
|
|
3049
|
+
:return: code
|
|
3050
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3051
|
+
"""
|
|
3052
|
+
return self._arm.set_collision_tool_model(tool_type, *args, **kwargs)
|
|
3053
|
+
|
|
3054
|
+
def set_simulation_robot(self, on_off):
|
|
3055
|
+
"""
|
|
3056
|
+
Set the simulation robot
|
|
3057
|
+
|
|
3058
|
+
:param on_off: True/False
|
|
3059
|
+
:return: code
|
|
3060
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3061
|
+
"""
|
|
3062
|
+
return self._arm.set_simulation_robot(on_off)
|
|
3063
|
+
|
|
3064
|
+
def vc_set_joint_velocity(self, speeds, is_radian=None, is_sync=True, duration=-1, **kwargs):
|
|
3065
|
+
"""
|
|
3066
|
+
Joint velocity control, need to be set to joint velocity control mode(self.set_mode(4))
|
|
3067
|
+
Note:
|
|
3068
|
+
1. only available if firmware_version >= 1.6.9
|
|
3069
|
+
|
|
3070
|
+
:param speeds: [spd_J1, spd_J2, ..., spd_J7]
|
|
3071
|
+
:param is_radian: the spd_Jx in radians or not, default is self.default_is_radian
|
|
3072
|
+
:param is_sync: whether all joints accelerate and decelerate synchronously, default is True
|
|
3073
|
+
:param duration: The duration of this speed command, over this time will automatically set the speed to 0
|
|
3074
|
+
Note: only available if firmware_version >= 1.8.0
|
|
3075
|
+
duration > 0: seconds
|
|
3076
|
+
duration == 0: Always effective, will not stop automatically
|
|
3077
|
+
duration < 0: default value, only used to be compatible with the old protocol, equivalent to 0
|
|
3078
|
+
:return: code
|
|
3079
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3080
|
+
"""
|
|
3081
|
+
return self._arm.vc_set_joint_velocity(speeds, is_radian=is_radian, is_sync=is_sync, duration=duration, **kwargs)
|
|
3082
|
+
|
|
3083
|
+
def vc_set_cartesian_velocity(self, speeds, is_radian=None, is_tool_coord=False, duration=-1, **kwargs):
|
|
3084
|
+
"""
|
|
3085
|
+
Cartesian velocity control, need to be set to cartesian velocity control mode(self.set_mode(5))
|
|
3086
|
+
Note:
|
|
3087
|
+
1. only available if firmware_version >= 1.6.9
|
|
3088
|
+
|
|
3089
|
+
:param speeds: [spd_x, spd_y, spd_z, spd_rx, spd_ry, spd_rz]
|
|
3090
|
+
:param is_radian: the spd_rx/spd_ry/spd_rz in radians or not, default is self.default_is_radian
|
|
3091
|
+
:param is_tool_coord: is tool coordinate or not, default is False
|
|
3092
|
+
:param duration: the maximum duration of the speed, over this time will automatically set the speed to 0
|
|
3093
|
+
Note: only available if firmware_version >= 1.8.0
|
|
3094
|
+
duration > 0: seconds, indicates the maximum number of seconds that this speed can be maintained
|
|
3095
|
+
duration == 0: Always effective, will not stop automatically
|
|
3096
|
+
duration < 0: default value, only used to be compatible with the old protocol, equivalent to 0
|
|
3097
|
+
:return: code
|
|
3098
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3099
|
+
"""
|
|
3100
|
+
return self._arm.vc_set_cartesian_velocity(speeds, is_radian=is_radian, is_tool_coord=is_tool_coord, duration=duration, **kwargs)
|
|
3101
|
+
|
|
3102
|
+
def calibrate_tcp_coordinate_offset(self, four_points, is_radian=None):
|
|
3103
|
+
"""
|
|
3104
|
+
Four-point method to calibrate tool coordinate system position offset
|
|
3105
|
+
Note:
|
|
3106
|
+
1. only available if firmware_version >= 1.6.9
|
|
3107
|
+
|
|
3108
|
+
:param four_points: a list of four teaching coordinate positions [x, y, z, roll, pitch, yaw]
|
|
3109
|
+
:param is_radian: the roll/pitch/yaw value of the each point in radians or not, default is self.default_is_radian
|
|
3110
|
+
:return: tuple((code, xyz_offset)), only when code is 0, the returned result is correct.
|
|
3111
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3112
|
+
xyz_offset: calculated xyz(mm) TCP offset, [x, y, z]
|
|
3113
|
+
"""
|
|
3114
|
+
return self._arm.calibrate_tcp_coordinate_offset(four_points, is_radian=is_radian)
|
|
3115
|
+
|
|
3116
|
+
def calibrate_tcp_orientation_offset(self, rpy_be, rpy_bt, input_is_radian=None, return_is_radian=None):
|
|
3117
|
+
"""
|
|
3118
|
+
An additional teaching point to calibrate the tool coordinate system attitude offset
|
|
3119
|
+
Note:
|
|
3120
|
+
1. only available if firmware_version >= 1.6.9
|
|
3121
|
+
|
|
3122
|
+
:param rpy_be: the rpy value of the teaching point without TCP offset [roll, pitch, yaw]
|
|
3123
|
+
:param rpy_bt: the rpy value of the teaching point with TCP offset [roll, pitch, yaw]
|
|
3124
|
+
:param input_is_radian: the roll/pitch/yaw value of rpy_be and rpy_bt in radians or not, default is self.default_is_radian
|
|
3125
|
+
:param return_is_radian: the roll/pitch/yaw value of result in radians or not, default is self.default_is_radian
|
|
3126
|
+
:return: tuple((code, rpy_offset)), only when code is 0, the returned result is correct.
|
|
3127
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3128
|
+
rpy_offset: calculated rpy TCP offset, [roll, pitch, yaw]
|
|
3129
|
+
"""
|
|
3130
|
+
return self._arm.calibrate_tcp_orientation_offset(rpy_be, rpy_bt, input_is_radian=input_is_radian, return_is_radian=return_is_radian)
|
|
3131
|
+
|
|
3132
|
+
def calibrate_user_orientation_offset(self, three_points, mode=0, trust_ind=0, input_is_radian=None, return_is_radian=None):
|
|
3133
|
+
"""
|
|
3134
|
+
Three-point method teaches user coordinate system posture offset
|
|
3135
|
+
Note:
|
|
3136
|
+
1. only available if firmware_version >= 1.6.9
|
|
3137
|
+
|
|
3138
|
+
Note:
|
|
3139
|
+
First determine a point in the working space, move along the desired coordinate system x+ to determine the second point,
|
|
3140
|
+
and then move along the desired coordinate system y+ to determine the third point.
|
|
3141
|
+
Note that the x+ direction is as accurate as possible.
|
|
3142
|
+
If the y+ direction is not completely perpendicular to x+, it will be corrected in the calculation process.
|
|
3143
|
+
|
|
3144
|
+
:param three_points: a list of teaching TCP coordinate positions [x, y, z, roll, pitch, yaw]
|
|
3145
|
+
:param input_is_radian: the roll/pitch/yaw value of the each point in radians or not, default is self.default_is_radian
|
|
3146
|
+
:param return_is_radian: the roll/pitch/yaw value of result in radians or not, default is self.default_is_radian
|
|
3147
|
+
:return: tuple((code, rpy_offset)), only when code is 0, the returned result is correct.
|
|
3148
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3149
|
+
rpy_offset: calculated rpy user offset, [roll, pitch, yaw]
|
|
3150
|
+
"""
|
|
3151
|
+
return self._arm.calibrate_user_orientation_offset(three_points, mode=mode, trust_ind=trust_ind, input_is_radian=input_is_radian, return_is_radian=return_is_radian)
|
|
3152
|
+
|
|
3153
|
+
def calibrate_user_coordinate_offset(self, rpy_ub, pos_b_uorg, is_radian=None):
|
|
3154
|
+
"""
|
|
3155
|
+
An additional teaching point determines the position offset of the user coordinate system.
|
|
3156
|
+
Note:
|
|
3157
|
+
1. only available if firmware_version >= 1.6.9
|
|
3158
|
+
|
|
3159
|
+
:param rpy_ub: the confirmed offset of the base coordinate system in the user coordinate system [roll, pitch, yaw], which is the result of calibrate_user_orientation_offset()
|
|
3160
|
+
:param pos_b_uorg: the position of the teaching point in the base coordinate system [x, y, z], if the arm cannot reach the target position, the user can manually input the position of the target in the base coordinate.
|
|
3161
|
+
:param is_radian: the roll/pitch/yaw value of rpy_ub in radians or not, default is self.default_is_radian
|
|
3162
|
+
:return: tuple((code, xyz_offset)), only when code is 0, the returned result is correct.
|
|
3163
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3164
|
+
xyz_offset: calculated xyz(mm) user offset, [x, y, z]
|
|
3165
|
+
"""
|
|
3166
|
+
return self._arm.calibrate_user_coordinate_offset(rpy_ub, pos_b_uorg, is_radian=is_radian)
|
|
3167
|
+
|
|
3168
|
+
def get_base_board_version(self, board_id=10):
|
|
3169
|
+
"""
|
|
3170
|
+
Get base board version
|
|
3171
|
+
|
|
3172
|
+
:param board_id: int
|
|
3173
|
+
:return: : (code, version)
|
|
3174
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3175
|
+
"""
|
|
3176
|
+
return self._arm.get_base_board_version(board_id)
|
|
3177
|
+
|
|
3178
|
+
def set_impedance(self, coord, c_axis, M, K, B, **kwargs):
|
|
3179
|
+
"""
|
|
3180
|
+
Set all parameters of impedance control through the Six-axis Force Torque Sensor.
|
|
3181
|
+
Note:
|
|
3182
|
+
1. only available if firmware_version >= 1.8.3
|
|
3183
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3184
|
+
|
|
3185
|
+
:param coord: task frame. 0: base frame. 1: tool frame.
|
|
3186
|
+
:param c_axis: a 6d vector of 0s and 1s. 1 means that robot will be impedance in the corresponding axis of the task frame.
|
|
3187
|
+
:param M: mass. (kg)
|
|
3188
|
+
:param K: stiffness coefficient.
|
|
3189
|
+
:param B: damping coefficient. invalid.
|
|
3190
|
+
Note: the value is set to 2*sqrt(M*K) in controller.
|
|
3191
|
+
:return: code
|
|
3192
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3193
|
+
"""
|
|
3194
|
+
return self._arm.set_impedance(coord, c_axis, M, K, B, **kwargs)
|
|
3195
|
+
|
|
3196
|
+
def set_impedance_mbk(self, M, K, B, **kwargs):
|
|
3197
|
+
"""
|
|
3198
|
+
Set mbk parameters of impedance control through the Six-axis Force Torque Sensor.
|
|
3199
|
+
Note:
|
|
3200
|
+
1. only available if firmware_version >= 1.8.3
|
|
3201
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3202
|
+
|
|
3203
|
+
:param M: mass. (kg)
|
|
3204
|
+
:param K: stiffness coefficient.
|
|
3205
|
+
:param B: damping coefficient. invalid.
|
|
3206
|
+
Note: the value is set to 2*sqrt(M*K) in controller.
|
|
3207
|
+
:return: code
|
|
3208
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3209
|
+
"""
|
|
3210
|
+
return self._arm.set_impedance_mbk(M, K, B, **kwargs)
|
|
3211
|
+
|
|
3212
|
+
def set_impedance_config(self, coord, c_axis):
|
|
3213
|
+
"""
|
|
3214
|
+
Set impedance control parameters of impedance control through the Six-axis Force Torque Sensor.
|
|
3215
|
+
Note:
|
|
3216
|
+
1. only available if firmware_version >= 1.8.3
|
|
3217
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3218
|
+
|
|
3219
|
+
:param coord: task frame. 0: base frame. 1: tool frame.
|
|
3220
|
+
:param c_axis: a 6d vector of 0s and 1s. 1 means that robot will be impedance in the corresponding axis of the task frame.
|
|
3221
|
+
:return: code
|
|
3222
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3223
|
+
"""
|
|
3224
|
+
return self._arm.set_impedance_config(coord, c_axis)
|
|
3225
|
+
|
|
3226
|
+
def config_force_control(self, coord, c_axis, f_ref, limits, **kwargs):
|
|
3227
|
+
"""
|
|
3228
|
+
Set force control parameters through the Six-axis Force Torque Sensor.
|
|
3229
|
+
Note:
|
|
3230
|
+
1. only available if firmware_version >= 1.8.3
|
|
3231
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3232
|
+
|
|
3233
|
+
:param coord: task frame. 0: base frame. 1: tool frame.
|
|
3234
|
+
:param c_axis: a 6d vector of 0s and 1s. 1 means that robot will be compliant in the corresponding axis of the task frame.
|
|
3235
|
+
:param f_ref: the forces/torques the robot will apply to its environment. The robot adjusts its position along/about compliant axis in order to achieve the specified force/torque.
|
|
3236
|
+
:param limits: for compliant axes, these values are the maximum allowed tcp speed along/about the axis.
|
|
3237
|
+
:return: code
|
|
3238
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3239
|
+
"""
|
|
3240
|
+
return self._arm.config_force_control(coord, c_axis, f_ref, limits, **kwargs)
|
|
3241
|
+
|
|
3242
|
+
def set_force_control_pid(self, kp, ki, kd, xe_limit, **kwargs):
|
|
3243
|
+
"""
|
|
3244
|
+
Set force control pid parameters through the Six-axis Force Torque Sensor.
|
|
3245
|
+
Note:
|
|
3246
|
+
1. only available if firmware_version >= 1.8.3
|
|
3247
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3248
|
+
|
|
3249
|
+
:param kp: proportional gain.
|
|
3250
|
+
:param ki: integral gain.
|
|
3251
|
+
:param kd: differential gain.
|
|
3252
|
+
:param xe_limit: 6d vector. for compliant axes, these values are the maximum allowed tcp speed along/about the axis. mm/s
|
|
3253
|
+
:return: code
|
|
3254
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3255
|
+
"""
|
|
3256
|
+
return self._arm.set_force_control_pid(kp, ki, kd, xe_limit, **kwargs)
|
|
3257
|
+
|
|
3258
|
+
def ft_sensor_set_zero(self):
|
|
3259
|
+
"""
|
|
3260
|
+
Set the current state to the zero point of the Six-axis Force Torque Sensor
|
|
3261
|
+
Note:
|
|
3262
|
+
1. only available if firmware_version >= 1.8.3
|
|
3263
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3264
|
+
|
|
3265
|
+
:return: code
|
|
3266
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3267
|
+
"""
|
|
3268
|
+
return self._arm.ft_sensor_set_zero()
|
|
3269
|
+
|
|
3270
|
+
def ft_sensor_iden_load(self):
|
|
3271
|
+
"""
|
|
3272
|
+
Identification the tcp load with the the Six-axis Force Torque Sensor
|
|
3273
|
+
Note:
|
|
3274
|
+
1. only available if firmware_version >= 1.8.3
|
|
3275
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3276
|
+
3. starting from SDK v1.11.0, the centroid unit is millimeters (originally meters)
|
|
3277
|
+
|
|
3278
|
+
:return: tuple((code, load)) only when code is 0, the returned result is correct.
|
|
3279
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3280
|
+
load: [mass(kg), x_centroid(mm), y_centroid(mm), z_centroid(mm), Fx_offset, Fy_offset, Fz_offset, Tx_offset, Ty_offset, Tz_ffset]
|
|
3281
|
+
"""
|
|
3282
|
+
return self._arm.ft_sensor_iden_load()
|
|
3283
|
+
|
|
3284
|
+
def ft_sensor_cali_load(self, iden_result_list, association_setting_tcp_load=False, **kwargs):
|
|
3285
|
+
"""
|
|
3286
|
+
Write the load offset parameters identified by the Six-axis Force Torque Sensor
|
|
3287
|
+
Note:
|
|
3288
|
+
1. only available if firmware_version >= 1.8.3
|
|
3289
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3290
|
+
3. starting from SDK v1.11.0, the centroid unit is millimeters (originally meters)
|
|
3291
|
+
|
|
3292
|
+
:param iden_result_list: [mass(kg), x_centroid(mm), y_centroid(mm), z_centroid(mm), Fx_offset, Fy_offset, Fz_offset, Tx_offset, Ty_offset, Tz_ffset]
|
|
3293
|
+
:param association_setting_tcp_load: whether to convert the parameter to the corresponding tcp load and set, default is False
|
|
3294
|
+
Note: If True, the value of tcp load will be modified
|
|
3295
|
+
:return: code
|
|
3296
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3297
|
+
"""
|
|
3298
|
+
return self._arm.ft_sensor_cali_load(iden_result_list, association_setting_tcp_load=association_setting_tcp_load, **kwargs)
|
|
3299
|
+
|
|
3300
|
+
def ft_sensor_enable(self, on_off):
|
|
3301
|
+
"""
|
|
3302
|
+
Used for enabling and disabling the use of the Six-axis Force Torque Sensor measurements in the controller.
|
|
3303
|
+
Note:
|
|
3304
|
+
1. only available if firmware_version >= 1.8.3
|
|
3305
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3306
|
+
|
|
3307
|
+
:param on_off: enable or disable F/T data sampling.
|
|
3308
|
+
:return: code
|
|
3309
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3310
|
+
"""
|
|
3311
|
+
return self._arm.ft_sensor_enable(on_off)
|
|
3312
|
+
|
|
3313
|
+
def ft_sensor_app_set(self, app_code):
|
|
3314
|
+
"""
|
|
3315
|
+
Set robot to be controlled in force mode. (Through the Six-axis Force Torque Sensor)
|
|
3316
|
+
Note:
|
|
3317
|
+
1. only available if firmware_version >= 1.8.3
|
|
3318
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3319
|
+
|
|
3320
|
+
:param app_code: force mode.
|
|
3321
|
+
0: non-force mode
|
|
3322
|
+
1: impendance control
|
|
3323
|
+
2: force control
|
|
3324
|
+
:return: code
|
|
3325
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3326
|
+
"""
|
|
3327
|
+
return self._arm.ft_sensor_app_set(app_code)
|
|
3328
|
+
|
|
3329
|
+
def ft_sensor_app_get(self):
|
|
3330
|
+
"""
|
|
3331
|
+
Get force mode
|
|
3332
|
+
Note:
|
|
3333
|
+
1. only available if firmware_version >= 1.8.3
|
|
3334
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3335
|
+
|
|
3336
|
+
:return: tuple((code, app_code))
|
|
3337
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3338
|
+
app_code:
|
|
3339
|
+
0: non-force mode
|
|
3340
|
+
1: impedance control mode
|
|
3341
|
+
2: force control mode
|
|
3342
|
+
"""
|
|
3343
|
+
return self._arm.ft_sensor_app_get()
|
|
3344
|
+
|
|
3345
|
+
def get_ft_sensor_data(self):
|
|
3346
|
+
"""
|
|
3347
|
+
Get the data of the Six-axis Force Torque Sensor
|
|
3348
|
+
Note:
|
|
3349
|
+
1. only available if firmware_version >= 1.8.3
|
|
3350
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3351
|
+
|
|
3352
|
+
:return: tuple((code, exe_ft))
|
|
3353
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3354
|
+
ft_data: only when code is 0, the returned result is correct.
|
|
3355
|
+
Note: The external force detection value of the Six-axis Force Torque Sensor after filtering, load and offset compensation
|
|
3356
|
+
"""
|
|
3357
|
+
return self._arm.get_ft_sensor_data()
|
|
3358
|
+
|
|
3359
|
+
def get_ft_sensor_config(self):
|
|
3360
|
+
"""
|
|
3361
|
+
Get the config of the Six-axis Force Torque Sensor
|
|
3362
|
+
Note:
|
|
3363
|
+
1. only available if firmware_version >= 1.8.3
|
|
3364
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3365
|
+
|
|
3366
|
+
:return: tuple((code, config))
|
|
3367
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3368
|
+
config: [...], the config of the Six-axis Force Torque Sensor, only when code is 0, the returned result is correct.
|
|
3369
|
+
[0] ft_app_status: force mode
|
|
3370
|
+
0: non-force mode
|
|
3371
|
+
1: impendance control
|
|
3372
|
+
2: force control
|
|
3373
|
+
[1] ft_is_started: ft sensor is enable or not
|
|
3374
|
+
[2] ft_type: ft sensor type
|
|
3375
|
+
[3] ft_id: ft sensor id
|
|
3376
|
+
[4] ft_freq: ft sensor frequency
|
|
3377
|
+
[5] ft_mass: load mass
|
|
3378
|
+
[6] ft_dir_bias: reversed
|
|
3379
|
+
[7] ft_centroid: [x_centroid, y_centroid, z_centroid]
|
|
3380
|
+
[8] ft_zero: [Fx_offset, Fy_offset, Fz_offset, Tx_offset, Ty_offset, Tz_ffset]
|
|
3381
|
+
[9] imp_coord: task frame of impendance control mode.
|
|
3382
|
+
0: base frame.
|
|
3383
|
+
1: tool frame.
|
|
3384
|
+
[10] imp_c_axis: a 6d vector of 0s and 1s. 1 means that robot will be impedance in the corresponding axis of the task frame.
|
|
3385
|
+
[11] M: mass. (kg)
|
|
3386
|
+
[12] K: stiffness coefficient.
|
|
3387
|
+
[13] B: damping coefficient. invalid. Note: the value is set to 2*sqrt(M*K) in controller.
|
|
3388
|
+
[14] f_coord: task frame of force control mode.
|
|
3389
|
+
0: base frame.
|
|
3390
|
+
1: tool frame.
|
|
3391
|
+
[15] f_c_axis: a 6d vector of 0s and 1s. 1 means that robot will be impedance in the corresponding axis of the task frame.
|
|
3392
|
+
[16] f_ref: the forces/torques the robot will apply to its environment. The robot adjusts its position along/about compliant axis in order to achieve the specified force/torque.
|
|
3393
|
+
[17] f_limits: reversed.
|
|
3394
|
+
[18] kp: proportional gain
|
|
3395
|
+
[19] ki: integral gain.
|
|
3396
|
+
[20] kd: differential gain.
|
|
3397
|
+
[21] xe_limit: 6d vector. for compliant axes, these values are the maximum allowed tcp speed along/about the axis. mm/s
|
|
3398
|
+
"""
|
|
3399
|
+
return self._arm.get_ft_sensor_config()
|
|
3400
|
+
|
|
3401
|
+
def get_ft_sensor_error(self):
|
|
3402
|
+
"""
|
|
3403
|
+
Get the error code of the Six-axis Force Torque Sensor
|
|
3404
|
+
Note:
|
|
3405
|
+
1. only available if firmware_version >= 1.8.3
|
|
3406
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
3407
|
+
|
|
3408
|
+
:return: tuple((code, error))
|
|
3409
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3410
|
+
error: See the [Six-axis Force Torque Sensor Error Code Documentation](./xarm_api_code.md#six-axis-force-torque-sensor-error-code) for details.
|
|
3411
|
+
"""
|
|
3412
|
+
return self._arm.get_ft_sensor_error()
|
|
3413
|
+
|
|
3414
|
+
def iden_tcp_load(self, estimated_mass=0):
|
|
3415
|
+
"""
|
|
3416
|
+
Identification the tcp load with current
|
|
3417
|
+
Note:
|
|
3418
|
+
1. only available if firmware_version >= 1.8.0
|
|
3419
|
+
|
|
3420
|
+
:param estimated_mass: estimated mass
|
|
3421
|
+
Note: this parameter is only available on the lite6 model manipulator, and this parameter must be specified for the lite6 model manipulator
|
|
3422
|
+
:return: tuple((code, load)) only when code is 0, the returned result is correct.
|
|
3423
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3424
|
+
load: [mass, x_centroid, y_centroid, z_centroid]
|
|
3425
|
+
"""
|
|
3426
|
+
return self._arm.iden_tcp_load(estimated_mass)
|
|
3427
|
+
|
|
3428
|
+
def get_linear_track_registers(self, **kwargs):
|
|
3429
|
+
"""
|
|
3430
|
+
Get the status of the linear track
|
|
3431
|
+
Note:
|
|
3432
|
+
1. only available if firmware_version >= 1.8.0
|
|
3433
|
+
|
|
3434
|
+
:return: tuple((code, status)) only when code is 0, the returned result is correct.
|
|
3435
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3436
|
+
status: status, like
|
|
3437
|
+
{
|
|
3438
|
+
'pos': 0,
|
|
3439
|
+
'status': 0,
|
|
3440
|
+
'error': 0,
|
|
3441
|
+
'is_enabled': 0,
|
|
3442
|
+
'on_zero': 0,
|
|
3443
|
+
'sci': 1,
|
|
3444
|
+
'sco': [0, 0],
|
|
3445
|
+
}
|
|
3446
|
+
"""
|
|
3447
|
+
return self._arm.get_linear_track_registers(**kwargs)
|
|
3448
|
+
|
|
3449
|
+
def get_linear_track_pos(self):
|
|
3450
|
+
"""
|
|
3451
|
+
Get the pos of the linear track
|
|
3452
|
+
Note:
|
|
3453
|
+
1. only available if firmware_version >= 1.8.0
|
|
3454
|
+
|
|
3455
|
+
:return: tuple((code, position)) only when code is 0, the returned result is correct.
|
|
3456
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3457
|
+
position: position
|
|
3458
|
+
"""
|
|
3459
|
+
return self._arm.get_linear_track_pos()
|
|
3460
|
+
|
|
3461
|
+
def get_linear_track_status(self):
|
|
3462
|
+
"""
|
|
3463
|
+
Get the status of the linear track
|
|
3464
|
+
Note:
|
|
3465
|
+
1. only available if firmware_version >= 1.8.0
|
|
3466
|
+
|
|
3467
|
+
:return: tuple((code, status)) only when code is 0, the returned result is correct.
|
|
3468
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3469
|
+
status: status
|
|
3470
|
+
status & 0x00: motion finish
|
|
3471
|
+
status & 0x01: in motion
|
|
3472
|
+
status & 0x02: has stop
|
|
3473
|
+
"""
|
|
3474
|
+
return self._arm.get_linear_track_status()
|
|
3475
|
+
|
|
3476
|
+
def get_linear_track_error(self):
|
|
3477
|
+
"""
|
|
3478
|
+
Get the error code of the linear track
|
|
3479
|
+
Note:
|
|
3480
|
+
1. only available if firmware_version >= 1.8.0
|
|
3481
|
+
|
|
3482
|
+
:return: tuple((code, error)) only when code is 0, the returned result is correct.
|
|
3483
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3484
|
+
error: See the [Linear Motor Error Code Documentation](./xarm_api_code.md#linear-motor-error-code) for details.
|
|
3485
|
+
"""
|
|
3486
|
+
return self._arm.get_linear_track_error()
|
|
3487
|
+
|
|
3488
|
+
def get_linear_track_is_enabled(self):
|
|
3489
|
+
"""
|
|
3490
|
+
Get the linear track is enabled or not
|
|
3491
|
+
Note:
|
|
3492
|
+
1. only available if firmware_version >= 1.8.0
|
|
3493
|
+
|
|
3494
|
+
:return: tuple((code, status)) only when code is 0, the returned result is correct.
|
|
3495
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3496
|
+
status:
|
|
3497
|
+
0: linear track is not enabled
|
|
3498
|
+
1: linear track is enabled
|
|
3499
|
+
"""
|
|
3500
|
+
return self._arm.get_linear_track_is_enabled()
|
|
3501
|
+
|
|
3502
|
+
def get_linear_track_on_zero(self):
|
|
3503
|
+
"""
|
|
3504
|
+
Get the linear track is on zero positon or not
|
|
3505
|
+
Note:
|
|
3506
|
+
1. only available if firmware_version >= 1.8.0
|
|
3507
|
+
|
|
3508
|
+
:return: tuple((code, status)) only when code is 0, the returned result is correct.
|
|
3509
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3510
|
+
status:
|
|
3511
|
+
0: linear track is not on zero
|
|
3512
|
+
1: linear track is on zero
|
|
3513
|
+
"""
|
|
3514
|
+
return self._arm.get_linear_track_on_zero()
|
|
3515
|
+
|
|
3516
|
+
def get_linear_track_sci(self):
|
|
3517
|
+
"""
|
|
3518
|
+
Get the sci1 value of the linear track
|
|
3519
|
+
Note:
|
|
3520
|
+
1. only available if firmware_version >= 1.8.0
|
|
3521
|
+
|
|
3522
|
+
:return: tuple((code, sci1)) only when code is 0, the returned result is correct.
|
|
3523
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3524
|
+
"""
|
|
3525
|
+
return self._arm.get_linear_track_sci()
|
|
3526
|
+
|
|
3527
|
+
def get_linear_track_sco(self):
|
|
3528
|
+
"""
|
|
3529
|
+
Get the sco value of the linear track
|
|
3530
|
+
Note:
|
|
3531
|
+
1. only available if firmware_version >= 1.8.0
|
|
3532
|
+
|
|
3533
|
+
:return: tuple((code, sco)) only when code is 0, the returned result is correct.
|
|
3534
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3535
|
+
sco: [sco0, sco1]
|
|
3536
|
+
"""
|
|
3537
|
+
return self._arm.get_linear_track_sco()
|
|
3538
|
+
|
|
3539
|
+
def clean_linear_track_error(self):
|
|
3540
|
+
"""
|
|
3541
|
+
Clean the linear track error
|
|
3542
|
+
Note:
|
|
3543
|
+
1. only available if firmware_version >= 1.8.0
|
|
3544
|
+
|
|
3545
|
+
:return: code
|
|
3546
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3547
|
+
"""
|
|
3548
|
+
return self._arm.clean_linear_track_error()
|
|
3549
|
+
|
|
3550
|
+
def set_linear_track_enable(self, enable):
|
|
3551
|
+
"""
|
|
3552
|
+
Set the linear track enable/disable
|
|
3553
|
+
Note:
|
|
3554
|
+
1. only available if firmware_version >= 1.8.0
|
|
3555
|
+
|
|
3556
|
+
:param enable: enable or not
|
|
3557
|
+
:return: code
|
|
3558
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3559
|
+
"""
|
|
3560
|
+
return self._arm.set_linear_track_enable(enable)
|
|
3561
|
+
|
|
3562
|
+
def set_linear_track_speed(self, speed):
|
|
3563
|
+
"""
|
|
3564
|
+
Set the speed of the linear track
|
|
3565
|
+
Note:
|
|
3566
|
+
1. only available if firmware_version >= 1.8.0
|
|
3567
|
+
|
|
3568
|
+
:param speed: Integer between 1 and 1000mm/s.
|
|
3569
|
+
:return: code
|
|
3570
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3571
|
+
"""
|
|
3572
|
+
return self._arm.set_linear_track_speed(speed)
|
|
3573
|
+
|
|
3574
|
+
def set_linear_track_back_origin(self, wait=True, **kwargs):
|
|
3575
|
+
"""
|
|
3576
|
+
Set the linear track go back to the origin position
|
|
3577
|
+
Note:
|
|
3578
|
+
1. only available if firmware_version >= 1.8.0
|
|
3579
|
+
2. only useful when powering on for the first time
|
|
3580
|
+
3. this operation must be performed at the first power-on
|
|
3581
|
+
|
|
3582
|
+
:param wait: wait to motion finish or not, default is True
|
|
3583
|
+
:param kwargs:
|
|
3584
|
+
auto_enable: enable after back to origin or not, default is True
|
|
3585
|
+
:return: code
|
|
3586
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3587
|
+
"""
|
|
3588
|
+
return self._arm.set_linear_track_back_origin(wait=wait, **kwargs)
|
|
3589
|
+
|
|
3590
|
+
def set_linear_track_pos(self, pos, speed=None, wait=True, timeout=100, **kwargs):
|
|
3591
|
+
"""
|
|
3592
|
+
Set the position of the linear track
|
|
3593
|
+
Note:
|
|
3594
|
+
1. only available if firmware_version >= 1.8.0
|
|
3595
|
+
|
|
3596
|
+
:param pos: position. Integer between 0 and 700/1000/1500mm.
|
|
3597
|
+
If SN start with AL1300 the position range is 0~700mm.
|
|
3598
|
+
If SN start with AL1301 the position range is 0~1000mm.
|
|
3599
|
+
If SN start with AL1302 the position range is 0~1500mm.
|
|
3600
|
+
:param speed: speed of the linear track. Integer between 1 and 1000mm/s. default is not set
|
|
3601
|
+
:param wait: wait to motion finish or not, default is True
|
|
3602
|
+
:param timeout: wait timeout, seconds, default is 100s.
|
|
3603
|
+
:return: code
|
|
3604
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3605
|
+
"""
|
|
3606
|
+
return self._arm.set_linear_track_pos(pos, speed=speed, wait=wait, timeout=timeout, **kwargs)
|
|
3607
|
+
|
|
3608
|
+
def set_linear_track_stop(self):
|
|
3609
|
+
"""
|
|
3610
|
+
Set the linear track to stop
|
|
3611
|
+
Note:
|
|
3612
|
+
1. only available if firmware_version >= 1.8.0
|
|
3613
|
+
|
|
3614
|
+
:return: code
|
|
3615
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3616
|
+
"""
|
|
3617
|
+
return self._arm.set_linear_track_stop()
|
|
3618
|
+
|
|
3619
|
+
def delete_blockly_app(self, name):
|
|
3620
|
+
"""
|
|
3621
|
+
Delete blockly app
|
|
3622
|
+
|
|
3623
|
+
:param name: blockly app name
|
|
3624
|
+
|
|
3625
|
+
:return: code
|
|
3626
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3627
|
+
"""
|
|
3628
|
+
return self._studio.delete_blockly_app(name)
|
|
3629
|
+
|
|
3630
|
+
def delete_trajectory(self, name):
|
|
3631
|
+
"""
|
|
3632
|
+
Delete trajectory
|
|
3633
|
+
|
|
3634
|
+
:param name: trajectory name
|
|
3635
|
+
|
|
3636
|
+
:return: code
|
|
3637
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3638
|
+
"""
|
|
3639
|
+
return self._studio.delete_trajectory(name)
|
|
3640
|
+
|
|
3641
|
+
def get_initial_point(self):
|
|
3642
|
+
"""
|
|
3643
|
+
Get the initial point from studio
|
|
3644
|
+
|
|
3645
|
+
:return: tuple((code, point)), only when code is 0, the returned result is correct.
|
|
3646
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3647
|
+
point: initial point, [J1, J2, ..., J7]
|
|
3648
|
+
"""
|
|
3649
|
+
return self._studio.get_initial_point()
|
|
3650
|
+
|
|
3651
|
+
def set_initial_point(self, point):
|
|
3652
|
+
"""
|
|
3653
|
+
Set the initial point
|
|
3654
|
+
|
|
3655
|
+
:param point: initial point, [J1, J2, ..., J7]
|
|
3656
|
+
|
|
3657
|
+
:return: code
|
|
3658
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3659
|
+
"""
|
|
3660
|
+
return self._studio.set_initial_point(point)
|
|
3661
|
+
|
|
3662
|
+
def get_mount_direction(self):
|
|
3663
|
+
"""
|
|
3664
|
+
Get the mount degrees from studio
|
|
3665
|
+
|
|
3666
|
+
:return: tuple((code, degrees)), only when code is 0, the returned result is correct.
|
|
3667
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3668
|
+
degrees: mount degrees, [tilt angle, rotate angle]
|
|
3669
|
+
"""
|
|
3670
|
+
return self._studio.get_mount_direction()
|
|
3671
|
+
|
|
3672
|
+
def set_cartesian_velo_continuous(self, on_off):
|
|
3673
|
+
"""
|
|
3674
|
+
Set cartesian motion velocity continuous
|
|
3675
|
+
Note:
|
|
3676
|
+
1. only available if firmware_version >= 1.9.0
|
|
3677
|
+
|
|
3678
|
+
:param on_off: continuous or not, True means continuous, default is False
|
|
3679
|
+
|
|
3680
|
+
:return: code
|
|
3681
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3682
|
+
"""
|
|
3683
|
+
return self._arm.set_cartesian_velo_continuous(on_off)
|
|
3684
|
+
|
|
3685
|
+
def set_allow_approx_motion(self, on_off):
|
|
3686
|
+
"""
|
|
3687
|
+
Settings allow to avoid overspeed near some singularities using approximate solutions
|
|
3688
|
+
Note:
|
|
3689
|
+
1. only available if firmware_version >= 1.9.0
|
|
3690
|
+
|
|
3691
|
+
:param on_off: allow or not, True means allow, default is False
|
|
3692
|
+
|
|
3693
|
+
:return: code
|
|
3694
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3695
|
+
"""
|
|
3696
|
+
return self._arm.set_allow_approx_motion(on_off)
|
|
3697
|
+
|
|
3698
|
+
def get_allow_approx_motion(self):
|
|
3699
|
+
"""
|
|
3700
|
+
Obtain whether to enable approximate solutions to avoid certain singularities
|
|
3701
|
+
Note:
|
|
3702
|
+
1. only available if firmware_version >= 1.9.0
|
|
3703
|
+
|
|
3704
|
+
:return: code
|
|
3705
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3706
|
+
"""
|
|
3707
|
+
return self._arm.get_allow_approx_motion()
|
|
3708
|
+
|
|
3709
|
+
def get_joint_states(self, is_radian=None, num=3):
|
|
3710
|
+
"""
|
|
3711
|
+
Get the joint states
|
|
3712
|
+
Note:
|
|
3713
|
+
1. only available if firmware_version >= 1.9.0
|
|
3714
|
+
|
|
3715
|
+
:param is_radian: the returned value(position and velocity) is in radians or not, default is self.default_is_radian
|
|
3716
|
+
:return: tuple((code, [position, velocity, effort])), only when code is 0, the returned result is correct.
|
|
3717
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3718
|
+
position: the angles of joints, like [angle-1, ..., angle-7]
|
|
3719
|
+
velocity: the velocities of joints, like [velo-1, ..., velo-7]
|
|
3720
|
+
effort: the efforts of joints, like [effort-1, ..., effort-7]
|
|
3721
|
+
"""
|
|
3722
|
+
return self._arm.get_joint_states(is_radian=is_radian, num=num)
|
|
3723
|
+
|
|
3724
|
+
def iden_joint_friction(self, sn=None):
|
|
3725
|
+
"""
|
|
3726
|
+
Identification the friction
|
|
3727
|
+
Note:
|
|
3728
|
+
1. only available if firmware_version >= 1.9.0
|
|
3729
|
+
|
|
3730
|
+
:param sn: sn value
|
|
3731
|
+
:return: tuple((code, result)) only when code is 0, the returned result is correct.
|
|
3732
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3733
|
+
result:
|
|
3734
|
+
0: success
|
|
3735
|
+
-1: failure
|
|
3736
|
+
"""
|
|
3737
|
+
return self._arm.iden_joint_friction(sn)
|
|
3738
|
+
|
|
3739
|
+
def set_only_check_type(self, only_check_type=0):
|
|
3740
|
+
"""
|
|
3741
|
+
Set the motion process detection type (valid for all motion interfaces of the current SDK instance)
|
|
3742
|
+
|
|
3743
|
+
Note:
|
|
3744
|
+
1. only available if firmware_version >= 1.11.100
|
|
3745
|
+
2. This interface is a global configuration item of the current SDK, and affects all motion-related interfaces
|
|
3746
|
+
3. Generally, you only need to call when you don't want to move the robotic arm and only check whether some paths will have self-collision/angle-limit/cartesian-limit/overspeed.
|
|
3747
|
+
4. Currently only self-collision/angle-limit/cartesian-limit/overspeed are detected
|
|
3748
|
+
5. If only_check_type is set to be greater than 0, and the return value of calling the motion interface is not 0, you can view arm.only_check_result to view the specific error code
|
|
3749
|
+
|
|
3750
|
+
Example: (Common scenarios, here is an example of the set_position interface)
|
|
3751
|
+
1. Check whether the process from point A to point B is normal (no self-collision and overspeed triggered)
|
|
3752
|
+
1.1 Move to point A
|
|
3753
|
+
arm.set_only_check_type(0)
|
|
3754
|
+
code = arm.set_position(A)
|
|
3755
|
+
1.2 Check if the process from point A to point B is normal (no self-collision and overspeed triggered)
|
|
3756
|
+
arm.set_only_check_type(1)
|
|
3757
|
+
code = arm.set_position(B)
|
|
3758
|
+
# If code is not equal to 0, it means that the path does not pass. You can check the specific error code through arm.only_check_result
|
|
3759
|
+
arm.set_only_check_type(0)
|
|
3760
|
+
|
|
3761
|
+
2. Check whether the process from point A to point B, C, and D to point E is normal (no self-collision and overspeed are triggered)
|
|
3762
|
+
2.1 Move to point A
|
|
3763
|
+
arm.set_only_check_type(0)
|
|
3764
|
+
code = arm.set_position(A)
|
|
3765
|
+
2.2 Check whether the process of point A passing through points B, C, D to point E is normal (no self-collision and overspeed are triggered)
|
|
3766
|
+
arm.set_only_check_type(3)
|
|
3767
|
+
code = arm.set_position(B)
|
|
3768
|
+
# If code is not equal to 0, it means that the path does not pass. You can check the specific error code through arm.only_check_result
|
|
3769
|
+
code = arm.set_position(C)
|
|
3770
|
+
# If code is not equal to 0, it means that the path does not pass. You can check the specific error code through arm.only_check_result
|
|
3771
|
+
code = arm.set_position(D)
|
|
3772
|
+
# If code is not equal to 0, it means that the path does not pass. You can check the specific error code through arm.only_check_result
|
|
3773
|
+
code = arm.set_position(E)
|
|
3774
|
+
# If code is not equal to 0, it means that the path does not pass. You can check the specific error code through arm.only_check_result
|
|
3775
|
+
arm.set_only_check_type(0)
|
|
3776
|
+
|
|
3777
|
+
:param only_check_type: Motion Detection Type
|
|
3778
|
+
only_check_type == 0: Restore the original function of the motion interface, it will move, the default is 0
|
|
3779
|
+
only_check_type == 1: Only check the self-collision without moving, take the actual state of the manipulator as the initial planned path, and check whether the path has self-collision (the intermediate state will be updated at this time)
|
|
3780
|
+
only_check_type == 2: Only check the self-collision without moving, use the intermediate state as the starting planning path, check whether the path has self-collision (the intermediate state will be updated at this time), and restore the intermediate state to the actual state after the end
|
|
3781
|
+
only_check_type == 3: Only check the self-collision without moving, use the intermediate state as the starting planning path, and check whether the path has self-collision (the intermediate state will be updated at this time)
|
|
3782
|
+
:return: code
|
|
3783
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3784
|
+
"""
|
|
3785
|
+
return self._arm.set_only_check_type(only_check_type)
|
|
3786
|
+
|
|
3787
|
+
def open_lite6_gripper(self, sync=True):
|
|
3788
|
+
"""
|
|
3789
|
+
Open the gripper of Lite6 series robotic arms
|
|
3790
|
+
Note:
|
|
3791
|
+
1. only available if firmware_version >= 1.10.0
|
|
3792
|
+
2. this API can only be used on Lite6 series robotic arms
|
|
3793
|
+
|
|
3794
|
+
:param sync: whether to execute in the motion queue, set to False to execute immediately(default is True)
|
|
3795
|
+
1. only available if firmware_version >= 2.4.101
|
|
3796
|
+
:return: code
|
|
3797
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3798
|
+
"""
|
|
3799
|
+
return self._arm.open_lite6_gripper(sync=sync)
|
|
3800
|
+
|
|
3801
|
+
def close_lite6_gripper(self, sync=True):
|
|
3802
|
+
"""
|
|
3803
|
+
Close the gripper of Lite6 series robotic arms
|
|
3804
|
+
Note:
|
|
3805
|
+
1. only available if firmware_version >= 1.10.0
|
|
3806
|
+
2. this API can only be used on Lite6 series robotic arms
|
|
3807
|
+
|
|
3808
|
+
:param sync: whether to execute in the motion queue, set to False to execute immediately(default is True)
|
|
3809
|
+
1. only available if firmware_version >= 2.4.101
|
|
3810
|
+
:return: code
|
|
3811
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3812
|
+
"""
|
|
3813
|
+
return self._arm.close_lite6_gripper(sync=sync)
|
|
3814
|
+
|
|
3815
|
+
def stop_lite6_gripper(self, sync=True):
|
|
3816
|
+
"""
|
|
3817
|
+
Stop the gripper of Lite6 series robotic arms
|
|
3818
|
+
Note:
|
|
3819
|
+
1. only available if firmware_version >= 1.10.0
|
|
3820
|
+
2. this API can only be used on Lite6 series robotic arms
|
|
3821
|
+
|
|
3822
|
+
:param sync: whether to execute in the motion queue, set to False to execute immediately(default is True)
|
|
3823
|
+
1. only available if firmware_version >= 2.4.101
|
|
3824
|
+
:return: code
|
|
3825
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3826
|
+
"""
|
|
3827
|
+
return self._arm.stop_lite6_gripper(sync=sync)
|
|
3828
|
+
|
|
3829
|
+
def get_dh_params(self):
|
|
3830
|
+
"""
|
|
3831
|
+
Get the DH parameters
|
|
3832
|
+
Note:
|
|
3833
|
+
1. only available if firmware_version >= 2.0.0
|
|
3834
|
+
|
|
3835
|
+
:return: tuple((code, dh_params)), only when code is 0, the returned result is correct.
|
|
3836
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3837
|
+
dh_params: DH parameters
|
|
3838
|
+
dh_params[0:4]: DH parameters of Joint-1
|
|
3839
|
+
dh_params[4:8]: DH parameters of Joint-2
|
|
3840
|
+
...
|
|
3841
|
+
dh_params[24:28]: DH parameters of Joint-7
|
|
3842
|
+
"""
|
|
3843
|
+
return self._arm.get_dh_params()
|
|
3844
|
+
|
|
3845
|
+
def set_dh_params(self, dh_params, flag=0):
|
|
3846
|
+
"""
|
|
3847
|
+
Set the DH parameters
|
|
3848
|
+
Note:
|
|
3849
|
+
1. only available if firmware_version >= 2.0.0
|
|
3850
|
+
2. this interface is only provided for users who need to use external DH parameters, ordinary users should not try to modify DH parameters.
|
|
3851
|
+
|
|
3852
|
+
:param dh_params: DH parameters
|
|
3853
|
+
:param flag:
|
|
3854
|
+
0: Use the set DH parameters, but do not write to the configuration file
|
|
3855
|
+
1: Use the set DH parameters and write to the configuration file
|
|
3856
|
+
2: Use the set DH parameters and delete the DH parameters of the configuration file
|
|
3857
|
+
3: Use the default DH parameters, but will not delete the DH parameters of the configuration file
|
|
3858
|
+
4: Use the default DH parameters and delete the DH parameters of the configuration file
|
|
3859
|
+
:return: code
|
|
3860
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3861
|
+
"""
|
|
3862
|
+
return self._arm.set_dh_params(dh_params, flag)
|
|
3863
|
+
|
|
3864
|
+
def set_feedback_type(self, feedback_type):
|
|
3865
|
+
"""
|
|
3866
|
+
Set the feedback type
|
|
3867
|
+
Note:
|
|
3868
|
+
1. only available if firmware_version >= 2.1.0
|
|
3869
|
+
2. only works in position mode
|
|
3870
|
+
3. the setting will only affect subsequent tasks and will not affect previously cached tasks
|
|
3871
|
+
4. only valid for the current connection
|
|
3872
|
+
|
|
3873
|
+
:param feedback_type:
|
|
3874
|
+
0: disable feedback
|
|
3875
|
+
1: feedback when the motion task starts executing
|
|
3876
|
+
2: feedback when the motion task execution ends or motion task is discarded(usually when the distance is too close to be planned)
|
|
3877
|
+
4: feedback when the non-motion task is triggered
|
|
3878
|
+
:return: code
|
|
3879
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3880
|
+
"""
|
|
3881
|
+
return self._arm.set_feedback_type(feedback_type)
|
|
3882
|
+
|
|
3883
|
+
def register_feedback_callback(self, callback=None):
|
|
3884
|
+
"""
|
|
3885
|
+
Register the callback of feedback
|
|
3886
|
+
Note:
|
|
3887
|
+
1. only available if firmware_version >= 2.1.0
|
|
3888
|
+
|
|
3889
|
+
:param callback:
|
|
3890
|
+
callback data: bytes data
|
|
3891
|
+
data[0:2]: transaction id, (Big-endian conversion to unsigned 16-bit integer data), command ID corresponding to the feedback, consistent with issued instructions
|
|
3892
|
+
Note: this can be used to distinguish which instruction the feedback belongs to
|
|
3893
|
+
data[4:6]: feedback_length, feedback_length == len(data) - 6, (Big-endian conversion to unsigned 16-bit integer data)
|
|
3894
|
+
data[8]: feedback type
|
|
3895
|
+
1: the motion task starts executing
|
|
3896
|
+
2: the motion task execution ends or motion task is discarded(usually when the distance is too close to be planned)
|
|
3897
|
+
4: the non-motion task is triggered
|
|
3898
|
+
data[9]: feedback funcode, command code corresponding to feedback, consistent with issued instructions
|
|
3899
|
+
Note: this can be used to distinguish what instruction the feedback belongs to
|
|
3900
|
+
data[10:12]: feedback taskid, (Big-endian conversion to unsigned 16-bit integer data)
|
|
3901
|
+
data[12]: feedback code, execution status code, generally only meaningful when the feedback type is end, normally 0, 2 means discarded
|
|
3902
|
+
data[13:21]: feedback us, (Big-endian conversion to unsigned 64-bit integer data), time when feedback triggers (microseconds)
|
|
3903
|
+
Note: this time is the corresponding controller system time when the feedback is triggered
|
|
3904
|
+
:return: True/False
|
|
3905
|
+
"""
|
|
3906
|
+
return self._arm.register_feedback_callback(callback=callback)
|
|
3907
|
+
|
|
3908
|
+
def release_feedback_callback(self, callback=None):
|
|
3909
|
+
"""
|
|
3910
|
+
Release the callback of feedback
|
|
3911
|
+
Note:
|
|
3912
|
+
1. only available if firmware_version >= 2.1.0
|
|
3913
|
+
|
|
3914
|
+
:param callback:
|
|
3915
|
+
:return: True/False
|
|
3916
|
+
"""
|
|
3917
|
+
return self._arm.release_feedback_callback(callback=callback)
|
|
3918
|
+
|
|
3919
|
+
def read_coil_bits(self, addr, quantity):
|
|
3920
|
+
"""
|
|
3921
|
+
([Standard Modbus TCP](../UF_ModbusTCP_Manual.md)) Read Coils (0x01)
|
|
3922
|
+
|
|
3923
|
+
:param addr: the starting address of the register to be read
|
|
3924
|
+
:param quantity: number of registers
|
|
3925
|
+
:return: tuple((code, bits)) only when code is 0, the returned result is correct.
|
|
3926
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3927
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
3928
|
+
"""
|
|
3929
|
+
return self._arm.read_coil_bits(addr, quantity)
|
|
3930
|
+
|
|
3931
|
+
def read_input_bits(self, addr, quantity):
|
|
3932
|
+
"""
|
|
3933
|
+
([Standard Modbus TCP](../UF_ModbusTCP_Manual.md)) Read Discrete Inputs (0x02)
|
|
3934
|
+
|
|
3935
|
+
:param addr: the starting address of the register to be read
|
|
3936
|
+
:param quantity: number of registers
|
|
3937
|
+
:return: tuple((code, bits)) only when code is 0, the returned result is correct.
|
|
3938
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3939
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
3940
|
+
"""
|
|
3941
|
+
return self._arm.read_input_bits(addr, quantity)
|
|
3942
|
+
|
|
3943
|
+
def read_holding_registers(self, addr, quantity, is_signed=False):
|
|
3944
|
+
"""
|
|
3945
|
+
([Standard Modbus TCP](../UF_ModbusTCP_Manual.md)) Read Holding Registers (0x03)
|
|
3946
|
+
|
|
3947
|
+
:param addr: the starting address of the register to be read
|
|
3948
|
+
:param quantity: number of registers
|
|
3949
|
+
:param is_signed: whether to convert the read register value into a signed form
|
|
3950
|
+
:return: tuple((code, bits)) only when code is 0, the returned result is correct.
|
|
3951
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3952
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
3953
|
+
"""
|
|
3954
|
+
return self._arm.read_holding_registers(addr, quantity, is_signed)
|
|
3955
|
+
|
|
3956
|
+
def read_input_registers(self, addr, quantity, is_signed=False):
|
|
3957
|
+
"""
|
|
3958
|
+
([Standard Modbus TCP](../UF_ModbusTCP_Manual.md)) Read Input Registers (0x04)
|
|
3959
|
+
|
|
3960
|
+
:param addr: the starting address of the register to be read
|
|
3961
|
+
:param quantity: number of registers
|
|
3962
|
+
:param is_signed: whether to convert the read register value into a signed form
|
|
3963
|
+
:return: tuple((code, bits)) only when code is 0, the returned result is correct.
|
|
3964
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3965
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
3966
|
+
"""
|
|
3967
|
+
return self._arm.read_input_registers(addr, quantity, is_signed)
|
|
3968
|
+
|
|
3969
|
+
def write_single_coil_bit(self, addr, bit_val):
|
|
3970
|
+
"""
|
|
3971
|
+
([Standard Modbus TCP](../UF_ModbusTCP_Manual.md)) Write Single Coil (0x05)
|
|
3972
|
+
|
|
3973
|
+
:param addr: register address
|
|
3974
|
+
:param bit_val: the value to write (0/1)
|
|
3975
|
+
:return: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3976
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
3977
|
+
"""
|
|
3978
|
+
return self._arm.write_single_coil_bit(addr, bit_val)
|
|
3979
|
+
|
|
3980
|
+
def write_single_holding_register(self, addr, reg_val):
|
|
3981
|
+
"""
|
|
3982
|
+
([Standard Modbus TCP](../UF_ModbusTCP_Manual.md)) Write Single Holding Register (0x06)
|
|
3983
|
+
|
|
3984
|
+
:param addr: register address
|
|
3985
|
+
:param bit_val: the value to write
|
|
3986
|
+
:return: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3987
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
3988
|
+
"""
|
|
3989
|
+
return self._arm.write_single_holding_register(addr, reg_val)
|
|
3990
|
+
|
|
3991
|
+
def write_multiple_coil_bits(self, addr, bits):
|
|
3992
|
+
"""
|
|
3993
|
+
([Standard Modbus TCP](../UF_ModbusTCP_Manual.md)) Write Multiple Coils (0x0F)
|
|
3994
|
+
|
|
3995
|
+
:param addr: the starting address of the register to be written
|
|
3996
|
+
:param bits: array of values to write
|
|
3997
|
+
:return: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
3998
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
3999
|
+
"""
|
|
4000
|
+
return self._arm.write_multiple_coil_bits(addr, bits)
|
|
4001
|
+
|
|
4002
|
+
def write_multiple_holding_registers(self, addr, regs):
|
|
4003
|
+
"""
|
|
4004
|
+
([Standard Modbus TCP](../UF_ModbusTCP_Manual.md)) Write Multiple Holding Registers (0x10)
|
|
4005
|
+
|
|
4006
|
+
:param addr: the starting address of the register to be written
|
|
4007
|
+
:param regs: array of values to write
|
|
4008
|
+
:return: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4009
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
4010
|
+
"""
|
|
4011
|
+
return self._arm.write_multiple_holding_registers(addr, regs)
|
|
4012
|
+
|
|
4013
|
+
def mask_write_holding_register(self, addr, and_mask, or_mask):
|
|
4014
|
+
"""
|
|
4015
|
+
([Standard Modbus TCP](../UF_ModbusTCP_Manual.md)) Mask Write Holding Register (0x16)
|
|
4016
|
+
|
|
4017
|
+
:param addr: register address
|
|
4018
|
+
:param and_mask: mask to be AND with
|
|
4019
|
+
:param or_mask: mask to be OR with
|
|
4020
|
+
:return: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4021
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
4022
|
+
"""
|
|
4023
|
+
return self._arm.mask_write_holding_register(addr, and_mask, or_mask)
|
|
4024
|
+
|
|
4025
|
+
def write_and_read_holding_registers(self, r_addr, r_quantity, w_addr, w_regs, is_signed=False):
|
|
4026
|
+
"""
|
|
4027
|
+
([Standard Modbus TCP](../UF_ModbusTCP_Manual.md)) Write and Read Holding Registers (0x17)
|
|
4028
|
+
|
|
4029
|
+
:param r_addr: the starting address of the register to be read
|
|
4030
|
+
:param r_quantity: number of registers to read
|
|
4031
|
+
:param w_addr: the starting address of the register to be written
|
|
4032
|
+
:param w_regs: array of values to write
|
|
4033
|
+
:param is_signed: whether to convert the read register value into a signed form
|
|
4034
|
+
:return: tuple((code, regs)) only when code is 0, the returned result is correct.
|
|
4035
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4036
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
4037
|
+
"""
|
|
4038
|
+
return self._arm.write_and_read_holding_registers(r_addr, r_quantity, w_addr, w_regs, is_signed)
|
|
4039
|
+
|
|
4040
|
+
def send_hex_cmd(self, datas, **kwargs):
|
|
4041
|
+
"""
|
|
4042
|
+
Hexadecimal communication protocol instruction
|
|
4043
|
+
|
|
4044
|
+
:param datas: Hexadecimal data_list
|
|
4045
|
+
:param timeout: timeout: wait timeout, seconds, default is 10s.
|
|
4046
|
+
:return : Hexadecimal data_list or code
|
|
4047
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4048
|
+
Note: code 129~144 means modbus tcp exception, the actual modbus tcp exception code is (code-0x80), refer to [Standard Modbus TCP](../UF_ModbusTCP_Manual.md)
|
|
4049
|
+
"""
|
|
4050
|
+
return self._arm.send_hex_cmd(datas, **kwargs)
|
|
4051
|
+
|
|
4052
|
+
def set_linear_spd_limit_factor(self, factor):
|
|
4053
|
+
"""
|
|
4054
|
+
Set linear speed limit factor (default is 1.2)
|
|
4055
|
+
Note:
|
|
4056
|
+
1. only available if firmware_version >= 2.3.0
|
|
4057
|
+
2. only available in mode 1
|
|
4058
|
+
|
|
4059
|
+
:param factor: speed limit factor
|
|
4060
|
+
:return: code
|
|
4061
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4062
|
+
"""
|
|
4063
|
+
return self._arm.set_common_param(1, factor)
|
|
4064
|
+
|
|
4065
|
+
def set_cmd_mat_history_num(self, num):
|
|
4066
|
+
"""
|
|
4067
|
+
Set cmd mat history num
|
|
4068
|
+
Note:
|
|
4069
|
+
Only available if firmware_version >= 2.3.0
|
|
4070
|
+
|
|
4071
|
+
:param num: history num
|
|
4072
|
+
:return: code
|
|
4073
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4074
|
+
"""
|
|
4075
|
+
return self._arm.set_common_param(2, num)
|
|
4076
|
+
|
|
4077
|
+
def set_fdb_mat_history_num(self, num):
|
|
4078
|
+
"""
|
|
4079
|
+
Set fdb mat history num
|
|
4080
|
+
Note:
|
|
4081
|
+
Only available if firmware_version >= 2.3.0
|
|
4082
|
+
|
|
4083
|
+
:param num: history num
|
|
4084
|
+
:return: code
|
|
4085
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4086
|
+
"""
|
|
4087
|
+
return self._arm.set_common_param(3, num)
|
|
4088
|
+
|
|
4089
|
+
def get_linear_spd_limit_factor(self):
|
|
4090
|
+
"""
|
|
4091
|
+
Get linear speed limit factor
|
|
4092
|
+
Note:
|
|
4093
|
+
Only available if firmware_version >= 2.3.0
|
|
4094
|
+
|
|
4095
|
+
:return: tuple((code, factor)), only when code is 0, the returned result is correct.
|
|
4096
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4097
|
+
factor: linear speed limit factor
|
|
4098
|
+
"""
|
|
4099
|
+
return self._arm.get_common_param(1)
|
|
4100
|
+
|
|
4101
|
+
def get_cmd_mat_history_num(self):
|
|
4102
|
+
"""
|
|
4103
|
+
Get cmd mat history num
|
|
4104
|
+
Note:
|
|
4105
|
+
Only available if firmware_version >= 2.3.0
|
|
4106
|
+
|
|
4107
|
+
:return: tuple((code, num)), only when code is 0, the returned result is correct.
|
|
4108
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4109
|
+
num: cmd mat history num
|
|
4110
|
+
"""
|
|
4111
|
+
return self._arm.get_common_param(2)
|
|
4112
|
+
|
|
4113
|
+
def get_fdb_mat_history_num(self):
|
|
4114
|
+
"""
|
|
4115
|
+
Get fdb mat history num
|
|
4116
|
+
Note:
|
|
4117
|
+
Only available if firmware_version >= 2.3.0
|
|
4118
|
+
|
|
4119
|
+
:return: tuple((code, num)), only when code is 0, the returned result is correct.
|
|
4120
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4121
|
+
num: fdb mat history num
|
|
4122
|
+
"""
|
|
4123
|
+
return self._arm.get_common_param(3)
|
|
4124
|
+
|
|
4125
|
+
def get_tgpio_modbus_timeout(self, is_transparent_transmission=False):
|
|
4126
|
+
"""
|
|
4127
|
+
Get tgpio modbus timeout
|
|
4128
|
+
Note:
|
|
4129
|
+
Only available if firmware_version >= 2.3.0
|
|
4130
|
+
|
|
4131
|
+
:param is_transparent_transmission: is transparent transmission or not
|
|
4132
|
+
:return: tuple((code, timeout)), only when code is 0, the returned result is correct.
|
|
4133
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4134
|
+
timeout: timeout of the tgpio modbus, milliseconds
|
|
4135
|
+
"""
|
|
4136
|
+
if is_transparent_transmission:
|
|
4137
|
+
return self._arm.get_common_param(5)
|
|
4138
|
+
else:
|
|
4139
|
+
return self._arm.get_common_param(4)
|
|
4140
|
+
|
|
4141
|
+
def get_poe_status(self):
|
|
4142
|
+
"""
|
|
4143
|
+
Get poe status
|
|
4144
|
+
Note:
|
|
4145
|
+
Only available if firmware_version >= 2.3.0
|
|
4146
|
+
|
|
4147
|
+
:return: tuple((code, status)), only when code is 0, the returned result is correct.
|
|
4148
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4149
|
+
status: 1 means poe is valid, 0 means poe is invalid
|
|
4150
|
+
"""
|
|
4151
|
+
return self._arm.get_common_info(1)
|
|
4152
|
+
|
|
4153
|
+
def get_iden_status(self):
|
|
4154
|
+
"""
|
|
4155
|
+
Get iden status
|
|
4156
|
+
Note:
|
|
4157
|
+
Only available if firmware_version >= 2.3.0
|
|
4158
|
+
|
|
4159
|
+
:return: tuple((code, status)), only when code is 0, the returned result is correct.
|
|
4160
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4161
|
+
status: 1 means in identifying, 0 means not in identifying
|
|
4162
|
+
"""
|
|
4163
|
+
return self._arm.get_common_info(2)
|
|
4164
|
+
|
|
4165
|
+
def get_c31_error_info(self):
|
|
4166
|
+
"""
|
|
4167
|
+
Get collision error (C31) info
|
|
4168
|
+
Note:
|
|
4169
|
+
Only available if firmware_version >= 2.3.0
|
|
4170
|
+
|
|
4171
|
+
:return: tuple((code, err_info)), only when code is 0, the returned result is correct.
|
|
4172
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4173
|
+
err_info: [servo_id, theoratival tau, actual tau]
|
|
4174
|
+
"""
|
|
4175
|
+
return self._arm.get_common_info(101, return_val=False)
|
|
4176
|
+
|
|
4177
|
+
def get_c37_error_info(self, is_radian=None):
|
|
4178
|
+
"""
|
|
4179
|
+
Get payload error (C37) info
|
|
4180
|
+
Note:
|
|
4181
|
+
Only available if firmware_version >= 2.3.0
|
|
4182
|
+
|
|
4183
|
+
:return: tuple((code, err_info)), only when code is 0, the returned result is correct.
|
|
4184
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4185
|
+
err_info: [servo_id, angle]
|
|
4186
|
+
"""
|
|
4187
|
+
ret = self._arm.get_common_info(102, return_val=False)
|
|
4188
|
+
if ret[0] == 0 and len(ret) > 1 and len(ret[1]) > 1:
|
|
4189
|
+
is_rad = self._is_radian if is_radian is None else is_radian
|
|
4190
|
+
ret[1][1] = ret[1][1] if is_rad else math.degrees(ret[1][1])
|
|
4191
|
+
return ret
|
|
4192
|
+
|
|
4193
|
+
def get_c23_error_info(self, is_radian=None):
|
|
4194
|
+
"""
|
|
4195
|
+
Get joint angle limit error (C23) info
|
|
4196
|
+
Note:
|
|
4197
|
+
Only available if firmware_version >= 2.3.0
|
|
4198
|
+
|
|
4199
|
+
:return: tuple((code, err_info)), only when code is 0, the returned result is correct.
|
|
4200
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4201
|
+
err_info: [(servo_id, angle), ...]
|
|
4202
|
+
"""
|
|
4203
|
+
ret = self._arm.get_common_info(103, return_val=False)
|
|
4204
|
+
if ret[0] == 0 and len(ret) > 1 and len(ret[1]) > 1:
|
|
4205
|
+
is_rad = self._is_radian if is_radian is None else is_radian
|
|
4206
|
+
err_info = []
|
|
4207
|
+
bits = ret[1][0]
|
|
4208
|
+
for i in range(self.axis):
|
|
4209
|
+
if (bits >> i) & 0x01:
|
|
4210
|
+
err_info.append((i + 1, ret[1][i+1] if is_rad else math.degrees(ret[1][i+1])))
|
|
4211
|
+
return 0, err_info
|
|
4212
|
+
# ret[1][1] = ret[1][1] if is_rad else math.degrees(ret[1][1])
|
|
4213
|
+
return ret
|
|
4214
|
+
|
|
4215
|
+
def get_c24_error_info(self, is_radian=None):
|
|
4216
|
+
"""
|
|
4217
|
+
Get joint speed limit error (C24) info
|
|
4218
|
+
Note:
|
|
4219
|
+
Only available if firmware_version >= 2.3.0
|
|
4220
|
+
|
|
4221
|
+
:return: tuple((code, err_info)), only when code is 0, the returned result is correct.
|
|
4222
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4223
|
+
err_info: [servo_id, speed]
|
|
4224
|
+
"""
|
|
4225
|
+
ret = self._arm.get_common_info(104, return_val=False)
|
|
4226
|
+
if ret[0] == 0 and len(ret) > 1 and len(ret[1]) > 1:
|
|
4227
|
+
is_rad = self._is_radian if is_radian is None else is_radian
|
|
4228
|
+
ret[1][1] = ret[1][1] if is_rad else math.degrees(ret[1][1])
|
|
4229
|
+
return ret
|
|
4230
|
+
|
|
4231
|
+
def get_c60_error_info(self):
|
|
4232
|
+
"""
|
|
4233
|
+
Get linear speed limit error (C60) info
|
|
4234
|
+
Note:
|
|
4235
|
+
1. Only available if firmware_version >= 2.3.0
|
|
4236
|
+
2. Only available in mode 1
|
|
4237
|
+
|
|
4238
|
+
:return: tuple((code, err_info)), only when code is 0, the returned result is correct.
|
|
4239
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4240
|
+
err_info: [max_linear_speed, curr_linear_speed]
|
|
4241
|
+
"""
|
|
4242
|
+
return self._arm.get_common_info(105, return_val=False)
|
|
4243
|
+
|
|
4244
|
+
def get_c38_error_info(self, is_radian=None):
|
|
4245
|
+
"""
|
|
4246
|
+
Get joint hard angle limit error (C38) info
|
|
4247
|
+
Note:
|
|
4248
|
+
Only available if firmware_version >= 2.4.0
|
|
4249
|
+
|
|
4250
|
+
:return: tuple((code, err_info)), only when code is 0, the returned result is correct.
|
|
4251
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4252
|
+
err_info: [(servo_id, angle), ...]
|
|
4253
|
+
"""
|
|
4254
|
+
ret = self._arm.get_common_info(106, return_val=False)
|
|
4255
|
+
if ret[0] == 0 and len(ret) > 1 and len(ret[1]) > 1:
|
|
4256
|
+
is_rad = self._is_radian if is_radian is None else is_radian
|
|
4257
|
+
err_info = []
|
|
4258
|
+
bits = ret[1][0]
|
|
4259
|
+
for i in range(self.axis):
|
|
4260
|
+
if (bits >> i) & 0x01:
|
|
4261
|
+
err_info.append((i + 1, ret[1][i+1] if is_rad else math.degrees(ret[1][i+1])))
|
|
4262
|
+
return 0, err_info
|
|
4263
|
+
# ret[1][1] = ret[1][1] if is_rad else math.degrees(ret[1][1])
|
|
4264
|
+
return ret
|
|
4265
|
+
|
|
4266
|
+
def get_c54_error_info(self):
|
|
4267
|
+
"""
|
|
4268
|
+
Get (Six-axis Force Torque Sensor) collision error (C54) info
|
|
4269
|
+
Note:
|
|
4270
|
+
Only available if firmware_version >= 2.6.103
|
|
4271
|
+
|
|
4272
|
+
:return: tuple((code, err_info)), only when code is 0, the returned result is correct.
|
|
4273
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4274
|
+
err_info: [dir, tau threshold, actual tau]
|
|
4275
|
+
"""
|
|
4276
|
+
return self._arm.get_common_info(107, return_val=False)
|
|
4277
|
+
|
|
4278
|
+
def run_gcode_app(self, path, **kwargs):
|
|
4279
|
+
"""
|
|
4280
|
+
Run gcode project file by xArmStudio software
|
|
4281
|
+
:param path: gcode file path
|
|
4282
|
+
|
|
4283
|
+
:return: code, only when code is 0, the returned result is correct.
|
|
4284
|
+
"""
|
|
4285
|
+
return self._arm.run_gcode_app(path, **kwargs)
|
|
4286
|
+
|
|
4287
|
+
def get_traj_speeding(self, rate):
|
|
4288
|
+
"""
|
|
4289
|
+
Obtain the joint and velocity values of joint overspeed during trajectory recording
|
|
4290
|
+
:param rate: speed rate, It can only be 1/2/4
|
|
4291
|
+
|
|
4292
|
+
:return: tuple((code, speed_info)), only when code is 0, the returned result is correct.
|
|
4293
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4294
|
+
speed_info: [result_code, servo_id, servo_speed]
|
|
4295
|
+
result_code: 0: Pass, -1: Fail, >0: abnormal(1:Trajectory not loaded or incorrect status;2:The input magnification is incorrect)
|
|
4296
|
+
servo_id: Effective only when result_code is -1
|
|
4297
|
+
servo_speed: Effective only when result_code is -1
|
|
4298
|
+
"""
|
|
4299
|
+
return self._arm.get_traj_speeding(rate)
|
|
4300
|
+
|
|
4301
|
+
def set_ft_collision_detection(self, on_off):
|
|
4302
|
+
"""
|
|
4303
|
+
Set whether to enable collision detection with the Six-axis Force Torque Sensor
|
|
4304
|
+
Note:
|
|
4305
|
+
1. only available if firmware_version >= 2.6.103
|
|
4306
|
+
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
|
|
4307
|
+
3. the Six-axis Force Torque Sensor needs to be enabled and set force mode
|
|
4308
|
+
|
|
4309
|
+
:param on_off: enable or not
|
|
4310
|
+
|
|
4311
|
+
:return: code
|
|
4312
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4313
|
+
"""
|
|
4314
|
+
return self._arm.set_ft_collision_detection(on_off)
|
|
4315
|
+
|
|
4316
|
+
def set_ft_collision_rebound(self, on_off):
|
|
4317
|
+
"""
|
|
4318
|
+
Set whether to enable collision rebound with the Six-axis Force Torque Sensor
|
|
4319
|
+
Note:
|
|
4320
|
+
1. only available if firmware_version >= 2.6.103
|
|
4321
|
+
|
|
4322
|
+
:param on_off: enable or not
|
|
4323
|
+
|
|
4324
|
+
:return: code
|
|
4325
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4326
|
+
"""
|
|
4327
|
+
return self._arm.set_ft_collision_rebound(on_off)
|
|
4328
|
+
|
|
4329
|
+
def set_ft_collision_threshold(self, thresholds):
|
|
4330
|
+
"""
|
|
4331
|
+
Set the threshold of the collision detection with the Six-axis Force Torque Sensor
|
|
4332
|
+
Note:
|
|
4333
|
+
1. only available if firmware_version >= 2.6.103
|
|
4334
|
+
|
|
4335
|
+
:param thresholds: collision detection thresholds, [x(N), y(N), z(N), Rx(Nm), Ry(Nm), Rz(Nm)]
|
|
4336
|
+
x: [5, 200] (N)
|
|
4337
|
+
y: [5, 200] (N)
|
|
4338
|
+
z: [5, 200] (N)
|
|
4339
|
+
Rx: [0.1, 4] (Nm)
|
|
4340
|
+
Ry: [0.1, 4] (Nm)
|
|
4341
|
+
Rz: [0.1, 4] (Nm)
|
|
4342
|
+
|
|
4343
|
+
:return: code
|
|
4344
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4345
|
+
"""
|
|
4346
|
+
return self._arm.set_ft_collision_threshold(thresholds)
|
|
4347
|
+
|
|
4348
|
+
def set_ft_collision_reb_distance(self, distances, is_radian=None):
|
|
4349
|
+
"""
|
|
4350
|
+
Set the rebound distance of the collision rebound with the Six-axis Force Torque Sensor
|
|
4351
|
+
Note:
|
|
4352
|
+
1. only available if firmware_version >= 2.6.103
|
|
4353
|
+
|
|
4354
|
+
:param distances: collision rebound distance, [x(mm), y(mm), z(mm), Rx(° or rad), Ry(° or rad), Rz(° or rad)]
|
|
4355
|
+
x: [2, 500] (mm)
|
|
4356
|
+
y: [2, 500] (mm)
|
|
4357
|
+
z: [2, 500] (mm)
|
|
4358
|
+
Rx: [0.2, 50] (°)
|
|
4359
|
+
Ry: [0.2, 50] (°)
|
|
4360
|
+
Rz: [0.2, 50] (°)
|
|
4361
|
+
:param is_radian: the value of distance (only Rx/Ry/Rz) is in radians or not, default is self.default_is_radian
|
|
4362
|
+
|
|
4363
|
+
:return: code
|
|
4364
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4365
|
+
"""
|
|
4366
|
+
return self._arm.set_ft_collision_reb_distance(distances, is_radian=is_radian)
|
|
4367
|
+
|
|
4368
|
+
def get_ft_collision_detection(self):
|
|
4369
|
+
"""
|
|
4370
|
+
Get the collision detection with the Six-axis Force Torque Sensor is enable or not
|
|
4371
|
+
Note:
|
|
4372
|
+
1. only available if firmware_version >= 2.6.103
|
|
4373
|
+
|
|
4374
|
+
:return: tuple((code, on_off)), only when code is 0, the returned result is correct.
|
|
4375
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4376
|
+
on_off: enable or not
|
|
4377
|
+
"""
|
|
4378
|
+
return self._arm.get_ft_collision_detection()
|
|
4379
|
+
|
|
4380
|
+
def get_ft_collision_rebound(self):
|
|
4381
|
+
"""
|
|
4382
|
+
Get the collision rebound with the Six-axis Force Torque Sensor is enable or not
|
|
4383
|
+
Note:
|
|
4384
|
+
1. only available if firmware_version >= 2.6.103
|
|
4385
|
+
|
|
4386
|
+
:return: tuple((code, on_off)), only when code is 0, the returned result is correct.
|
|
4387
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4388
|
+
on_off: enable or not
|
|
4389
|
+
"""
|
|
4390
|
+
return self._arm.get_ft_collision_rebound()
|
|
4391
|
+
|
|
4392
|
+
def get_ft_collision_threshold(self):
|
|
4393
|
+
"""
|
|
4394
|
+
Get the collision threshold with the Six-axis Force Torque Sensor
|
|
4395
|
+
Note:
|
|
4396
|
+
1. only available if firmware_version >= 2.6.103
|
|
4397
|
+
|
|
4398
|
+
:return: tuple((code, threshold)), only when code is 0, the returned result is correct.
|
|
4399
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4400
|
+
threshold: [x(N), y(N), z(N), Rx(Nm), Ry(Nm), Rz(Nm)]
|
|
4401
|
+
"""
|
|
4402
|
+
return self._arm.get_ft_collision_threshold()
|
|
4403
|
+
|
|
4404
|
+
def get_ft_collision_reb_distance(self, is_radian=None):
|
|
4405
|
+
"""
|
|
4406
|
+
Get the collision rebound distance with the Six-axis Force Torque Sensor
|
|
4407
|
+
Note:
|
|
4408
|
+
1. only available if firmware_version >= 2.6.103
|
|
4409
|
+
|
|
4410
|
+
:param is_radian: the returned value (only Rx/Ry/Rz) is in radians or not, default is self.default_is_radian
|
|
4411
|
+
|
|
4412
|
+
:return: tuple((code, threshold)), only when code is 0, the returned result is correct.
|
|
4413
|
+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
|
|
4414
|
+
distance: [x(mm), y(mm), z(mm), Rx(° or rad), Ry(° or rad), Rz(° or rad)]
|
|
4415
|
+
"""
|
|
4416
|
+
return self._arm.get_ft_collision_reb_distance(is_radian=is_radian)
|