使用 PlatformIO 和 Micro-ROS 通过 ESP32 发布 DHT11 温湿度数据到 ROS 2
本文介绍如何使用 PlatformIO 和 Micro-ROS,在 ESP32 上通过 DHT11 传感器采集温湿度数据并发布到 ROS 2 系统。整个项目包括硬件连接、软件配置以及代码实现。
硬件准备
- ESP32 开发板
- DHT11 温湿度传感器
- 10kΩ 上拉电阻(可选,用于数据引脚)
- 连接线若干
硬件连接
- DHT11 引脚说明:
- VCC: 连接 ESP32 的 3.3V
- GND: 连接 ESP32 的 GND
- DATA: 连接 ESP32 的 GPIO4(可根据需要修改代码中的
DHTPIN
)
- 上拉电阻(可选):
- 在 DHT11 的 DATA 引脚与 VCC 引脚之间连接一个 10kΩ 电阻。
软件准备
安装 PlatformIO
PlatformIO 是一个强大的物联网开发工具,支持多种硬件平台。安装方法如下:
- 在 VS Code 中安装 PlatformIO 插件.
- 安装完成后重启 VS Code。
安装所需库
在 platformio.ini
文件中配置所需库,确保代码能正常编译。
[env:esp32dev]
platform = espressif32
board = esp32dev
framework = arduino
lib_deps =
https://github.com/micro-ROS/micro_ros_platformio
adafruit/DHT sensor library @ ^1.4.6
adafruit/Adafruit Unified Sensor@^1.1.7
kaiaai/micro_ros_kaia@^2.0.7-iron.5
monitor_speed = 115200
build_flags =
-DMICRO_ROS_TRANSPORT_ARDUINO_SERIAL
代码实现
主程序
以下代码实现了 DHT11 数据采集,并通过 micro-ROS 发布温度和湿度消息到 ROS 2。
#include <micro_ros_arduino.h>
#include <DHT.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <sensor_msgs/msg/temperature.h>
#include <sensor_msgs/msg/relative_humidity.h>
#define DHTPIN 4 // 数据引脚
#define DHTTYPE DHT11 // DHT类型(若为DHT22,请改为DHT22)
DHT dht(DHTPIN, DHTTYPE);
rcl_publisher_t temp_pub;
rcl_publisher_t humidity_pub;
sensor_msgs__msg__Temperature temp_msg;
sensor_msgs__msg__RelativeHumidity humidity_msg;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
// 定时器逻辑
unsigned long previousMillis = 0;
const unsigned long interval = 2000; // 2秒
#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}
// 错误循环
void error_loop() {
while (1) {
delay(100);
}
}
// 数据发布逻辑
void publish_sensor_data() {
float temperature = dht.readTemperature();
float humidity = dht.readHumidity();
if (!isnan(temperature) && !isnan(humidity)) {
// 填充温度消息
temp_msg.temperature = temperature;
temp_msg.variance = 0.0; // 可选设置,表示温度精度
// 填充湿度消息
humidity_msg.relative_humidity = humidity;
humidity_msg.variance = 0.0; // 可选设置,表示湿度精度
// 发布消息
RCCHECK(rcl_publish(&temp_pub, &temp_msg, NULL));
RCCHECK(rcl_publish(&humidity_pub, &humidity_msg, NULL));
// 打印发布信息
Serial.print("Temperature: ");
Serial.print(temperature);
Serial.println(" °C");
Serial.print("Humidity: ");
Serial.print(humidity);
Serial.println(" %");
} else {
Serial.println("Failed to read from DHT sensor!");
}
}
void setup() {
Serial.begin(115200);
set_microros_transports();
// 延迟以确保串口稳定
delay(2000);
// 初始化DHT传感器
dht.begin();
allocator = rcl_get_default_allocator();
// 初始化micro-ROS支持
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
// 创建节点
RCCHECK(rclc_node_init_default(&node, "dht_node", "", &support));
// 创建温度和湿度发布者
RCCHECK(rclc_publisher_init_default(
&temp_pub,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, Temperature),
"temperature"));
RCCHECK(rclc_publisher_init_default(
&humidity_pub,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, RelativeHumidity),
"humidity"));
}
void loop() {
unsigned long currentMillis = millis();
if (currentMillis - previousMillis >= interval) {
previousMillis = currentMillis;
publish_sensor_data();
}
delay(50); // 避免占用CPU
}
运行步骤
-
上传代码: 使用 PlatformIO 上传代码到 ESP32,确保编译通过。
- 启动 ROS 2 代理:
在运行 ROS 2 的主机上启动 micro-ROS Agent:
ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0
- 验证 ROS 2 数据:
- 查看 ROS 2 节点:
ros2 node list
- 查看发布的消息:
ros2 topic list
- 订阅温度和湿度数据:
ros2 topic echo /temperature ros2 topic echo /humidity
- 查看 ROS 2 节点:
输出示例
以下是正确运行后的串口和 ROS 2 输出示例:
串口输出
Temperature: 25.3 °C
Humidity: 45.7 %
ROS 2 输出
data:
temperature: 25.3
variance: 0.0
---
data:
relative_humidity: 45.7
variance: 0.0
---
总结
成功实现:
- ESP32 读取 DHT11 传感器数据。
- 使用 micro-ROS 将温湿度数据发布到 ROS 2 系统。