Skip to content

7. Force Torque Sensor

For UFACTORY's 6-axis force torque sensor, xArm-Python-SDK provides a series of interfaces for control and data reading.

API FunctionDescription
ft_sensor_enable()Enable or disable the force torque sensor
ft_sensor_iden_load()Identify the load of the force torque sensor
ft_sensor_cali_load()Set the load identification result as the zero point of the force torque sensor
ft_sensor_set_zero()Set the current state as the zero point (not recommended)
get_ft_sensor_data()Get the compensated and filtered force torque sensor data
ft_sensor_app_set()Set the force control application type (0: non-force control, 1: impedance control, 2: force-position hybrid control)
ft_sensor_app_get()Get the current force control application type
set_impedance_mbk()Set impedance control parameters (M, B, K)
set_impedance_config()Set the reference coordinate system and compliant axes for impedance control
set_ft_collision_detection()Set collision detection based on the force torque sensor
set_ft_collision_threshold()Set the threshold for force torque sensor collision detection
set_ft_collision_rebound()Set whether to rebound after a collision
set_ft_collision_reb_distance()Set the rebound distance after a collision

Note: The ft_sensor_set_zero() interface is not recommended. This interface uses the current force torque sensor values for load compensation, which becomes invalid when the arm's posture changes. It is recommended to use ft_sensor_iden_load() and ft_sensor_cali_load() for load identification and zeroing.

Get Force Torque Sensor Data

Use the get_ft_sensor_data(is_raw=False) method to get the sensor data.

  • is_raw: Boolean. The default is False, which returns data after gravity compensation and filtering; if True, it returns the raw data.
  • Return value: A tuple containing an error code and a data array. The data array includes the values of Fx, Fy, Fz, Tx, Ty, Tz, in units of N and N·m.

Example:

python
arm.ft_sensor_enable(True)                  # Enable the force torque sensor
iden_data = arm.ft_sensor_iden_load()       # Identify the load of the force torque sensor (takes about 4 minutes)
arm.ft_sensor_cali_load(iden_data[1])       # Use the load identification result to compensate for the zero point

code, data = arm.get_ft_sensor_data()       # Get the compensated sensor data
if code == 0:
    print("Force torque sensor data:", data)
arm.ft_sensor_enable(False)                 # Disable the force torque sensor

Drag-and-Teach Example with Force Torque

By setting the stiffness of the target axes to zero, you can achieve manual guidance for Cartesian space drag-and-teach.

python
# 1. Set drag-and-teach parameters
# Note: The smaller the M and J values, the less effort is required for dragging, but values that are too small can cause jitter.
K_pos = 0               # Linear stiffness coefficient (x,y,z), range: 0 ~ 2000 (N/m)
K_ori = 0               # Rotational stiffness coefficient (Rx,Ry,Rz), range: 0 ~ 20 (N·m/rad)
M = 0.05                # Equivalent mass, range 0.02 ~ 1 kg
J = M * 0.01            # Equivalent moment of inertia, range 1e-4 ~ 0.01 (Kg·m²)
c_axis = [1,1,1,0,0,0]  # Set x,y,z directions as compliant axes
ref_frame = 0           # Reference coordinate system: 0: base, 1: tool

# 2. Set impedance parameters
# B (damping) is a reserved parameter, set to 0
arm.set_impedance_mbk([M, M, M, J, J, J], [K_pos, K_pos, K_pos, K_ori, K_ori, K_ori], [0]*6)
arm.set_impedance_config(ref_frame, c_axis)

# 3. Enable impedance control mode
arm.ft_sensor_enable(True)  # Enable the force torque sensor
arm.ft_sensor_app_set(1)    # Switch to impedance control mode
arm.set_state(0)            # Start

# 4. Drag the arm along the compliant axes, end compliant mode after 20 seconds
time.sleep(20)

# 5. Reset the mode after finishing teaching
arm.ft_sensor_app_set(0)
arm.ft_sensor_enable(False)

Collision Detection Example with Force Torque

Here is a complete example of using the force torque sensor for collision detection. The arm will move downwards until it touches the table and triggers a collision, then it will rebound.

python
from xarm.wrapper import XArmAPI
import time
arm = XArmAPI('192.168.1.47')

arm.ft_sensor_enable(True) # Enable the force torque sensor
arm.set_ft_collision_detection(True)    # Enable force torque collision detection
arm.set_ft_collision_rebound(True)      # Set rebound after force torque collision
arm.set_ft_collision_threshold([200, 200, 30, 4, 4, 4]) # Set Z-axis force threshold to 30N

time.sleep(0.5)
arm.set_mode(0)
arm.set_state(0)
arm.set_position(x=300, y=0, z=300, roll=180, pitch=0, yaw=0, speed=100, wait=True) # Move to initial position

code = arm.set_position(x=300, y=0, z=100, roll=180, pitch=0, yaw=0, speed=20, wait=True)
if arm.has_err_warn:
    print("Error or warning detected, a collision may have occurred.")
print("Collision detection example finished.")

time.sleep(1)
arm.clean_error()  # Clear the error
arm.set_ft_collision_detection(False) # Disable force torque collision detection