哈喽大家好,我是钢板兽!
今天更新一篇和ROS相关的文章,有个项目需求是在ROS中获取并发布UBS式传感器的温湿度,我使用的温湿度传感器简介如下:
DL11- MC-S1 温湿度传感器通过USB 接口采用标准MODBUS RTU 协议通信,采用高精度的SHT40测量单元。
一开始尝试通过pymodbus通信,但是在安装好对应的依赖后依然不成功,于是使用字节级Modbus报文构造,通过 Python 的 pyserial
库以字节流形式与设备通信。
1.Modbus RTU 协议原理
Modbus RTU 是一种工业标准的串行通信协议,采用主从架构,每帧通信格式如下:
字段 | 长度 | 说明 |
---|---|---|
地址 | 1B | 从设备地址,通常为 1 |
功能码 | 1B | 0x03 表示读保持寄存器 |
起始地址 | 2B | 要读取的寄存器起始地址 |
寄存器数量 | 2B | 要读取的寄存器个数 |
CRC 校验 | 2B | 帧末尾附带的错误校验值 |
请求帧解析:
01 03 00 00 00 02 C4 0B
01
:设备地址(从站地址 1)03
:功能码,表示“读取保持寄存器”00 00
:寄存器起始地址 = 0x0000,即温度寄存器00 02
:读取 2 个寄存器(温度 + 湿度)C4 0B
:CRC 校验(低位在前,高位在后)
响应帧解析:
01 03 04 01 19 02 11 EB 64
01
:从站地址03
:功能码04
:后续数据字节数(4 字节)01 19
:寄存器 0x0000 的值 → 281(温度 28.1°C)02 11
:寄存器 0x0001 的值 → 529(湿度 52.9%RH)EB 64
:CRC 校验
2.调试串口
-
查看串口是否被识别:
ls /dev/ttyUSB*
-
串口权限设置:
sudo usermod -aG dialout $USER # 重启系统后生效
3.Ros节点
-
脚本路径
~/catkin_ws/src/temperature_sensor/scripts/modbus_raw_node.py
-
节点代码
节点要实现的功能:
- 每秒向串口写入 Modbus 请求报文
- 读取 9 字节返回帧,并解析温湿度原始值
- 构造 ROS 消息并发布到
/sensor/temperature
与/sensor/humidity
#!/usr/bin/env python3 import rospy import serial from sensor_msgs.msg import Temperature # 引入标准温度消息类型 from std_msgs.msg import Float32 # 引入标准浮点数消息类型# 解析 Modbus 响应帧,提取温湿度 def parse_modbus_response(data):if len(data) != 9 or data[0] != 0x01 or data[1] != 0x03:return None, None # 帧长度或地址/功能码错误则返回空值temp_raw = data[3] << 8 | data[4] # 拼接为温度原始值hum_raw = data[5] << 8 | data[6] # 拼接为湿度原始值temp = temp_raw / 10.0 # 转换为实际温度值hum = hum_raw / 10.0 # 转换为实际湿度值return temp, hum# 主函数def main():rospy.init_node("modbus_raw_temperature_node") # 初始化 ROS 节点# 获取串口参数port = rospy.get_param("~port", "/dev/ttyUSB0") # 默认串口设备baudrate = rospy.get_param("~baudrate", 9600) # 默认波特率# 初始化两个 ROS 发布器temp_pub = rospy.Publisher("/sensor/temperature", Temperature, queue_size=10)hum_pub = rospy.Publisher("/sensor/humidity", Float32, queue_size=10)try:# 尝试打开串口ser = serial.Serial(port=port, baudrate=baudrate, bytesize=8, parity='N', stopbits=1, timeout=1)rospy.loginfo("串口连接成功")except Exception as e:rospy.logerr(f"串口打开失败: {e}")returnrate = rospy.Rate(1) # 循环频率:1Hzwhile not rospy.is_shutdown():request = bytes.fromhex("01 03 00 00 00 02 C4 0B") # 构造 Modbus 请求帧ser.write(request) # 向串口写入请求response = ser.read(9) # 读取9字节响应temp, hum = parse_modbus_response(response) # 解析响应数据now = rospy.Time.now() # 获取当前时间戳if temp is not None:msg = Temperature()msg.header.stamp = nowmsg.temperature = tempmsg.variance = 0.0temp_pub.publish(msg) # 发布温度消息rospy.loginfo(f"温度: {temp} ℃")if hum is not None:hum_pub.publish(Float32(data=hum)) # 发布湿度消息rospy.loginfo(f"湿度: {hum} %RH")rate.sleep() # 等待下一次循环ser.close() # 程序退出时关闭串口if __name__ == "__main__":main() # 调用主函数启动节点
-
添加执行权限
chmod +x modbus_raw_node.py
-
运行
rosrun temperature_sensor modbus_raw_node.py _port:=/dev/ttyUSB0
-
话题发布
rostopic echo /sensor/temperature rostopic echo /sensor/humidit
如果这篇文章对你有帮助,欢迎点赞、转发、留言!