Skip to content

Commit 125ec4f

Browse files
committed
[feat] Added parameter to support get raw data of the Six-axis Force Torque Sensor
1 parent 70b0bb8 commit 125ec4f

File tree

6 files changed

+15
-7
lines changed

6 files changed

+15
-7
lines changed

README.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@ xArm Python SDK
4141

4242
## Update Summary
4343
- > ### 1.16.0
44+
- Added parameter to support get raw data of the Six-axis Force Torque Sensor
4445
- Added an interface to control xArm Gripper G2
4546
- Optimize the interface for controlling BIO Gripper G2
4647
- Extend the get_joint_states interface

ReleaseNotes.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
## Update Summary
44

55
- > ### 1.16.0
6+
- Added parameter to support get raw data of the Six-axis Force Torque Sensor
67
- Added an interface to control xArm Gripper G2
78
- Optimize the interface for controlling BIO Gripper G2
89
- Extend the get_joint_states interface

doc/api/xarm_api.md

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -724,13 +724,14 @@ xArm-Python-SDK API Documentation (V1.16.0): class XArmAPI in module xarm.wrappe
724724
>         [21] xe_limit: 6d vector. for compliant axes, these values are the maximum allowed tcp speed along/about the axis. mm/s
725725
726726

727-
#### def __get_ft_sensor_data__(self):
727+
#### def __get_ft_sensor_data__(self, is_raw=False):
728728

729729
> Get the data of the Six-axis Force Torque Sensor
730730
> Note:
731731
>     1. only available if firmware_version >= 1.8.3
732732
>     2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
733733
>
734+
> :param is_raw: get the raw data or not.
734735
> :return: tuple((code, exe_ft))
735736
>     code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
736737
>     ft_data: only when code is 0, the returned result is correct.

xarm/core/wrapper/uxbus_cmd.py

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1207,8 +1207,11 @@ def ft_sensor_app_set(self, app_code):
12071207
def ft_sensor_app_get(self):
12081208
return self.get_nu8(XCONF.UxbusReg.FTSENSOR_GET_APP, 1)
12091209

1210-
def ft_sensor_get_data(self, is_new=True):
1211-
return self.get_nfp32(XCONF.UxbusReg.FTSENSOR_GET_DATA if is_new else XCONF.UxbusReg.FTSENSOR_GET_DATA_OLD, 6)
1210+
def ft_sensor_get_data(self, is_new=True, is_raw=False):
1211+
if is_new and is_raw:
1212+
return self.get_nfp32_with_datas(XCONF.UxbusReg.FTSENSOR_GET_DATA, [1], 1, 6)
1213+
else:
1214+
return self.get_nfp32(XCONF.UxbusReg.FTSENSOR_GET_DATA if is_new else XCONF.UxbusReg.FTSENSOR_GET_DATA_OLD, 6)
12121215

12131216
def ft_sensor_get_config(self):
12141217
ret = self.get_nu8(XCONF.UxbusReg.FTSENSOR_GET_CONFIG, 280)

xarm/wrapper/xarm_api.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3357,19 +3357,20 @@ def ft_sensor_app_get(self):
33573357
"""
33583358
return self._arm.ft_sensor_app_get()
33593359

3360-
def get_ft_sensor_data(self):
3360+
def get_ft_sensor_data(self, is_raw=False):
33613361
"""
33623362
Get the data of the Six-axis Force Torque Sensor
33633363
Note:
33643364
1. only available if firmware_version >= 1.8.3
33653365
2. the Six-axis Force Torque Sensor is required (the third party is not currently supported)
33663366
3367+
:param is_raw: get the raw data or not.
33673368
:return: tuple((code, exe_ft))
33683369
code: See the [API Code Documentation](./xarm_api_code.md#api-code) for details.
33693370
ft_data: only when code is 0, the returned result is correct.
33703371
Note: The external force detection value of the Six-axis Force Torque Sensor after filtering, load and offset compensation
33713372
"""
3372-
return self._arm.get_ft_sensor_data()
3373+
return self._arm.get_ft_sensor_data(is_raw=is_raw)
33733374

33743375
def get_ft_sensor_config(self):
33753376
"""

xarm/x3/ft_sensor.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -190,8 +190,9 @@ def ft_sensor_app_get(self):
190190
return self._check_code(ret[0]), ret[1]
191191

192192
@xarm_is_connected(_type='get')
193-
def get_ft_sensor_data(self):
194-
ret = self.arm_cmd.ft_sensor_get_data(self.version_is_ge(1, 8, 3))
193+
def get_ft_sensor_data(self, is_raw=False):
194+
is_raw = is_raw if self.version_is_ge(2, 6, 109) else False
195+
ret = self.arm_cmd.ft_sensor_get_data(self.version_is_ge(1, 8, 3), is_raw)
195196
return self._check_code(ret[0]), ret[1:7]
196197

197198
@xarm_is_connected(_type='get')

0 commit comments

Comments
 (0)