哈嘍大家好,我是鋼板獸!
今天更新一篇和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
如果這篇文章對你有幫助,歡迎點贊、轉發、留言!