Skip to content

Commit 0986871

Browse files
committed
[feat] add get_gripper_g2_position/get_bio_gripper_g2_position
1 parent a54b2fd commit 0986871

File tree

6 files changed

+110
-51
lines changed

6 files changed

+110
-51
lines changed

README.md

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
# xArm-Python-SDK
22

3+
[![PyPI Downloads](https://static.pepy.tech/badge/xarm-python-sdk)](https://pepy.tech/projects/xarm-python-sdk)
4+
35
## Overview
46
xArm Python SDK
57

@@ -21,7 +23,7 @@ xArm Python SDK
2123
```bash
2224
pip install build
2325
python -m build
24-
pip install dist/xarm_python_sdk-1.15.1-py3-none-any.whl
26+
pip install dist/xarm_python_sdk-1.16.0-py3-none-any.whl
2527
```
2628
- install with source code
2729
```bash

README.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,9 @@ xarm-python-sdk
44
.. image:: https://badge.fury.io/py/xarm-python-sdk.svg
55
:target: https://pypi.org/project/xarm-python-sdk/
66

7+
.. image:: https://static.pepy.tech/badge/xarm-python-sdk
8+
:target: https://pepy.tech/projects/xarm-python-sdk
9+
710
.. image:: https://img.shields.io/github/license/xArm-Developer/xArm-Python-SDK.svg
811
:target: https://github.com/xArm-Developer/xArm-Python-SDK/blob/main/LICENSE
912

doc/api/xarm_api.md

Lines changed: 26 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -414,6 +414,14 @@ xArm-Python-SDK API Documentation (V1.16.0): class XArmAPI in module xarm.wrappe
414414
>     error_code: See the [Bio Gripper Error Code Documentation](./xarm_api_code.md#bio-gripper-error-code) for details.
415415
416416

417+
#### def __get_bio_gripper_g2_position__(self, **kwargs):
418+
419+
> Get the position (mm) of the BIO Gripper G2
420+
>
421+
> :return: tuple((code, pos)), only when code is 0, the returned result is correct.
422+
>     code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
423+
424+
417425
#### def __get_bio_gripper_status__(self):
418426

419427
> Get the status of the bio gripper
@@ -760,9 +768,17 @@ xArm-Python-SDK API Documentation (V1.16.0): class XArmAPI in module xarm.wrappe
760768
>     err_code: See the [Gripper Error Code Documentation](./xarm_api_code.md#gripper-error-code) for details.
761769
762770

771+
#### def __get_gripper_g2_position__(self, **kwargs):
772+
773+
> Get the position (mm) of the xArm Gripper G2
774+
>
775+
> :return: tuple((code, pos)), only when code is 0, the returned result is correct.
776+
>     code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
777+
778+
763779
#### def __get_gripper_position__(self, **kwargs):
764780

765-
> Get the gripper position
781+
> Get the gripper position (pulse)
766782
>
767783
> :return: tuple((code, pos)), only when code is 0, the returned result is correct.
768784
>     code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
@@ -1294,7 +1310,7 @@ xArm-Python-SDK API Documentation (V1.16.0): class XArmAPI in module xarm.wrappe
12941310
> :param min_res_len: the minimum length of modbus response data. Used to check the data length, if not specified, no check
12951311
> :param host_id: host_id, default is 9 (TGPIO_HOST_ID)
12961312
>     9: END RS485
1297-
>     10: CONTROLLER RS485
1313+
>     11: CONTROLLER RS485
12981314
> :param is_transparent_transmission: whether to choose transparent transmission, default is False
12991315
>     Note: only available if firmware_version >= 1.11.0
13001316
> :param use_503_port: whether to use port 503 for communication, default is False
@@ -2299,11 +2315,17 @@ xArm-Python-SDK API Documentation (V1.16.0): class XArmAPI in module xarm.wrappe
22992315
>         self.set_collision_tool_model(21, radius=45, height=137)
23002316
>         :param radius: the radius of cylinder, (unit: mm)
23012317
>         :param height: the height of cylinder, (unit: mm)
2318+
>         :param x_offset: offset in the x direction, (unit: mm)
2319+
>         :param y_offset: offset in the y direction, (unit: mm)
2320+
>         :param z_offset: offset in the z direction, (unit: mm)
23022321
>     22: Cuboid, need additional parameters x, y, z
23032322
>         self.set_collision_tool_model(22, x=234, y=323, z=23)
23042323
>         :param x: the length of the cuboid in the x coordinate direction, (unit: mm)
23052324
>         :param y: the length of the cuboid in the y coordinate direction, (unit: mm)
23062325
>         :param z: the length of the cuboid in the z coordinate direction, (unit: mm)
2326+
>         :param x_offset: offset in the x direction, (unit: mm)
2327+
>         :param y_offset: offset in the y direction, (unit: mm)
2328+
>         :param z_offset: offset in the z direction, (unit: mm)
23072329
> :param args: additional parameters
23082330
> :param kwargs: additional parameters
23092331
> :return: code
@@ -2503,7 +2525,7 @@ xArm-Python-SDK API Documentation (V1.16.0): class XArmAPI in module xarm.wrappe
25032525

25042526
#### def __set_gripper_g2_position__(self, pos, speed=100, force=50, wait=False, timeout=None, **kwargs):
25052527

2506-
> Set the position of xArm Gripper G2
2528+
> Set the position of the xArm Gripper G2
25072529
>
25082530
> :param pos: gripper pos between 0 and 84, (unit: mm)
25092531
> :param speed: gripper speed between 15 and 225, default is 100, (unit: mm/s)
@@ -2530,7 +2552,7 @@ xArm-Python-SDK API Documentation (V1.16.0): class XArmAPI in module xarm.wrappe
25302552
>
25312553
> :param pos: pos
25322554
> :param wait: wait or not, default is False
2533-
> :param speed: speed,unit:r/min
2555+
> :param speed: speed, unit:r/min
25342556
> :param auto_enable: auto enable or not, default is False
25352557
> :param timeout: wait time, unit:second, default is 10s
25362558
> :return: code

xarm/wrapper/xarm_api.py

Lines changed: 29 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -104,6 +104,7 @@ def __init__(self, port=None, is_radian=False, do_not_open=False, **kwargs):
104104
'get_ft_senfor_config': self.get_ft_sensor_config,
105105
'shutdown_system': self.system_control,
106106
'set_bio_gripper_position': self.set_bio_gripper_g2_position,
107+
'get_bio_gripper_position': self.get_bio_gripper_g2_position,
107108
}
108109

109110
def __getattr__(self, item):
@@ -1821,20 +1822,29 @@ def set_gripper_mode(self, mode, **kwargs):
18211822

18221823
def get_gripper_position(self, **kwargs):
18231824
"""
1824-
Get the gripper position
1825+
Get the gripper position (pulse)
18251826
18261827
:return: tuple((code, pos)), only when code is 0, the returned result is correct.
18271828
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
18281829
"""
18291830
return self._arm.get_gripper_position(**kwargs)
18301831

1832+
def get_gripper_g2_position(self, **kwargs):
1833+
"""
1834+
Get the position (mm) of the xArm Gripper G2
1835+
1836+
:return: tuple((code, pos)), only when code is 0, the returned result is correct.
1837+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
1838+
"""
1839+
return self._arm.get_gripper_g2_position(**kwargs)
1840+
18311841
def set_gripper_position(self, pos, wait=False, speed=None, auto_enable=False, timeout=None, **kwargs):
18321842
"""
18331843
Set the gripper position
18341844
18351845
:param pos: pos
18361846
:param wait: wait or not, default is False
1837-
:param speed: speed,unit:r/min
1847+
:param speed: speed, unit:r/min
18381848
:param auto_enable: auto enable or not, default is False
18391849
:param timeout: wait time, unit:second, default is 10s
18401850
:return: code
@@ -1844,7 +1854,7 @@ def set_gripper_position(self, pos, wait=False, speed=None, auto_enable=False, t
18441854

18451855
def set_gripper_g2_position(self, pos, speed=100, force=50, wait=False, timeout=None, **kwargs):
18461856
"""
1847-
Set the position of xArm Gripper G2
1857+
Set the position of the xArm Gripper G2
18481858
18491859
:param pos: gripper pos between 0 and 84, (unit: mm)
18501860
:param speed: gripper speed between 15 and 225, default is 100, (unit: mm/s)
@@ -2859,6 +2869,15 @@ def set_bio_gripper_force(self, force):
28592869

28602870
return self._arm.set_bio_gripper_force(force)
28612871

2872+
def get_bio_gripper_g2_position(self, **kwargs):
2873+
"""
2874+
Get the position (mm) of the BIO Gripper G2
2875+
2876+
:return: tuple((code, pos)), only when code is 0, the returned result is correct.
2877+
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
2878+
"""
2879+
return self._arm.get_bio_gripper_g2_position(**kwargs)
2880+
28622881
def set_bio_gripper_g2_position(self, pos, speed=2000, force=100, wait=True, timeout=5, **kwargs):
28632882
"""
28642883
Set the position of BIO Gripper G2
@@ -2990,7 +3009,7 @@ def getset_tgpio_modbus_data(self, datas, min_res_len=0, host_id=9, is_transpare
29903009
:param min_res_len: the minimum length of modbus response data. Used to check the data length, if not specified, no check
29913010
:param host_id: host_id, default is 9 (TGPIO_HOST_ID)
29923011
9: END RS485
2993-
10: CONTROLLER RS485
3012+
11: CONTROLLER RS485
29943013
:param is_transparent_transmission: whether to choose transparent transmission, default is False
29953014
Note: only available if firmware_version >= 1.11.0
29963015
:param use_503_port: whether to use port 503 for communication, default is False
@@ -3054,11 +3073,17 @@ def set_collision_tool_model(self, tool_type, *args, **kwargs):
30543073
self.set_collision_tool_model(21, radius=45, height=137)
30553074
:param radius: the radius of cylinder, (unit: mm)
30563075
:param height: the height of cylinder, (unit: mm)
3076+
:param x_offset: offset in the x direction, (unit: mm)
3077+
:param y_offset: offset in the y direction, (unit: mm)
3078+
:param z_offset: offset in the z direction, (unit: mm)
30573079
22: Cuboid, need additional parameters x, y, z
30583080
self.set_collision_tool_model(22, x=234, y=323, z=23)
30593081
:param x: the length of the cuboid in the x coordinate direction, (unit: mm)
30603082
:param y: the length of the cuboid in the y coordinate direction, (unit: mm)
30613083
:param z: the length of the cuboid in the z coordinate direction, (unit: mm)
3084+
:param x_offset: offset in the x direction, (unit: mm)
3085+
:param y_offset: offset in the y direction, (unit: mm)
3086+
:param z_offset: offset in the z direction, (unit: mm)
30623087
:param args: additional parameters
30633088
:param kwargs: additional parameters
30643089
:return: code

xarm/x3/base.py

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -206,6 +206,7 @@ def __init__(self, port=None, is_radian=False, do_not_open=False, **kwargs):
206206

207207
self.bio_gripper_is_enabled = False
208208
self.bio_gripper_speed = 0
209+
self.bio_gripper_force = 0
209210
self.bio_gripper_error_code = 0
210211

211212
self.robotiq_is_activated = False
@@ -334,6 +335,7 @@ def _init(self):
334335

335336
self.bio_gripper_is_enabled = False
336337
self.bio_gripper_speed = 0
338+
self.bio_gripper_force = 0
337339
self.bio_gripper_error_code = 0
338340

339341
self.robotiq_is_activated = False
@@ -1343,6 +1345,7 @@ def __handle_report_normal_old(rx_data):
13431345
self.gripper_is_enabled = False
13441346
self.bio_gripper_is_enabled = False
13451347
self.bio_gripper_speed = 0
1348+
self.bio_gripper_force = 0
13461349
self.gripper_is_enabled = False
13471350
self.gripper_speed = 0
13481351
self.gripper_version_numbers = [-1, -1, -1]
@@ -1357,6 +1360,7 @@ def __handle_report_normal_old(rx_data):
13571360
# self.gripper_is_enabled = False
13581361
# self.bio_gripper_is_enabled = False
13591362
# self.bio_gripper_speed = 0
1363+
# self.bio_gripper_force = 0
13601364
# self.gripper_is_enabled = False
13611365
# self.gripper_speed = 0
13621366
# self.gripper_version_numbers = [-1, -1, -1]
@@ -1547,6 +1551,7 @@ def __handle_report_normal(rx_data):
15471551
self.gripper_is_enabled = False
15481552
self.bio_gripper_is_enabled = False
15491553
self.bio_gripper_speed = 0
1554+
self.bio_gripper_force = 0
15501555
self.gripper_is_enabled = False
15511556
self.gripper_speed = 0
15521557
self.gripper_version_numbers = [-1, -1, -1]
@@ -1561,6 +1566,7 @@ def __handle_report_normal(rx_data):
15611566
# self.gripper_is_enabled = False
15621567
# self.bio_gripper_is_enabled = False
15631568
# self.bio_gripper_speed = -1
1569+
# self.bio_gripper_force = -1
15641570
# self.gripper_speed = -1
15651571
# self.gripper_version_numbers = [-1, -1, -1]
15661572
# self.linear_track_is_enabled = False

0 commit comments

Comments
 (0)