7. 力矩传感器 (Force Torque Sensor)
对于UFACTORY的六维力矩传感器,xArm-Python-SDK提供了一系列接口进行控制和数据读取。
API函数 | 描述 |
---|---|
ft_sensor_enable() | 使能或断使能力矩传感器 |
ft_sensor_iden_load() | 力矩传感器的负载辨识 |
ft_sensor_cali_load() | 将力矩传感器负载辨识结果设为0点 |
ft_sensor_set_zero() | 将当前状态设为零点(不推荐使用) |
get_ft_sensor_data() | 获取补偿和滤波后的力矩传感器数据 |
ft_sensor_app_set() | 设置力控应用类型 (0: 非力控, 1: 导纳控制, 2: 力位混合控制) |
ft_sensor_app_get() | 获取当前力控应用类型 |
set_impedance_mbk() | 设置导纳控制参数 (M, B, K) |
set_impedance_config() | 设置导纳控制的参考坐标系和柔顺轴 |
set_ft_collision_detection() | 设置基于力矩传感器的碰撞检测 |
set_ft_collision_threshold() | 设置力矩传感器碰撞检测的阈值 |
set_ft_collision_rebound() | 设置碰撞后是否回弹 |
set_ft_collision_reb_distance() | 设置碰撞后回弹的距离 |
注意:
ft_sensor_set_zero()
接口不推荐使用。此接口会使用当前的力矩传感器数值进行负载补偿,当机械臂姿态变化后,该补偿即失效。推荐使用ft_sensor_iden_load()
和ft_sensor_cali_load()
进行负载辨识与清零。
获取力矩传感器数据
使用 get_ft_sensor_data(is_raw=False)
方法可以获取传感器数据。
is_raw
: 布尔值。默认为False
,返回经过重力补偿和滤波后的数据;如果为True
,则返回原始数据。- 返回值: 一个包含错误码和数据数组的元组。数据数组中包含了Fx, Fy, Fz, Tx, Ty, Tz的值,单位是N 和 N·m
示例:
python
arm.ft_sensor_enable(True) #使能力矩传感器
iden_data = arm.ft_sensor_iden_load() #力矩传感器负载辨识(耗时约4分钟)
arm.ft_sensor_cali_load(iden_data[1]) #将上述负载辨识结果用于补偿零点
code, data = arm.get_ft_sensor_data() #获取补偿后的传感器数据
if code == 0:
print("力矩传感器数据:", data)
arm.ft_sensor_enable(False) #断使能力矩传感器
力矩的拖动示教示例
通过将目标轴的刚度设置为零,可以实现手动引导的笛卡尔空间拖动示教。
python
# 1. 设置拖动示教参数
# 注意: M和J值越小,拖动越省力,但是值过小会引起抖动。
K_pos = 0 # 线性刚度系数 (x,y,z), 范围: 0 ~ 2000 (N/m)
K_ori = 0 # 旋转刚度系数 (Rx,Ry,Rz), 范围: 0 ~ 20 (N·m/rad)
M = 0.05 # 等效质量,范围 0.02 ~ 1 kg
J = M * 0.01 # 等效转动惯量 1e-4 ~ 0.01 (Kg·m²)
c_axis = [1,1,1,0,0,0] # 设置x,y,z方向为柔顺轴
ref_frame = 0 # 参考坐标系: 0:基座, 1:工具
# 2. 设置导纳参数
# B(阻尼)是保留参数,统一设为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. 开启导纳控制模式
arm.ft_sensor_enable(True) # 使能力矩传感器
arm.ft_sensor_app_set(1) # 切换为导纳控制模式
arm.set_state(0) # 启动
# 4. 沿柔顺轴拖动机械臂,20秒后结束柔顺模式
time.sleep(20)
# 5. 结束示教后,重置模式
arm.ft_sensor_app_set(0)
arm.ft_sensor_enable(False)
力矩的碰撞检测示例
下面是一个使用力矩传感器进行碰撞检测的完整示例。机械臂会向下运动,直到接触桌面并触发碰撞检测,然后回弹。
python
from xarm.wrapper import XArmAPI
import time
arm = XArmAPI('192.168.1.47')
arm.ft_sensor_enable(True) #使能力矩传感器
arm.set_ft_collision_detection(True) # 开启力矩碰撞检测
arm.set_ft_collision_rebound(True) # 设置力矩碰撞后回弹
arm.set_ft_collision_threshold([200, 200, 30, 4, 4, 4]) # 设置Z轴力阈值为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) #移动到初始位置
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("检测到错误或警告,可能已触发碰撞。")
print("碰撞检测示例完成。")
time.sleep(1)
arm.clean_error() #清除错误
arm.set_ft_collision_detection(False) # 关闭力矩碰撞检测