Free Shipping for orders over ₹999

support@thinkrobotics.com | +91 93183 94903

Micro-ROS on STM32: Complete How-To Guide for ROS 2 on MCUs

Micro-ROS on STM32: Complete How-To Guide for ROS 2 on MCUs


Micro-ROS brings the power of ROS 2 to resource-constrained microcontrollers, enabling direct integration of STM32 MCUs into robotic systems as first-class ROS 2 entities. This comprehensive tutorial guides you through implementing micro-ROS on STM32 microcontrollers, transforming your embedded devices into competent ROS 2 nodes.

Unlike traditional approaches that require separate single-board computers, micro-ROS allows STM32 microcontrollers to publish, subscribe, and participate directly in ROS 2 networks with minimal overhead and real-time performance.

Understanding Micro-ROS Architecture

What is Micro-ROS?

Micro-ROS is a specialized implementation of ROS 2 designed for microcontrollers with limited computational resources. It provides a lightweight middleware that enables MCUs to communicate with the broader ROS 2 ecosystem while maintaining real-time constraints and low power consumption.

Key Components:

  • Micro-ROS Client: Runs on the microcontroller (STM32)

  • Micro-ROS Agent: Bridges MCU and ROS 2 network (runs on PC/SBC)

  • XRCE-DDS: Lightweight communication protocol

  • Custom Transport Layer: UART, USB, or Ethernet communication

Hardware Requirements

Minimum STM32 Requirements:

  • ARM Cortex-M4 or higher processor

  • 32KB+ RAM (64KB+ recommended)

  • 256KB+ Flash memory

  • UART/USB peripheral for communication

  • Crystal oscillator for stable timing

Recommended Development Boards:

  • STM32F407 Discovery (196KB RAM, 1MB Flash)

  • STM32F429 Nucleo (256KB RAM, 2MB Flash)

  • STM32L4 series for low-power applications

  • STM32H7 series for high-performance requirements

Development Environment Setup

Prerequisites Installation

Host Computer Requirements:

  • Ubuntu 22.04 LTS (recommended) or Docker container

  • ROS 2 Humble Hawksbill installation

  • STM32CubeMX for project generation

  • ARM GCC toolchain

Install ROS 2 Humble:

bash

# Add ROS 2 repository

sudo apt update && sudo apt install curl gnupg lsb-release

sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key \

  -o /usr/share/keyrings/ros-archive-keyring.gpg


echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] \

  http://packages.ros.org/ros2/ubuntu $(source /etc/os-release && echo $UBUNTU_CODENAME) main" | \

  sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null


# Install ROS 2 Humble

sudo apt update

sudo apt install ros-humble-desktop

source /opt/ros/humble/setup.bash

Micro-ROS Setup

Create Micro-ROS Workspace:

bash

# Source ROS 2 environment

source /opt/ros/humble/setup.bash


# Create workspace and clone micro-ROS setup

mkdir microros_ws && cd microros_ws

git clone -b humble https://github.com/micro-ROS/micro_ros_setup.git src/micro_ros_setup


# Update dependencies and build

sudo apt update && rosdep update

rosdep install --from-paths src --ignore-src -y

colcon build

source install/local_setup.bash

Create and Build Micro-ROS Agent:

bash

# Download and build micro-ROS agent

ros2 run micro_ros_setup create_agent_ws.sh

ros2 run micro_ros_setup build_agent.sh

source install/local_setup.bash

STM32 Project Configuration with STM32CubeMX

Basic Project Setup

Step 1: Create New Project

  1. Launch STM32CubeMX

  2. Select your target STM32 microcontroller

  3. Create a new project and configure basic settings

Step 2: System Configuration

System Core → RCC → High Speed Clock (HSE): Crystal/Ceramic Resonator

System Core → SYS → Timebase Source: TIM1 (not SysTick)

Step 3: FreeRTOS Configuration

Middleware → FREERTOS → Interface: CMSIS_V2

Middleware → FREERTOS → Configuration → Tasks and Queues:

- Increase defaultStack size to 3000 words minimum

- Total heap size: 10240 bytes minimum

Step 4: UART Configuration for Communication

Connectivity → UART (e.g., USART2):

- Mode: Asynchronous

- Baud Rate: 115200

- Word Length: 8 bits

- Parity: None

- Stop Bits: 1


DMA Settings → Add:

- UART Rx: Mode = Circular, Priority = Very High

- UART Tx: Mode = Normal, Priority = Very High


NVIC Settings:

- Enable UART global interrupt

Step 5: Project Generation

Project Manager → Toolchain/IDE: Makefile

Project Manager → Code Generator: 

- Generate peripheral initialization as pairs of .c/.h files per peripheral

Micro-ROS Integration

Step 1: Clone Utilities Repository

bash

# In your generated STM32 project root folder

git clone https://github.com/micro-ROS/micro_ros_stm32cubemx_utils.git

Step 2: Modify Makefile. Add the following to your generated Makefile:

makefile

####################################### 

# micro-ROS addons

####################################### 

LDFLAGS += micro_ros_stm32cubemx_utils/microros_static_library/libmicroros/libmicroros.a

C_INCLUDES += -Imicro_ros_stm32cubemx_utils/microros_static_library/libmicroros/microros_include


# Add micro-ROS utils

C_SOURCES += micro_ros_stm32cubemx_utils/extra_sources/custom_memory_manager.c

C_SOURCES += micro_ros_stm32cubemx_utils/extra_sources/microros_allocators.c

C_SOURCES += micro_ros_stm32cubemx_utils/extra_sources/microros_time.c


# Set custom transport implementation

C_SOURCES += micro_ros_stm32cubemx_utils/extra_sources/microros_transports/dma_transport.c


print_cflags:

@echo $(CFLAGS)

Step 3: Generate Micro-ROS Library

bash

# Pull Docker image and generate library

docker pull microros/micro_ros_static_library_builder: humble


# Run Docker container (from project root)

docker run --rm -v $(pwd):/project \

  --env MICROROS_LIBRARY_FOLDER=micro_ros_stm32cubemx_utils/microros_static_library \

  microros/micro_ros_static_library_builder:humble

Implementing Micro-ROS Application

Basic Publisher Example

Step 1: Modify main.c Replace the contents of your main.c with a micro-ROS publisher implementation:

c

#include "main.h"

#include "cmsis_os.h"


// micro-ROS includes

#include <rcl/rcl.h>

#include <rcl/error_handling.h>

#include <rclc/rclc.h>

#include <rclc/executor.h>

#include <rmw_microros/rmw_microros.h>

#include <std_msgs/msg/int32.h>


// Transport functions

bool cubemx_transport_open(struct uxrCustomTransport * transport);

bool cubemx_transport_close(struct uxrCustomTransport * transport);

size_t cubemx_transport_write(struct uxrCustomTransport* transport, 

                              const uint8_t * buf, size_t len, uint8_t * err);

size_t cubemx_transport_read(struct uxrCustomTransport* transport, 

                             uint8_t* buf, size_t len, int timeout, uint8_t* err);


// Memory management

void * microros_allocate(size_t size, void * state);

void microros_deallocate(void * pointer, void * state);

void * microros_reallocate(void * pointer, size_t size, void * state);

void * microros_zero_allocate(size_t number_of_elements, size_t size_of_element, void * state);


// Global variables

rcl_publisher_t publisher;

std_msgs__msg__Int32 msg;

rcl_timer_t timer;

rcl_node_t node;

rcl_allocator_t allocator;

rclc_support_t support;

rclc_executor_t executor;


// Timer callback

void timer_callback(rcl_timer_t * timer, int64_t last_call_time)

{

  RCLC_UNUSED(last_call_time);

  if (timer != NULL) {

    rcl_ret_t ret = rcl_publish(&publisher, &msg, NULL);

    msg.data++;

  }

}


void StartDefaultTask(void *argument)

{

  // Custom transport setup

  rmw_uros_set_custom_transport(

    true,

    (void *) &huart2,  // Use your configured UART

    cubemx_transport_open,

    cubemx_transport_close,

    cubemx_transport_write,

    cubemx_transport_read);


  // Memory allocator setup

  rcl_allocator_t allocator = rcutils_get_zero_initialized_allocator();

  allocator.allocate = microros_allocate;

  allocator.deallocate = microros_deallocate;

  allocator.reallocate = microros_reallocate;

  allocator.zero_allocate = microros_zero_allocate;


  if (!rcutils_set_default_allocator(&allocator)) {

    printf("Error on default allocators (line %d)\n", __LINE__); 

  }


  // Initialize micro-ROS

  rclc_support_init(&support, 0, NULL, &allocator);


  // Create node

  rclc_node_init_default(&node, "micro_ros_stm32_node", "", &support);


  // Create publisher

  rclc_publisher_init_default(

    &publisher,

    &node,

    ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),

    "micro_ros_stm32_publisher");


  // Create timer

  rclc_timer_init_default(

    &timer,

    &support,

    RCL_MS_TO_NS(1000),  // 1 second

    timer_callback);


  // Create executor

  rclc_executor_init(&executor, &support.context, 1, &allocator);

  rclc_executor_add_timer(&executor, &timer);


  msg.data = 0;


  for(;;)

  {

    rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));

    osDelay(100);

  }

}

Publisher-Subscriber Example

Advanced Application with Both Publishing and Subscription:

c

// Additional includes for subscriber

#include <std_msgs/msg/string.h>


// Global variables for subscriber

rcl_subscription_t subscriber;

std_msgs__msg__String recv_msg;


// Subscription callback

void subscription_callback(const void * msgin)

{

  const std_msgs__msg__String * msg = (const std_msgs__msg__String *)msgin;

  printf("Received: %s\n", msg->data.data);

  

  // Toggle LED or act based on received message

  HAL_GPIO_TogglePin(GPIOD, GPIO_PIN_12);

}


// In StartDefaultTask function, add after publisher creation:

void StartDefaultTask(void *argument)

{

  // ... previous initialization code ...


  // Initialize message buffers

  recv_msg.data.data = malloc(100);

  recv_msg.data.size = 0;

  recv_msg.data.capacity = 100;


  // Create subscriber

  rclc_subscription_init_default(

    &subscriber,

    &node,

    ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),

    "micro_ros_stm32_subscriber");


  // Add subscriber to executor

  rclc_executor_init(&executor, &support.context, 2, &allocator);

  rclc_executor_add_timer(&executor, &timer);

  rclc_executor_add_subscription(&executor, &subscriber, &recv_msg, 

                                 &subscription_callback, ON_NEW_DATA);


  // ... rest of the code ...

}

Building and Testing

Compilation Process

Step 1: Build the Project

bash

# In your STM32 project directory

make clean

make -j$(nproc)

Step 2: Flash the Firmware. Use ST-Link, JTAG, or your preferred flashing method:

bash

# Using OpenOCD (example)

openocd -f interface/stlink-v2.cfg -f target/stm32f4x.cfg \

  -c "program build/your_project.elf verify reset exit"

Running the Micro-ROS Agent

Step 1: Start the Agent

bash

# Source micro-ROS environment

source microros_ws/install/local_setup.bash


# Run agent (adjust device name as needed)

ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyACM0 -b 115200 -v6

Step 2: Verify Communication In another terminal:

bash

# List available topics

ros2 topic list


# Echo messages from STM32

ros2 topic echo /micro_ros_stm32_publisher


# Publish to STM32 (if using subscriber example)

ros2 topic pub /micro_ros_stm32_subscriber std_msgs/msg/String \

  "{data: 'Hello STM32'}"

Advanced Configuration Options

Memory Optimization

Customize Memory Usage: Create a colcon.meta file in your project:

json

{

    "names": {

        "rmw_microxrcedds": {

            "cmake-args": [

                "-DRMW_UXRCE_MAX_NODES=1",

                "-DRMW_UXRCE_MAX_PUBLISHERS=2",

                "-DRMW_UXRCE_MAX_SUBSCRIPTIONS=2",

                "-DRMW_UXRCE_MAX_SERVICES=1",

                "-DRMW_UXRCE_MAX_CLIENTS=1",

                "-DRMW_UXRCE_MAX_HISTORY=4"

            ]

        }

    }

}

Alternative Transport Methods

USB Transport: Enable USB CDC in STM32CubeMX and modify transport configuration:

c

// Use USB instead of UART

rmw_uros_set_custom_transport(

    true,

    NULL// USB doesn't need a handle

    cubemx_transport_open,

    cubemx_transport_close,

    cubemx_transport_write,

    cubemx_transport_read);

Ethernet UDP Transport: For boards with Ethernet capability:

c

// Configure for UDP transport

rmw_uros_set_custom_transport(

    false,  // UDP mode

    NULL,

    cubemx_transport_open,

    cubemx_transport_close,

    cubemx_transport_write,

    cubemx_transport_read);

Troubleshooting Common Issues

Compilation Problems

Missing Functions Error: If you encounter undefined _getpid or _kill errors, create a syscalls.c file:

c

#include <sys/stat.h>

#include <stdlib.h>

#include <errno.h>

#include <stdio.h>

#include <signal.h>

#include <time.h>

#include <sys/time.h>

#include <sys/times.h>


int _getpid(void) {

    return 1;

}


int _kill(int pid, int sig) {

    errno = EINVAL;

    return -1;

}


void _exit(int status) {

    _kill(status, -1);

    while (1) {}

}

Runtime Issues

Agent Connection Problems:

  • Verify UART configuration matches agent settings

  • Check cable connections and device permissions

  • Ensure consistent baud rates (115200)

  • Confirm STM32 is not stuck in error handlers

Memory Issues:

  • Increase FreeRTOS heap size in CubeMX

  • Reduce the maximum entities in colcon.meta

  • Monitor stack usage in FreeRTOS tasks

  • Use static memory allocation when possible

Performance Optimization

Communication Efficiency:

  • Use DMA for UART transfers

  • Implement circular buffers for high-frequency data

  • Optimize message sizes and publication rates

  • Consider using custom message types for specific applications

Real-World Applications

Sensor Data Publishing

Create a sensor node that publishes IMU data:

c

#include <sensor_msgs/msg/imu.h>


sensor_msgs__msg__Imu imu_msg;


void imu_timer_callback(rcl_timer_t * timer, int64_t last_call_time)

{

    // Read IMU sensor data

    float accel_x, accel_y, accel_z;

    float gyro_x, gyro_y, gyro_z;

    

    // Read_IMU_Data(&accel_x, &accel_y, &accel_z, &gyro_x, &gyro_y, &gyro_z);

    

    // Populate message

    imu_msg.linear_acceleration.x = accel_x;

    imu_msg.linear_acceleration.y = accel_y;

    imu_msg.linear_acceleration.z = accel_z;

    imu_msg.angular_velocity.x = gyro_x;

    imu_msg.angular_velocity.y = gyro_y;

    imu_msg.angular_velocity.z = gyro_z;

    

    // Publish

    rcl_publish(&imu_publisher, &imu_msg, NULL);

}

Motor Control Subscriber

Implement velocity command subscriber for robot control:

c

#include <geometry_msgs/msg/twist.h>


void cmd_vel_callback(const void * msgin)

{

    const geometry_msgs__msg__Twist * msg = (const geometry_msgs__msg__Twist *)msgin;

    

    float linear_x = msg->linear.x;

    float angular_z = msg->angular.z;

    

    // Convert to motor commands

    float left_speed = linear_x - angular_z * wheel_base / 2.0;

    float right_speed = linear_x + angular_z * wheel_base / 2.0;

    

    // Set motor speeds

    Set_Motor_Speed(left_speed, right_speed);

}

Conclusion

Micro-ROS on STM32 microcontrollers bridges the gap between embedded control systems and high-level robotics frameworks, enabling direct ROS 2 integration without additional computing overhead. This approach provides real-time performance, reduces system complexity, and enables cost-effective robotic solutions.

The combination of STM32's real-time capabilities with ROS 2's ecosystem creates powerful opportunities for distributed robotics applications, from simple sensor nodes to complex control systems. Success depends on proper memory management, efficient communication protocols, and understanding the constraints of microcontroller-based development.

Whether building sensor networks, motor controllers, or custom robotic devices, micro-ROS empowers STM32 microcontrollers to participate as full citizens in the ROS 2 ecosystem while maintaining the deterministic behavior required for embedded applications.

Frequently Asked Questions

1. What are the minimum hardware requirements for micro-ROS on STM32?

Micro-ROS requires at least 32KB RAM and 256KB Flash, though 64KB+ RAM is recommended. ARM Cortex-M4 or higher processors work best. Most modern STM32 development boards, like STM32F407 Discovery or Nucleo series, meet these requirements.

2. Can I use micro-ROS without FreeRTOS?

Yes, micro-ROS supports bare-metal implementations, but FreeRTOS is recommended for complex applications requiring multiple concurrent tasks. The RTOS provides better resource management and timing control for ROS 2 operations.

3. How do I handle network connectivity for remote robots?

Use WiFi-enabled STM32 boards or add external communication modules. Micro-ROS supports various transport methods, including Ethernet UDP, which can work over WiFi bridges. For remote operations, consider using ROS 2 networking features like DDS discovery.

4. What's the maximum message rate I can achieve?

Message rates depend on transport method, message size, and MCU performance. UART typically handles 10-100 Hz effectively, while USB and Ethernet can support higher rates. Real-world rates of 50-200 Hz are standard for sensor data.

5. How do I debug micro-ROS applications on STM32?

Use printf statements routed through UART for basic debugging. STM32CubeIDE provides full debugging with breakpoints—the micro-ROS agent's verbose mode (-v6) helps diagnose communication issues. Monitor FreeRTOS task stacks to detect memory problems.

Post a comment