Skip to content

Commit 3224b8b

Browse files
committed
[feat] suppport get C54 error info
1. add api `get_c54_error_info` 2. fix `ft_sensor_get_error` 3. update doc
1 parent b6b6070 commit 3224b8b

File tree

4 files changed

+70
-47
lines changed

4 files changed

+70
-47
lines changed

doc/api/xarm_api.md

Lines changed: 26 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrapper.xarm_api
1+
xArm-Python-SDK API Documentation (V1.15.1): class XArmAPI in module xarm.wrapper.xarm_api
22

33
## class __XArmAPI__
44
****************************************
@@ -485,6 +485,17 @@ xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrappe
485485
>     err_info: [(servo_id, angle), ...]
486486
487487

488+
#### def __get_c54_error_info__(self):
489+
490+
> Get (Six-axis Force Torque Sensor) collision error (C54) info
491+
> Note:
492+
>     Only available if firmware_version >= 2.6.103
493+
>
494+
> :return: tuple((code, err_info)), only when code is 0, the returned result is correct.
495+
>     code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
496+
>     err_info: [dir, tau threshold, actual tau]
497+
498+
488499
#### def __get_c60_error_info__(self):
489500

490501
> Get linear speed limit error (C60) info
@@ -630,7 +641,7 @@ xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrappe
630641

631642
> Get the collision detection with the Six-axis Force Torque Sensor is enable or not
632643
> Note:
633-
>     1. only available if firmware_version >= 2.5.109
644+
>     1. only available if firmware_version >= 2.6.103
634645
>
635646
> :return: tuple((code, on_off)), only when code is 0, the returned result is correct.
636647
>     code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
@@ -641,7 +652,7 @@ xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrappe
641652

642653
> Get the collision rebound distance with the Six-axis Force Torque Sensor
643654
> Note:
644-
>     1. only available if firmware_version >= 2.5.109
655+
>     1. only available if firmware_version >= 2.6.103
645656
>
646657
> :param is_radian: the returned value (only Rx/Ry/Rz) is in radians or not, default is self.default_is_radian
647658
>
@@ -654,7 +665,7 @@ xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrappe
654665

655666
> Get the collision rebound with the Six-axis Force Torque Sensor is enable or not
656667
> Note:
657-
>     1. only available if firmware_version >= 2.5.109
668+
>     1. only available if firmware_version >= 2.6.103
658669
>
659670
> :return: tuple((code, on_off)), only when code is 0, the returned result is correct.
660671
>     code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
@@ -665,7 +676,7 @@ xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrappe
665676

666677
> Get the collision threshold with the Six-axis Force Torque Sensor
667678
> Note:
668-
>     1. only available if firmware_version >= 2.5.109
679+
>     1. only available if firmware_version >= 2.6.103
669680
>
670681
> :return: tuple((code, threshold)), only when code is 0, the returned result is correct.
671682
>     code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
@@ -2063,8 +2074,9 @@ xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrappe
20632074
> Note:
20642075
>     1. Only available in the new version of BIO Gripper
20652076
>
2066-
> :param mode: 0: bio gripper opening and closing mode
2067-
>              1: position loop mode
2077+
> :param mode: mode
2078+
>     0: bio gripper opening and closing mode
2079+
>     1: position loop mode
20682080
>
20692081
> :return: code
20702082
>     code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
@@ -2401,7 +2413,7 @@ xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrappe
24012413

24022414
> Set whether to enable collision detection with the Six-axis Force Torque Sensor
24032415
> Note:
2404-
>     1. only available if firmware_version >= 2.5.109
2416+
>     1. only available if firmware_version >= 2.6.103
24052417
>     2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
24062418
>     3. the Six-axis Force Torque Sensor needs to be enabled and set force mode
24072419
>
@@ -2415,12 +2427,12 @@ xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrappe
24152427

24162428
> Set the rebound distance of the collision rebound with the Six-axis Force Torque Sensor
24172429
> Note:
2418-
>     1. only available if firmware_version >= 2.5.109
2430+
>     1. only available if firmware_version >= 2.6.103
24192431
>
24202432
> :param distances: collision rebound distance, [x(mm), y(mm), z(mm), Rx(° or rad), Ry(° or rad), Rz(° or rad)]
2421-
>     x: [2, 200] (mm)
2422-
>     y: [2, 200] (mm)
2423-
>     z: [2, 200] (mm)
2433+
>     x: [2, 500] (mm)
2434+
>     y: [2, 500] (mm)
2435+
>     z: [2, 500] (mm)
24242436
>     Rx: [0.2, 50] (°)
24252437
>     Ry: [0.2, 50] (°)
24262438
>     Rz: [0.2, 50] (°)
@@ -2434,7 +2446,7 @@ xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrappe
24342446

24352447
> Set whether to enable collision rebound with the Six-axis Force Torque Sensor
24362448
> Note:
2437-
>     1. only available if firmware_version >= 2.5.109
2449+
>     1. only available if firmware_version >= 2.6.103
24382450
>
24392451
> :param on_off: enable or not
24402452
>
@@ -2446,7 +2458,7 @@ xArm-Python-SDK API Documentation (V1.15.0): class XArmAPI in module xarm.wrappe
24462458

24472459
> Set the threshold of the collision detection with the Six-axis Force Torque Sensor
24482460
> Note:
2449-
>     1. only available if firmware_version >= 2.5.109
2461+
>     1. only available if firmware_version >= 2.6.103
24502462
>
24512463
> :param thresholds: collision detection thresholds, [x(N), y(N), z(N), Rx(Nm), Ry(Nm), Rz(Nm)]
24522464
>     x: [5, 200] (N)

xarm/core/wrapper/uxbus_cmd.py

Lines changed: 20 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -1247,27 +1247,26 @@ def ft_sensor_get_config(self):
12471247
]
12481248
return ret
12491249

1250-
def ft_sensor_get_error(self):
1251-
ret = self.servo_addr_r16(8, 0x0010)
1252-
if ret[0] in [0, 1, 2] and len(ret) > 1 and ret[1] == 27:
1253-
ret[0] = 0
1254-
return ret
1255-
1256-
# @lock_require
12571250
# def ft_sensor_get_error(self):
1258-
# txdata = bytes([8])
1259-
# txdata += convert.u16_to_bytes(0x0010)
1260-
# ret = self.send_modbus_request(XCONF.UxbusReg.SERVO_R16B, txdata, 3)
1261-
# if ret == -1:
1262-
# return [XCONF.UxbusState.ERR_NOTTCP] * (7 + 1)
1263-
1264-
# ret = self.recv_modbus_response(XCONF.UxbusReg.SERVO_R16B, ret, 4, self._G_TOUT)
1265-
# if ret[0] in [0, 1, 2]:
1266-
# if convert.bytes_to_long_big(ret[1:5]) == 27:
1267-
# return [ret[0], 0]
1268-
# else:
1269-
# return [ret[0], ret[3]]
1270-
# return [ret[0], 0]
1251+
# ret = self.servo_addr_r16(8, 0x0010)
1252+
# if ret[0] in [0, 1, 2] and len(ret) > 1 and ret[1] == 27:
1253+
# ret[0] = 0
1254+
# return ret
1255+
1256+
@lock_require
1257+
def ft_sensor_get_error(self):
1258+
txdata = bytes([8])
1259+
txdata += convert.u16_to_bytes(0x0010)
1260+
ret = self.send_modbus_request(XCONF.UxbusReg.SERVO_R16B, txdata, 3)
1261+
if ret == -1:
1262+
return [XCONF.UxbusState.ERR_NOTTCP] * (7 + 1)
1263+
ret = self.recv_modbus_response(XCONF.UxbusReg.SERVO_R16B, ret, 4, self._G_TOUT)
1264+
if ret[0] in [0, 1, 2]:
1265+
if convert.bytes_to_long_big(ret[1:5]) == 27:
1266+
return [ret[0], 0]
1267+
else:
1268+
return [ret[0], ret[3]]
1269+
return [ret[0], 0]
12711270

12721271
def cali_tcp_pose(self, four_pnts):
12731272
txdata = []
@@ -1429,7 +1428,7 @@ def get_common_info(self, param_type):
14291428
data[1] = ret[1]
14301429
elif param_type == 50:
14311430
data[1] = convert.bytes_to_fp32(ret[1:])
1432-
elif param_type == 101:
1431+
elif param_type in [101, 107]:
14331432
data[1] = ret[1]
14341433
data.append(convert.bytes_to_fp32(ret[2:6]))
14351434
data.append(convert.bytes_to_fp32(ret[6:10]))

xarm/version.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
__version__ = '1.15.0'
1+
__version__ = '1.15.1'

xarm/wrapper/xarm_api.py

Lines changed: 23 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -4263,6 +4263,18 @@ def get_c38_error_info(self, is_radian=None):
42634263
# ret[1][1] = ret[1][1] if is_rad else math.degrees(ret[1][1])
42644264
return ret
42654265

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+
42664278
def run_gcode_app(self, path, **kwargs):
42674279
"""
42684280
Run gcode project file by xArmStudio software
@@ -4290,7 +4302,7 @@ def set_ft_collision_detection(self, on_off):
42904302
"""
42914303
Set whether to enable collision detection with the Six-axis Force Torque Sensor
42924304
Note:
4293-
1. only available if firmware_version >= 2.5.109
4305+
1. only available if firmware_version >= 2.6.103
42944306
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
42954307
3. the Six-axis Force Torque Sensor needs to be enabled and set force mode
42964308
@@ -4305,7 +4317,7 @@ def set_ft_collision_rebound(self, on_off):
43054317
"""
43064318
Set whether to enable collision rebound with the Six-axis Force Torque Sensor
43074319
Note:
4308-
1. only available if firmware_version >= 2.5.109
4320+
1. only available if firmware_version >= 2.6.103
43094321
43104322
:param on_off: enable or not
43114323
@@ -4318,7 +4330,7 @@ def set_ft_collision_threshold(self, thresholds):
43184330
"""
43194331
Set the threshold of the collision detection with the Six-axis Force Torque Sensor
43204332
Note:
4321-
1. only available if firmware_version >= 2.5.109
4333+
1. only available if firmware_version >= 2.6.103
43224334
43234335
:param thresholds: collision detection thresholds, [x(N), y(N), z(N), Rx(Nm), Ry(Nm), Rz(Nm)]
43244336
x: [5, 200] (N)
@@ -4337,12 +4349,12 @@ def set_ft_collision_reb_distance(self, distances, is_radian=None):
43374349
"""
43384350
Set the rebound distance of the collision rebound with the Six-axis Force Torque Sensor
43394351
Note:
4340-
1. only available if firmware_version >= 2.5.109
4352+
1. only available if firmware_version >= 2.6.103
43414353
43424354
:param distances: collision rebound distance, [x(mm), y(mm), z(mm), Rx(° or rad), Ry(° or rad), Rz(° or rad)]
4343-
x: [2, 200] (mm)
4344-
y: [2, 200] (mm)
4345-
z: [2, 200] (mm)
4355+
x: [2, 500] (mm)
4356+
y: [2, 500] (mm)
4357+
z: [2, 500] (mm)
43464358
Rx: [0.2, 50] (°)
43474359
Ry: [0.2, 50] (°)
43484360
Rz: [0.2, 50] (°)
@@ -4357,7 +4369,7 @@ def get_ft_collision_detection(self):
43574369
"""
43584370
Get the collision detection with the Six-axis Force Torque Sensor is enable or not
43594371
Note:
4360-
1. only available if firmware_version >= 2.5.109
4372+
1. only available if firmware_version >= 2.6.103
43614373
43624374
:return: tuple((code, on_off)), only when code is 0, the returned result is correct.
43634375
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
@@ -4369,7 +4381,7 @@ def get_ft_collision_rebound(self):
43694381
"""
43704382
Get the collision rebound with the Six-axis Force Torque Sensor is enable or not
43714383
Note:
4372-
1. only available if firmware_version >= 2.5.109
4384+
1. only available if firmware_version >= 2.6.103
43734385
43744386
:return: tuple((code, on_off)), only when code is 0, the returned result is correct.
43754387
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
@@ -4381,7 +4393,7 @@ def get_ft_collision_threshold(self):
43814393
"""
43824394
Get the collision threshold with the Six-axis Force Torque Sensor
43834395
Note:
4384-
1. only available if firmware_version >= 2.5.109
4396+
1. only available if firmware_version >= 2.6.103
43854397
43864398
:return: tuple((code, threshold)), only when code is 0, the returned result is correct.
43874399
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
@@ -4393,7 +4405,7 @@ def get_ft_collision_reb_distance(self, is_radian=None):
43934405
"""
43944406
Get the collision rebound distance with the Six-axis Force Torque Sensor
43954407
Note:
4396-
1. only available if firmware_version >= 2.5.109
4408+
1. only available if firmware_version >= 2.6.103
43974409
43984410
:param is_radian: the returned value (only Rx/Ry/Rz) is in radians or not, default is self.default_is_radian
43994411

0 commit comments

Comments
 (0)