Bringing Micro-ROS to Life on ESP32 Using PlatformIO
In this project, we’ll explore the integration of Micro-ROS with an ESP32 microcontroller using PlatformIO. This setup allows for advanced ROS 2 functionalities on a microcontroller, opening up new possibilities for robotics and IoT applications. We will cover the entire process, from setting up the environment to running a Micro-ROS agent and launching a Gazebo simulation. Let’s dive in!
https://github.com/user-attachments/assets/35239472-ab11-4d1f-8cc7-afc0c007ece1
Introduction to Micro-ROS
Micro-ROS is an extension of ROS 2 that brings its powerful features to microcontrollers. It enables the use of ROS 2 functionalities on constrained devices, making it a perfect fit for integrating with the ESP32 microcontroller. By leveraging Micro-ROS, we can implement complex robotic functionalities on small and power-efficient devices.
Setting Up the Project
Step 1: Configure PlatformIO Project
First, we need to set up a PlatformIO project for the ESP32. PlatformIO is an open-source ecosystem for IoT development with a cross-platform build system and library manager.
Here’s how to configure your platformio.ini
file:
[env:ESP32_S3_DEV_4MB_QD_No_PSRAM]
platform = espressif32
board = ESP32_S3_DEV_4MB_QD_No_PSRAM
framework = arduino
board_microros_distro = humble
board_microros_transport = serial
lib_deps =
https://github.com/micro-ROS/micro_ros_platformio
Detailed Code Explanation
Let’s break down the code step by step:
Include Necessary Libraries
We start by including the necessary libraries for Micro-ROS and Arduino functionalities:
#include <micro_ros_platformio.h>
#include <Arduino.h>
#include <stdio.h>
#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <geometry_msgs/msg/twist.h>
Define Variables and Macros
We define the variables and macros needed for the project:
rcl_publisher_t publisher;
geometry_msgs__msg__Twist msg;
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;
#define LED_PIN 13
#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)){}}
publisher
: An object to handle the publishing of messages.msg
: A message object for sendingTwist
messages, which are commonly used for robot velocity commands.executor
,support
,allocator
,node
,timer
: These objects handle the Micro-ROS infrastructure.LED_PIN
: The pin number for an LED, used for indicating errors.RCCHECK
andRCSOFTCHECK
: Macros for error handling.
Error Handling Loop
We define an error handling loop that will blink an LED if an error occurs:
void error_loop() {
while(1) {
digitalWrite(LED_PIN, !digitalRead(LED_PIN));
delay(100);
}
}
This function continuously toggles an LED on and off to signal an error state.
Timer Callback Function
The timer callback function generates random linear and angular velocities and publishes them:
void timer_callback(rcl_timer_t * timer, int64_t last_call_time) {
RCLC_UNUSED(last_call_time);
if (timer != NULL) {
// Generate random linear and angular velocities
msg.linear.x = 0.5;
msg.angular.z = 1.0;
// Publish the message
RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL));
}
}
This function is called periodically by the timer to send velocity commands.
Setup Function
In the setup function, we initialize the Micro-ROS components and configure the publisher, node, timer, and executor:
void setup() {
Serial.begin(115200);
set_microros_serial_transports(Serial);
pinMode(LED_PIN, OUTPUT);
digitalWrite(LED_PIN, HIGH);
delay(2000);
allocator = rcl_get_default_allocator();
// Create init_options
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
// Create node
RCCHECK(rclc_node_init_default(&node, "esp32_node", "", &support));
// Create publisher
RCCHECK(rclc_publisher_init_default(
&publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(geometry_msgs, msg, Twist),
"/cmd_vel"));
// Create timer
const unsigned int timer_timeout = 100; // 100 ms
RCCHECK(rclc_timer_init_default(
&timer,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback));
// Create executor
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
RCCHECK(rclc_executor_add_timer(&executor, &timer));
msg.linear.x = 0;
msg.linear.y = 0;
msg.linear.z = 0;
msg.angular.x = 0;
msg.angular.y = 0;
msg.angular.z = 0;
}
Serial.begin(115200)
: Initializes the serial communication.set_microros_serial_transports(Serial)
: Configures the transport layer for Micro-ROS.pinMode(LED_PIN, OUTPUT)
: Sets the LED pin as an output.digitalWrite(LED_PIN, HIGH)
: Turns on the LED initially.allocator = rcl_get_default_allocator()
: Sets the default allocator.rclc_support_init(&support, 0, NULL, &allocator)
: Initializes the support structure.rclc_node_init_default(&node, "esp32_node", "", &support)
: Creates a ROS 2 node named "esp32_node".rclc_publisher_init_default(...)
: Initializes a publisher for the/cmd_vel
topic.rclc_timer_init_default(...)
: Creates a timer with a 100 ms period.rclc_executor_init(...)
: Initializes the executor to handle the timer callbacks.
Loop Function
The loop function ensures that the executor spins to handle the timer callback:
void loop() {
RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
}
Running the Micro-ROS Agent
To enable communication between the ESP32 and the ROS 2 environment, we need to run a Micro-ROS agent. The following commands will set up and run the agent:
cd microros_ws/
. install/setup.bash
ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0
Reboot the esp32 when above command has been run.
Running the Gazebo Client
export TURTLEBOT3_MODEL=waffle_pi
ros2 launch turtlebot3_gazebo empty_world.launch.py
Conclusion
This project demonstrates the powerful capabilities of integrating Micro-ROS with an ESP32 microcontroller using PlatformIO. By following these steps, you can leverage ROS 2 functionalities on microcontrollers, opening up new horizons for robotics and IoT applications. Whether you’re a hobbyist or a professional, this setup provides a robust platform for developing responsive and capable robotic systems.
#MicroROS #ESP32 #PlatformIO #ROS2 #Robotics #IoT #OpenSource #EmbeddedSystems #Automation 🚀🤖