# pymodbus 3.8.3
# Y轴 30齿 有减速机 变速比 19:1 距离变角位移:360/30/2*Sy_mm*19 地址 2
# X轴 丝杠1204 每周移动4mm 距离变角位移:360/4*Sx_mm 地址 3
# Z轴 20齿 无减速机 距离变角位移:360/20/2*Sz_mm 地址 4
# GT2同步皮带 齿距离2mm
from pymodbus.client.serial import ModbusSerialClient
from pymodbus.payload import BinaryPayloadBuilder
class MotorRTU:
def __init__(self, x_port='COM3', x_baud=115200,x_parity='N',x_stop_bits=1,x_byte_size=8):
# 配置串行通信参数
self.client = ModbusSerialClient(
#method='rtu', # 使用RTU模式
port=x_port, # 串行端口,根据你的设备连接情况修改
baudrate=x_baud, # 波特率,与你的设备设置相匹配
timeout=3, # 超时时间(秒)
parity=x_parity, # 校验位:无(N),奇(O),偶(E)
stopbits=x_stop_bits, # 停止位:1
bytesize=x_byte_size # 数据位:8
)
self.reg_list = list()
# 在Modbus协议中,功能码0x04(十六进制表示)用于读取输入寄存器(Input Registers)
def read_04(self,reg_address =0x0046,reg_count=3,slave_address =1):
#清空,准备放新的结果
self.reg_list.clear()
ret = False
# 连接到Modbus RTU服务器
if self.client.connect():
print("成功连接到Modbus RTU服务器")
# 读取输入寄存器
address = reg_address # 寄存器起始地址(从0开始)
count = reg_count # 要读取的寄存器数量
result = self.client.read_input_registers(address,count=count,slave=slave_address)#功能码号 04
# 检查读取是否成功
if not result.isError():
print("读取成功")
for register in result.registers:
self.reg_list.append(register)
print(f"寄存器值: {register}")
ret = True
else:
print("读取失败")
# 关闭连接
self.client.close()
else:
print("无法连接到Modbus RTU服务器")
return ret
#在Modbus协议中,功能码0x06(十六进制表示)用于预置单个寄存器(Preset Single Register)
def write_06(self,reg_address =0x000E,reg_value=0x0001,slave_address =1):
# 要写入的值(注意:Modbus寄存器通常存储16位值)
value = reg_value # 示例值,确保它在0到65535的范围内
# 将值转换为两个字节(Modbus寄存器是16位的)
value_bytes = value.to_bytes(2, byteorder='big') # 大端序,根据设备文档可能需要调整
# 地址(注意:地址可能因设备而异)
address = reg_address # 示例地址
ret = False
try:
# 连接到Modbus服务器(从设备)
if self.client.connect():
# 预置单个寄存器(功能码0x06)
# 注意:pymodbus的write_register方法内部处理了功能码0x06的调用
result = self.client.write_register(address, int.from_bytes(value_bytes, byteorder='big'),slave=slave_address)
# 检查写入是否成功
if result.isError():
print("写入失败,错误代码:", result.status)
else:
print("写入成功")
ret = True
else:
print("无法连接到Modbus服务器")
except Exception as e:
print("发生异常:", e)
finally:
# 关闭连接
self.client.close()
print("已关闭连接")
return ret
def write_10(self, reg_address =0x00F0, reg_list=None, slave_address =1):
# 要写入的数据(这里以两个16位寄存器为例,每个寄存器存储一个无符号整数)
# 要写入的数据(这里以两个16位寄存器为例,每个寄存器存储一个无符号整数)
if reg_list is None:
reg_list = [0x0000,0x0000 ]
values = reg_list # 示例值
ret = False
# 尝试连接到Modbus服务器(从设备)并写入数据
try:
if self.client.connect():
# 写入多个保持寄存器(功能码10H)
# 注意:unit参数对应于从设备的地址或ID,根据设备配置设置
# 直接将值列表传递给write_registers方法
result = self.client.write_registers(address=reg_address, values=values, slave=slave_address )
# 检查写入是否成功
if result.isError():
print("写入失败,错误代码:", result.status)
else:
print("写入成功")
ret = True
else:
print("无法连接到Modbus服务器")
except Exception as e:
print("发生异常:", e)
finally:
# 关闭连接
self.client.close()
print("已关闭连接")
return ret
#"解除堵转控制" 的英文可以翻译为 "Deactivate Stall Control" 或 "Disable Stall Prevention Control"。
# 在这里,“stall”指的是电机或机械设备在负载过大时停止转动的状态,而“control”指的是对这种情况进行控制或预防的机制。
def deactivate_stall_ctrl(self,motor_id =0x01):#串口地址
ret = self.write_06(reg_address=0x000E, reg_value=0x0001, slave_address=motor_id )
return ret
# 不得超过65535
# 按照梯形曲线控制电机速度、加速度,运行指定的角位移,单位度
def trapezoid_position_ctrl(self,
motor_id =0x01, #串口地址
is_ccw_direction = 1,# 方向 cw:0
positive_acceleration = 2000,# RPM/s
negative_acceleration = 2000,# RPM/s
max_speed =2000, # 最高RPM
angular_displacement=36000, # 角位移,度
is_absolute_angular = 0): # 0,相对角位移
#相对运动是以当前位置角度为起点进行相对位置运动,绝对运动是
#以上电时/清零后的位置角度为零点进行绝对位置坐标运动
# 按照梯形曲线控制电机速度、加速度,运行指定的角位移,单位度
low_word_angular_displacement =angular_displacement%0x10000
high_word_angular_displacement =angular_displacement>>16
values =[is_ccw_direction,positive_acceleration,negative_acceleration,max_speed,low_word_angular_displacement,high_word_angular_displacement,is_absolute_angular]
ret = self.write_10(reg_address=0x00F6, reg_list=values, slave_address=motor_id)
return ret
#力矩模式控制的英文翻译是 "Torque Mode Control"。在这个模式下,电机或执行器的输出力矩(或扭矩)是被直接控制的变量,
#而不是速度或位置。力矩模式控制常用于需要精确控制输出力或扭矩的应用中,如机器人关节驱动、精密加工设备等。
def torque_limit_ctrl(self,
motor_id =0x01, #串口地址
is_ccw_direction=0x0000, #方向 cw:0
current_slope=5000, #电流斜率(Ma/s)
torque_current=100): #力矩电流(Ma)
values = [is_ccw_direction, current_slope,torque_current,0]
ret = self.write_10(reg_address=0x00E2, reg_list=values, slave_address=motor_id)
return ret
# 使用示例
if __name__ == "__main__":
motor_rtu= MotorRTU()
#motor_rtu.read_04(reg_address =0x0046,reg_count=3,slave_address =1)
#motor_rtu.write_06(reg_address =0x000E,reg_value=0x0001,slave_address =1)
#motor_rtu.write_10(reg_address=0x00F0, reg_list=[0,2000,36000,0,0], slave_address=1)
motor_rtu.trapezoid_position_ctrl(
motor_id=0x01, # Serial port address of the motor (电机串口地址)
is_ccw_direction=0, # Direction of rotation (1 for counterclockwise, 0 for clockwise) (旋转方向,1为逆时针,0为顺时针)
positive_acceleration=2000, # Acceleration rate in RPM per second when accelerating (加速时的加速度,单位:RPM/s)
negative_acceleration=2000, # Deceleration rate in RPM per second when decelerating (减速时的减速度,单位:RPM/s)
max_speed=5000, # Maximum speed of the motor in RPM (电机的最高速度,单位:RPM)
angular_displacement=36000, # Angular displacement in degrees (角位移,单位:度)
is_absolute_angular=0 # 0 for relative angular displacement, 1 for absolute (0表示相对角位移,1表示绝对角位移)
)
motor_rtu.deactivate_stall_ctrl(motor_id =0x01)#串口地址
# motor_rtu.torque_limit_ctrl( #单纯力矩控制
# motor_id=0x01, # Serial port address of the motor (电机的串口地址)
# is_ccw_direction=0x0000, # Direction flag (0x0000 for clockwise, potentially other values for counterclockwise or to indicate no specific direction) (方向标志,0x0000表示顺时针,其他值可能表示逆时针或无特定方向)
# current_slope=5000, # Current slope in milliamperes per second (mA/s) (电流斜率,单位:毫安/秒)
# torque_current=120 # Torque current in milliamperes (mA) (力矩电流,单位:毫安)
# )