(3)pyserial读取电子秤 的重量

232转USB 使用过程中,发现软件关闭串口后,必须重新插拔一次,否则串口处于被占用状态。
刚下单买了一个RS232转485的转接头,试一下。
1、串口通讯协议
- 数据格式
|
S |
T |
, |
N |
T |
, |
|
1 |
2 |
3 |
4 |
. |
5 |
6 |
|
k |
g |
CR |
LF |
|
Header1 |
Header2 |
重量数据(8个字节长度) |
单位 |
0D 0A |
||||||||||||||
|
Header1 |
Header2 |
||||||
|
S |
T |
, |
稳定(STABLE) |
N |
T |
, |
净重(NET) |
|
U |
S |
, |
不稳定(UNSTABLE) |
G |
S |
, |
毛重(GROSS) |
|
O |
V |
, |
超重 |
T |
R |
, |
皮重(扣重,TARE) |
重量数据为ASCII字符,可能有下列文字
“ 0” ~ “9”数字 “ ” 空白字符 “ . ”小数点 “ - ” 负号
如果为应答模式,并且上位机有送地址信息,则回送的数据前加上@XX,XX为具体的地址,如地址2则发送@02.
如果电子秤中设置有校验码,则CR和LF前有2个字符的异或校验码.异或校验码为除CR,LF和校验码以外的字符进行异或运算,并将结果的高4位和低4位分别转为字符.如高4位为1,则转为字符’1’,如高4为为15,则转为字符’E’.
- 上位机命令格式
|
R |
T |
CR |
LF |
|
Header |
13 |
10 |
|
|
Header(命令) |
十六进制 |
完整指令 |
||
|
R |
N |
读净重(NET) |
52 4E |
52 4E 13 10 |
|
T |
读皮重(扣重,TARE) |
52 54 |
52 54 13 10 |
|
|
G |
读毛重(GROSS) |
52 47 |
52 47 13 10 |
|
|
C |
读内码 |
52 43 |
52 43 13 10 |
|
|
U |
读单重(计数秤) |
52 55 |
52 55 13 10 |
|
|
Q |
读数量(计数秤) |
52 51 |
52 51 13 10 |
|
|
S |
Z |
归零 |
53 5A |
53 5A 13 10 |
|
T |
去皮(扣重) |
53 54 |
53 54 13 10 |
|
|
U |
切换单位 |
53 55 |
53 55 13 10 |
|
如果多台连机,则可在命令前加上地址,格式为@xx, xx为地址信息,如访问地址为02的电子秤,则前面加@02.
如果电子秤中设置有校验码,则CR和LF前有2个字符的异或校验码.异或校验码为除CR,LF和校验码以外的字符进行异或运算,并将结果的高4位和低4位分别转为字符.如高4位为1,则转为字符’1’,如高4为为15,则转为字符’E’.
注:CR的值为0D,字符为’\r’, LF的值为0A,字符为’\n’.
串口通讯模式设置中(电子秤的P2 TRA的FC参数),1234都兼容上位机命令,其中模式1(连续发送)和2和4只支持S开头的三个指令,3支持全部指令
出厂应该是0号通信协议
2、电子秤设置:
刷新1,2,3,...时,去皮按3次,进入设置
设置F8 串口波特率
设置F9 选择 通信方式4
设置FA 选择 协议3
3、协议3的应答

4、串口助手调试

5、python 测试代码
import serial import time try: ser = serial.Serial( port='COM3', baudrate=9600, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=1 ) time.sleep(2) # 等待串口初始化(部分设备需要) for i in range(1): message = "RT\x13\x10" ser.write(message.encode('ascii')) response = ser.readline().decode('ascii').strip() print(f"设备回复: {response}") except serial.SerialException as e: print(f"串口错误: {e}") # 检查常见错误类型 if "PermissionError" in str(e): print("提示:串口被占用或权限不足!") except Exception as e: print(f"其他错误: {e}") finally: if 'ser' in locals() and ser.is_open: ser.close() # 确保串口关闭
6、设计为ROS2 节点,读取电子称数据并topic发布
电子秤设置:
刷新1,2,3,...时,去皮按3次,进入设置
设置F8 串口波特率 9600
设置F9 选择 通信方式3 连续通信(连续将测量值发送到串口)
设置FA 选择 协议 1
setup.py 加入:
1 #!/usr/bin/env python3 2 import rclpy 3 from rclpy.node import Node 4 from std_msgs.msg import String 5 import serial 6 import time 7 from serial.serialutil import SerialException 8 import threading 9 import re 10 import numpy as np 11 from example_interfaces.msg import Float32 12 13 class SerialReaderNode(Node): 14 def __init__(self): 15 super().__init__('serial_reader') 16 17 # 声明参数并设置默认值 18 self.declare_parameters( 19 namespace='', 20 parameters=[ 21 ('port', '/dev/ttyUSB0'), 22 ('baudrate', 9600), 23 ('timeout', 0.1), 24 ('publish_raw', True), 25 ('publish_parsed', True), 26 ('max_retries', 3), 27 ('expected_pattern', r'ST,GS,\s*([\d.]+)\s*kg')#r'ST,GS\s+([\d.]+)\s*kg') # 数据解析正则表达式 28 ] 29 ) 30 31 # 获取参数值 32 self.port = self.get_parameter('port').value 33 self.baudrate = self.get_parameter('baudrate').value 34 self.timeout = self.get_parameter('timeout').value 35 self.publish_raw = self.get_parameter('publish_raw').value 36 self.publish_parsed = self.get_parameter('publish_parsed').value 37 self.max_retries = self.get_parameter('max_retries').value 38 self.expected_pattern = self.get_parameter('expected_pattern').value 39 40 # 创建发布者 41 if self.publish_raw: 42 self.raw_publisher = self.create_publisher(String, 'serial_raw_data', 10) 43 44 if self.publish_parsed: 45 self.parsed_publisher = self.create_publisher(Float32, 'weight_data', 10) 46 47 # 初始化串口连接 48 self.ser = None 49 self.retry_count = 0 50 self.connect_serial() 51 52 # 创建读取线程 53 self.read_thread = threading.Thread(target=self.read_serial_data) 54 self.read_thread.daemon = True 55 self.read_thread.start() 56 57 # 记录启动信息 58 self.get_logger().info(f"串口节点已启动: 端口={self.port}, 波特率={self.baudrate}") 59 self.get_logger().info(f"数据解析模式: 原始数据={self.publish_raw}, 解析数据={self.publish_parsed}") 60 61 def connect_serial(self): 62 """尝试连接串口设备""" 63 try: 64 if self.ser and self.ser.is_open: 65 self.ser.close() 66 67 self.ser = serial.Serial( 68 port=self.port, 69 baudrate=self.baudrate, 70 bytesize=serial.EIGHTBITS, 71 parity=serial.PARITY_NONE, 72 stopbits=serial.STOPBITS_ONE, 73 timeout=self.timeout 74 ) 75 76 # 等待串口初始化 77 time.sleep(0.5) 78 self.retry_count = 0 79 self.get_logger().info(f"成功连接到串口 {self.port}") 80 return True 81 82 except SerialException as e: 83 self.retry_count += 1 84 error_msg = f"串口连接错误: {e}" 85 86 # 检查常见错误类型 87 if "PermissionError" in str(e) or "Permission denied" in str(e): 88 error_msg += "\n提示: 串口被占用或权限不足! 请尝试:" 89 error_msg += f"\n 1. 使用 'sudo chmod 666 {self.port}' 授予权限" 90 error_msg += "\n 2. 将用户添加到 dialout 组: 'sudo usermod -a -G dialout $USER'" 91 error_msg += "\n 3. 重新登录使权限生效" 92 93 self.get_logger().error(error_msg) 94 95 if self.retry_count < self.max_retries: 96 self.get_logger().warning(f"将在 5 秒后重试 ({self.retry_count}/{self.max_retries})") 97 threading.Timer(5.0, self.connect_serial).start() 98 else: 99 self.get_logger().fatal("超过最大重试次数, 节点将关闭") 100 rclpy.shutdown() 101 102 return False 103 104 def read_serial_data(self): 105 """持续读取串口数据的线程函数""" 106 buffer = "" 107 while rclpy.ok(): 108 try: 109 if not self.ser or not self.ser.is_open: 110 time.sleep(1) 111 continue 112 113 # 读取串口数据 114 data = self.ser.read(self.ser.in_waiting or 1) 115 if data: 116 try: 117 # 解码数据并添加到缓冲区 118 buffer += data.decode('ascii', errors='replace') 119 120 # 处理完整行 121 while '\n' in buffer or '\r' in buffer: 122 # 提取一行数据 123 line, _, buffer = buffer.partition('\n') 124 line = line.strip() 125 self.get_logger().info(f'报文:{line}') 126 if '\r' in line: 127 line = line.split('\r')[-1].strip() 128 129 if line: 130 # 处理特殊字符 131 processed_line = re.sub( 132 r'[\x00-\x1F]', 133 lambda m: f'<{ord(m.group(0)):02X}>', 134 line 135 ) 136 137 # 发布原始数据 138 if self.publish_raw: 139 self.publish_raw_data(processed_line) 140 141 # 解析并发布重量数据 142 if self.publish_parsed: 143 weight = self.parse_weight_data(processed_line) 144 if weight is not None: 145 self.publish_parsed_data(weight) 146 self.get_logger().info(f'重量:{weight}') 147 except UnicodeDecodeError as e: 148 self.get_logger().error(f"解码错误: {e}") 149 buffer = "" 150 151 # 短暂休眠避免CPU占用过高 152 time.sleep(0.05) 153 154 except SerialException as e: 155 self.get_logger().error(f"串口读取错误: {e}") 156 self.connect_serial() 157 except Exception as e: 158 self.get_logger().error(f"未知错误: {e}") 159 buffer = "" 160 161 def parse_weight_data(self, data): 162 """解析重量数据""" 163 try: 164 # 使用正则表达式匹配重量值 165 match = re.search(self.expected_pattern, data) 166 if match: 167 weight_str = match.group(1) 168 weight = float(weight_str) 169 self.get_logger().info(f"解析到重量值: {weight} kg") 170 return weight 171 else: 172 self.get_logger().debug(f"未匹配到重量数据: {data}", throttle_duration_sec=5.0) 173 return None 174 except (ValueError, TypeError) as e: 175 self.get_logger().error(f"数据解析失败: {e} - 原始数据: {data}") 176 return None 177 178 def publish_raw_data(self, data): 179 """发布原始串口数据""" 180 msg = String() 181 msg.data = data 182 self.raw_publisher.publish(msg) 183 self.get_logger().debug(f"发布原始数据: {data}", throttle_duration_sec=1.0) 184 185 def publish_parsed_data(self, weight): 186 """发布解析后的重量数据""" 187 msg = Float32() 188 msg.data = weight 189 self.parsed_publisher.publish(msg) 190 self.get_logger().debug(f"发布重量数据: {weight} kg", throttle_duration_sec=1.0) 191 192 def close_serial(self): 193 """关闭串口连接""" 194 if self.ser and self.ser.is_open: 195 self.ser.close() 196 self.get_logger().info("串口连接已关闭") 197 198 def main(args=None): 199 rclpy.init(args=args) 200 node = SerialReaderNode() 201 202 try: 203 rclpy.spin(node) 204 except KeyboardInterrupt: 205 pass 206 finally: 207 node.close_serial() 208 node.destroy_node() 209 rclpy.shutdown() 210 211 if __name__ == '__main__': 212 main()
查看节点topic发布信息
ros2 topic list
ros2 topic echo /weight_data

浙公网安备 33010602011771号