How to Connect an Arduino Sensor to ROS 2 on a Raspberry Pi (BME280 Tutorial)
This tutorial shows you how to connect an Arduino with a BME280 environmental sensor to a Raspberry Pi running ROS 2 Humble. You'll learn how to send sensor data over serial and publish it to a ROS 2 topic in real time. Great for weather stations, robotics projects, greenhouses, or just getting hands-on with embedded systems + ROS.
What You'll Need
- Arduino Uno, Nano, or similar
 - BME280 sensor (I2C module)
 - Raspberry Pi (any model with Ubuntu and ROS 2 Humble installed)
 - USB cable for Arduino
 - Jumper wires (female-female)
 
Wiring the BME280 to Arduino (I2C)
BME280     →     Arduino
VCC        →     5V (or 3.3V depending on your module)
GND        →     GND
SDA        →     A4
SCL        →     A5
  
Arduino Code
Upload this code to your Arduino. It reads sensor values and prints them as comma-separated values over Serial.
#include <Wire.h>
#include <Adafruit_Sensor.h>
#include <Adafruit_BME280.h>
Adafruit_BME280 bme;
void setup() {
  Serial.begin(9600);
  while (!Serial);
  if (!bme.begin(0x76)) {
    Serial.println("BME280 not found!");
    while (1);
  }
  Serial.println("BME280 found.");
}
void loop() {
  float temp = bme.readTemperature();
  float hum = bme.readHumidity();
  float pres = bme.readPressure() / 100.0F;
  Serial.print(temp);
  Serial.print(",");
  Serial.print(hum);
  Serial.print(",");
  Serial.println(pres);
  delay(2000);
}
  
Raspberry Pi Setup (ROS 2 Humble)
Make sure ROS 2 Humble is installed on your Pi. If you followed a tutorial like this:
sudo apt update
sudo apt install ros-humble-ros-base
source /opt/ros/humble/setup.bash
  
Create a ROS 2 Python Package
mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
ros2 pkg create --build-type ament_python bme280_reader
  
ROS 2 Python Node: bme280_serial_node.py
Create the following file in ~/ros2_ws/src/bme280_reader/bme280_reader/bme280_serial_node.py
import rclpy
from rclpy.node import Node
import serial
from std_msgs.msg import Float32MultiArray
class BME280SerialNode(Node):
    def __init__(self):
        super().__init__('bme280_serial_reader')
        self.publisher_ = self.create_publisher(Float32MultiArray, 'bme280_data', 10)
        try:
            self.ser = serial.Serial('/dev/ttyACM1', 9600, timeout=1)
            self.get_logger().info("Connected to /dev/ttyACM1")
        except Exception as e:
            self.get_logger().error(f"Serial error: {e}")
            exit(1)
        self.timer = self.create_timer(2.0, self.read_serial)
    def read_serial(self):
        try:
            line = self.ser.readline().decode('utf-8').strip()
            if line:
                self.get_logger().info(f"RAW: {line}")
                parts = line.split(',')
                if len(parts) == 3:
                    temp = float(parts[0])
                    hum = float(parts[1])
                    pres = float(parts[2])
                    msg = Float32MultiArray(data=[temp, hum, pres])
                    self.publisher_.publish(msg)
        except Exception as e:
            self.get_logger().warn(f"Failed to read: {e}")
def main(args=None):
    rclpy.init(args=args)
    node = BME280SerialNode()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()
  
📜 Update setup.py
In ~/ros2_ws/src/bme280_reader/setup.py, add:
entry_points={
    'console_scripts': [
        'bme280_serial_node = bme280_reader.bme280_serial_node:main',
    ],
},
  
Build & Run
cd ~/ros2_ws
colcon build
source install/setup.bash
ros2 run bme280_reader bme280_serial_node
  
View the Data
In another terminal:
source ~/ros2_ws/install/setup.bash
ros2 topic echo /bme280_data
  
Example output:
data: [24.1, 49.3, 981.2]
---
  
Why This Matters
This is a real-world integration of ROS 2 with microcontroller sensors — perfect for robotics, IoT, or learning ROS 2 with actual hardware. Whether you're building a greenhouse, smart lab, or mobile robot, this pattern applies.
Next Steps
- Break into separate topics: 
/temperature,/humidity,/pressure - Visualize in 
rqt_plotor RViz - Log data to CSV or InfluxDB
 - Trigger automation when temperature exceeds a threshold
 
Stay tuned on ShillehTek.com and subscribe to our YouTube channel for more ROS and hardware tutorials.