Cross-RTOS Support in One Platform
How Hoomanely Leverages RTOS Abstraction to Build Unified Firmware Across Bare-Metal and FreeRTOS
Introduction
In modern embedded engineering, product families rarely run on a single RTOS. A hardware platform may ship as a bare-metal variant for simple, resource-constrained nodes and a FreeRTOS-based SKU for feature-rich devices, each with unique constraints, scheduling guarantees, and memory layouts. Traditionally, supporting multiple RTOSes forces engineering teams to maintain separate repositories, linker scripts, build configurations, and debugging workflows.
At Hoomanely, where we design highly modular IoT pet-care devices across diverse MCU platforms, this fragmentation was unacceptable.
We needed a cross-RTOS firmware architecture that unifies application logic while accommodating each RTOS's distinct memory model, interrupt behavior, and scheduling semantics.
This article explains how we built that system, enabling our platform to support Bare-Metal and FreeRTOS using shared interfaces with RTOS-specific linker scripts, heap strategies, and startup pipelines.
Hoomanely Context
Hoomanely builds modular IoT systems (sensor nodes, feeding bowls, cameras, gateways) using a universal System-on-Module (SoM) architecture. Different subsystems have different:
- Real-time requirements
- Power budgets
- Certification constraints
That naturally pushes us toward different RTOS choices across the product line.
A cross-RTOS firmware platform allows us to:
- Reuse 70 to 90 percent of the codebase across devices
- Reduce integration errors between SoMs
- Accelerate validation on new MCU families
- Maintain a consistent recovery pipeline across RTOSes
Cross-RTOS support is not a nice-to-have here; it is a core platform capability.
The Problem: One Hardware, Multiple RTOS Requirements
The recurring dilemma for embedded teams is:
"We want code reuse, but each RTOS forces different linker scripts, memory layouts, init sequences, and heap behavior."
RTOS differences are fundamental, not cosmetic:
Bare-Metal
- Direct MCU control
- No scheduler
- No dynamic memory unless manually implemented
- Deterministic but limited scalability
- Suitable for simple, low-power nodes
FreeRTOS
- Preemptive (or optionally cooperative) priority-based scheduler
- Multiple heap implementations (heap_1 to heap_5)
- Requires FromISR-safe APIs for interrupt contexts
- Built-in timers, queues, semaphores, mutexes
- Better for complex, multi-tasking applications
Supporting both in a single repo without turning into two partial forks is tricky. You cannot share the same:
- Startup code
- Linker script
- Heap model
- ISR wiring
Understanding RTOS Fundamentals
Before diving into our implementation, we establish what an RTOS provides and why it matters for embedded systems.
What is an RTOS?
A Real-Time Operating System (RTOS) is a specialized OS designed for embedded systems with timing constraints. Unlike general-purpose operating systems (Linux, Windows), an RTOS focuses on:
- Deterministic behavior: Predictable response times
- Priority-based scheduling: High-priority tasks preempt lower-priority ones
- Minimal overhead: Small memory footprint and fast context switching
- Real-time guarantees: Tasks meet their deadlines
Core RTOS Concepts
1. Tasks (Threads)
Independent execution units with their own stack and priority. In an RTOS, multiple tasks can run concurrently (the scheduler switches between them rapidly).
Benefits:
- Logical separation of functionality
- Independent timing requirements per task
- Simplified code structure (no complex state machines)
2. Scheduling
The RTOS scheduler decides which task runs based on:
- Priority: Higher-priority tasks run first
- Preemption: High-priority task can interrupt lower-priority ones
- Time-slicing: Equal-priority tasks share CPU time (optional)
3. Inter-Task Communication
Queues: Thread-safe message passing between tasks
Semaphores: Synchronization primitives for signaling events
Mutexes: Mutual exclusion for protecting shared resources
4. Memory Management
RTOSes provide heap management for:
- Task stacks
- Queues and semaphores
- Application buffers
- Dynamic data structures
Bare-Metal vs RTOS Trade-offs
| Aspect | Bare-Metal | RTOS |
|---|---|---|
| Complexity | Simple, single control flow | Multiple concurrent tasks |
| Memory | Minimal overhead | Kernel + per-task stacks |
| Determinism | Fully deterministic | Scheduling overhead (microseconds) |
| Code Structure | State machines | Natural task decomposition |
| Scalability | Limited | Excellent |
| Development Time | Fast for simple apps | Faster for complex apps |
When to use Bare-Metal:
- Ultra-low power requirements
- Simple, single-function devices
- Hard determinism requirements
- Memory-constrained MCUs (less than 16KB RAM)
When to use RTOS:
- Multiple concurrent operations
- Complex timing requirements
- Need for synchronization primitives
- Scalable architecture
Why FreeRTOS?
We chose FreeRTOS as our RTOS solution for several compelling reasons:
1. Industry Standard
- Used in billions of devices worldwide
- Extensive hardware support (ARM Cortex-M, RISC-V, x86, Xtensa)
- Large community and proven stability
2. Open Source and Free
- MIT License: No royalties or licensing fees
- Full source code access
- Active development and maintenance
3. Rich Feature Set
- Preemptive, priority-based scheduling
- Queues, semaphores, mutexes
- Software timers
- Event groups
- Task notifications (lightweight signaling)
4. Small Footprint
- Kernel: approximately 9KB code, 500 bytes RAM (minimal config)
- Scales from Cortex-M0+ to Cortex-A cores
- Configurable features (disable what you don't need)
5. Safety and Certification
- SAFERTOS: IEC 61508 (SIL 3) certified variant available
- Used in automotive, medical, industrial applications
- Mature, well-tested codebase
6. Flexible Memory Management
FreeRTOS provides five heap implementations:
| Heap | Characteristics | Use Case |
|---|---|---|
| heap_1 | Allocate only, no free | Static allocation pattern |
| heap_2 | Simple free, no coalescing | Fast, deterministic |
| heap_3 | Wraps malloc/free | Standard library integration |
| heap_4 | Coalescing, best-fit | General purpose (our choice) |
| heap_5 | Multi-region support | Fragmented memory maps |
How FreeRTOS Works: Core Mechanisms
Task Creation and Management
FreeRTOS tasks are functions that run independently:
void sensor_task(void *params)
{
/* Task initialization */
init_sensor();
/* Task loop */
while (1) {
uint32_t sensor_data = read_sensor();
process_data(sensor_data);
/* Yield CPU for 100ms */
vTaskDelay(pdMS_TO_TICKS(100));
}
}
/* Create task with 256-word stack, priority 2 */
xTaskCreate(
sensor_task, /* Task function */
"Sensor", /* Task name (debugging) */
256, /* Stack size (words) */
NULL, /* Parameters */
2, /* Priority */
NULL /* Task handle (optional) */
);
Task States:
- Running: Currently executing on CPU
- Ready: Can run, waiting for scheduler
- Blocked: Waiting for event/timeout
- Suspended: Manually paused
Scheduling Algorithm
FreeRTOS uses fixed-priority preemptive scheduling:
- Highest-priority ready task runs
- Equal-priority tasks share CPU (time-slicing if enabled)
- Task yields or blocks, scheduler picks next task
- Higher-priority task becomes ready, immediately preempts
/* Priority levels (0 = lowest, configMAX_PRIORITIES-1 = highest) */
xTaskCreate(idle_task, "Idle", 128, NULL, 0, NULL); /* Lowest */
xTaskCreate(sensor_task, "Sensor", 256, NULL, 2, NULL); /* Medium */
xTaskCreate(control_task, "Ctrl", 512, NULL, 5, NULL); /* High */
Inter-Task Communication: Queues
Queues provide thread-safe message passing:
/* Create queue: 10 items, each sizeof(sensor_reading_t) */
QueueHandle_t sensor_queue = xQueueCreate(10, sizeof(sensor_reading_t));
/* Producer task */
void sensor_task(void *params)
{
sensor_reading_t reading;
while (1) {
reading = read_sensor();
/* Send to queue, block max 100ms if full */
if (xQueueSend(sensor_queue, &reading, pdMS_TO_TICKS(100)) != pdPASS) {
/* Queue full, handle error */
}
vTaskDelay(pdMS_TO_TICKS(50));
}
}
/* Consumer task */
void processing_task(void *params)
{
sensor_reading_t reading;
while (1) {
/* Block until data available */
if (xQueueReceive(sensor_queue, &reading, portMAX_DELAY) == pdPASS) {
process_reading(&reading);
}
}
}
Queue Benefits:
- Thread-safe without manual locking
- Blocking semantics (tasks sleep when empty/full)
- Multiple readers/writers supported
- ISR-safe variants available
Synchronization: Semaphores and Mutexes
Binary Semaphore (signaling):
SemaphoreHandle_t data_ready_sem = xSemaphoreCreateBinary();
/* ISR signals data ready */
void UART_IRQHandler(void)
{
BaseType_t woken = pdFALSE;
/* Handle interrupt... */
xSemaphoreGiveFromISR(data_ready_sem, &woken);
portYIELD_FROM_ISR(woken);
}
/* Task waits for data */
void uart_task(void *params)
{
while (1) {
xSemaphoreTake(data_ready_sem, portMAX_DELAY);
process_uart_data();
}
}
Mutex (resource protection):
SemaphoreHandle_t spi_mutex = xSemaphoreCreateMutex();
void sensor_task(void *params)
{
while (1) {
xSemaphoreTake(spi_mutex, portMAX_DELAY);
/* Exclusive SPI access */
spi_transfer(sensor_data);
xSemaphoreGive(spi_mutex);
vTaskDelay(pdMS_TO_TICKS(100));
}
}
Mutex features:
- Priority inheritance (prevents priority inversion)
- Recursive locking support
- Cannot be used from ISRs
Software Timers
FreeRTOS timers run callbacks without dedicated tasks:
TimerHandle_t watchdog_timer;
void watchdog_callback(TimerHandle_t timer)
{
/* Check system health */
if (!system_healthy()) {
trigger_recovery();
}
}
/* Create 1-second periodic timer */
watchdog_timer = xTimerCreate(
"Watchdog", /* Name */
pdMS_TO_TICKS(1000), /* Period */
pdTRUE, /* Auto-reload */
NULL, /* Timer ID */
watchdog_callback /* Callback */
);
xTimerStart(watchdog_timer, 0);
FreeRTOS Memory Management: Why heap_4
FreeRTOS provides five heap implementations. We standardized on heap_4 for most applications.
heap_4 Characteristics
Algorithm:
- Best-fit allocation
- Coalesces adjacent free blocks
- Maintains free block list
Allocation:
void *pvPortMalloc(size_t xWantedSize)
{
/* Searches free list for best-fit block */
/* Splits block if larger than needed */
/* Returns pointer or NULL if insufficient memory */
}
Deallocation:
void vPortFree(void *pv)
{
/* Returns block to free list */
/* Merges with adjacent free blocks (coalescing) */
/* Reduces fragmentation over time */
}
Why heap_4 for Hoomanely?
| Criterion | heap_4 Performance |
|---|---|
| Fragmentation Control | Good (coalescing) |
| Allocation Speed | O(n) worst-case (acceptable for our use) |
| Determinism | Not hard real-time (but predictable bounds) |
| Memory Efficiency | Excellent |
| Simplicity | Single memory region |
When we use alternatives:
- heap_1: Boot-time allocations only (no free needed)
- heap_2: When strict determinism required, infrequent frees
- heap_5: Multi-region memory maps (e.g., internal + external RAM)
Configuring heap_4
In FreeRTOSConfig.h:
#define configTOTAL_HEAP_SIZE ((size_t)(32 * 1024)) /* 32KB heap */
#define configUSE_MALLOC_FAILED_HOOK 1 /* Detect OOM */
Linker script defines heap region:
.heap (NOLOAD) : {
__heap_start__ = .;
. = . + 32K;
__heap_end__ = .;
} > SRAM
FreeRTOS uses these symbols internally:
uint8_t ucHeap[configTOTAL_HEAP_SIZE];
Interrupt Handling in FreeRTOS
FreeRTOS has strict rules for ISR integration on ARM Cortex-M.
Interrupt Priority Levels
ARM Cortex-M: Lower number = higher priority
Priority 0 (Highest, most urgent)
Priority 1
Priority 2
...
Priority 15 (Lowest)
FreeRTOS Priority Configuration
In FreeRTOSConfig.h:
/* Cortex-M typically has 3-8 priority bits */
#define configPRIO_BITS 4 /* 16 priority levels (0-15) */
/* Highest ISR priority that can call FreeRTOS APIs */
#define configMAX_SYSCALL_INTERRUPT_PRIORITY (5 << (8 - configPRIO_BITS))
/* Kernel interrupt priority (lowest) */
#define configKERNEL_INTERRUPT_PRIORITY (15 << (8 - configPRIO_BITS))
ISR Priority Rules
Critical ISRs (Priority 0 through 4):
- Highest priority
- Cannot call FreeRTOS APIs
- Minimal latency
- Use case: Time-critical protocols, safety systems
void CriticalTimer_IRQHandler(void) /* Priority 3 */
{
/* Fast, direct hardware access only */
/* NO FreeRTOS calls allowed */
GPIO_SET(EMERGENCY_PIN);
clear_interrupt_flag();
}
RTOS-Aware ISRs (Priority 5 through 15):
- Can call FromISR APIs
- Slightly higher latency (scheduler overhead)
- Use case: Most peripherals
void UART_IRQHandler(void) /* Priority 6 */
{
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
uint8_t data = UART->DR;
/* Post to queue from ISR */
xQueueSendFromISR(uart_queue, &data, &xHigherPriorityTaskWoken);
/* Trigger context switch if higher-priority task woken */
portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
}
FromISR API Variants
FreeRTOS provides ISR-safe versions of APIs:
| Task API | ISR API | Notes |
|---|---|---|
| xQueueSend() | xQueueSendFromISR() | No blocking |
| xSemaphoreGive() | xSemaphoreGiveFromISR() | Binary/counting only |
| xTaskNotify() | xTaskNotifyFromISR() | Lightweight |
| vTaskDelay() | N/A | Cannot block in ISR |
| Mutex | N/A | No priority inheritance in ISR |
Key Differences:
- No timeout parameter (ISRs cannot block)
- Return xHigherPriorityTaskWoken flag
- Must call portYIELD_FROM_ISR() at end
Deferred Interrupt Processing Pattern
For complex ISR processing, use deferred task:
TaskHandle_t processing_task_handle;
/* High-priority ISR */
void ADC_IRQHandler(void) /* Priority 5 */
{
BaseType_t woken = pdFALSE;
/* Minimal work: read data */
uint16_t adc_value = ADC->DR;
/* Wake processing task */
xTaskNotifyFromISR(processing_task_handle, adc_value,
eSetValueWithOverwrite, &woken);
portYIELD_FROM_ISR(woken);
}
/* Task handles complex processing */
void adc_processing_task(void *params)
{
uint32_t adc_value;
while (1) {
/* Block until ISR notifies */
xTaskNotifyWait(0, 0, &adc_value, portMAX_DELAY);
/* Complex processing here */
float voltage = adc_to_voltage(adc_value);
apply_filtering(voltage);
update_control_loop(voltage);
}
}
Benefits:
- ISR stays fast and deterministic
- Complex work happens in task context
- Can use blocking APIs, mutexes, delays
Approach: Unified Platform with Per-RTOS Components
Our guiding principle:
"Application logic must be RTOS-agnostic."
Shared, RTOS-Independent Components
These live once, used everywhere:
- Drivers
- Hardware Abstraction Layer (HAL)
- Board configuration
- Peripheral discovery and device registry
- Messaging framework (events, queues, notifications)
- Telemetry and logging
RTOS-Specific Components
RTOS-specific code lives under:
/rtos/baremetal/
/rtos/freertos/
Each contains:
- Startup and reset handlers
- Linker scripts
- Memory and heap layout
- Scheduler glue and task bootstrap
- ISR routing and interrupt priority setup
- Error and recovery handling
The common firmware layer never reaches into RTOS internals directly.
System Architecture Overview
The architecture separates RTOS-specific implementation from application logic:

RTOS-Independent Interfaces
System API
We keep the system-level API narrow and explicit:
typedef struct {
void (*init)(void);
void (*delay_ms)(uint32_t ms);
uint32_t (*uptime_ms)(void);
} system_api_t;
extern const system_api_t system_api;
Implementation Mapping:
Bare-Metal:
static void bm_delay_ms(uint32_t ms)
{
uint32_t start = systick_counter;
while ((systick_counter - start) < ms) {
/* Busy wait */
}
}
static uint32_t bm_uptime_ms(void)
{
return systick_counter;
}
const system_api_t system_api = {
.init = bm_init,
.delay_ms = bm_delay_ms,
.uptime_ms = bm_uptime_ms
};
FreeRTOS:
static void freertos_delay_ms(uint32_t ms)
{
vTaskDelay(pdMS_TO_TICKS(ms));
}
static uint32_t freertos_uptime_ms(void)
{
return xTaskGetTickCount() * portTICK_PERIOD_MS;
}
const system_api_t system_api = {
.init = freertos_init,
.delay_ms = freertos_delay_ms,
.uptime_ms = freertos_uptime_ms
};
Event API (with ISR variants)
For events and queues, we define both normal and ISR-safe variants:
typedef struct {
bool (*post_event)(const event_t *ev);
bool (*post_event_from_isr)(const event_t *ev, bool *woken);
} event_api_t;
extern const event_api_t event_api;
FreeRTOS Implementation:
static bool freertos_post_event(const event_t *ev)
{
return xQueueSend(event_queue, ev, pdMS_TO_TICKS(100)) == pdPASS;
}
static bool freertos_post_event_from_isr(const event_t *ev, bool *woken)
{
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
bool result = xQueueSendFromISR(event_queue, ev,
&xHigherPriorityTaskWoken) == pdPASS;
if (woken) {
*woken = (xHigherPriorityTaskWoken == pdTRUE);
}
return result;
}
const event_api_t event_api = {
.post_event = freertos_post_event,
.post_event_from_isr = freertos_post_event_from_isr
};
Bare-Metal Implementation:
static bool baremetal_post_event(const event_t *ev)
{
/* Simple ring buffer */
uint32_t next = (event_write_idx + 1) % EVENT_QUEUE_SIZE;
if (next == event_read_idx) {
return false; /* Queue full */
}
event_queue[event_write_idx] = *ev;
event_write_idx = next;
return true;
}
static bool baremetal_post_event_from_isr(const event_t *ev, bool *woken)
{
/* Disable interrupts for atomic operation */
uint32_t primask = __get_PRIMASK();
__disable_irq();
bool result = baremetal_post_event(ev);
__set_PRIMASK(primask);
if (woken) {
*woken = false; /* No scheduler in bare-metal */
}
return result;
}
const event_api_t event_api = {
.post_event = baremetal_post_event,
.post_event_from_isr = baremetal_post_event_from_isr
};
Compile-Time Selection
#if defined(USE_FREERTOS)
#include "freertos_backend.h"
#else
#include "baremetal_backend.h"
#endif
This keeps application code ignorant of which RTOS is actually in play:
/* Application code */
void sensor_handler(void)
{
event_t ev = {
.type = EVENT_SENSOR_DATA,
.data = read_sensor()
};
event_api.post_event(&ev);
system_api.delay_ms(100);
}
Per-RTOS Linker Scripts
Each RTOS requires different memory organization.
Bare-Metal Linker Script
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K
SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
}
__stack_size__ = 4K;
__heap_size__ = 16K;
SECTIONS
{
.isr_vector : {
KEEP(*(.isr_vector))
} > FLASH
.text : {
*(.text*)
*(.rodata*)
} > FLASH
.data : {
*(.data*)
} > SRAM AT > FLASH
.bss (NOLOAD) : {
*(.bss*)
*(COMMON)
} > SRAM
.heap (NOLOAD) : {
__heap_start__ = .;
. = . + __heap_size__;
__heap_end__ = .;
} > SRAM
.stack (NOLOAD) : {
. = . + __stack_size__;
__stack_top__ = .;
} > SRAM
}
FreeRTOS Linker Script
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K
SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
}
__heap_size__ = 32K; /* Larger for FreeRTOS tasks */
SECTIONS
{
.isr_vector : {
KEEP(*(.isr_vector))
} > FLASH
.text : {
*(.text*)
*(.rodata*)
} > FLASH
.data : {
*(.data*)
} > SRAM AT > FLASH
.bss (NOLOAD) : {
*(.bss*)
*(COMMON)
} > SRAM
/* FreeRTOS heap region */
.heap (NOLOAD) : {
__heap_start__ = .;
. = . + __heap_size__;
__heap_end__ = .;
} > SRAM
/* Main stack (used only before scheduler starts) */
.stack (NOLOAD) : {
. = ALIGN(8);
. = . + 2K;
__stack_top__ = .;
} > SRAM
}
Key Differences:
- FreeRTOS heap is larger (supports multiple task stacks)
- Main stack is smaller (only for startup, ISRs use PSP after scheduler starts)
- Heap symbols (heap_start, heap_end) feed into heap_4.c
Per-RTOS Heap Models
Bare-Metal Heap: Bump Allocator
We only use this for early boot and simple nodes:
#define BM_HEAP_SIZE 4096
static uint8_t bm_heap[BM_HEAP_SIZE];
static size_t bm_heap_used = 0;
void *bm_malloc(size_t sz)
{
if (sz == 0) return NULL;
/* Align to 4-byte boundary for ARM Cortex-M */
sz = (sz + 3) & ~3;
if (sz > (BM_HEAP_SIZE - bm_heap_used)) {
/* Out of memory */
return NULL;
}
void *ptr = &bm_heap[bm_heap_used];
bm_heap_used += sz;
return ptr;
}
void bm_free(void *ptr)
{
/* No-op: bump allocator doesn't support free */
(void)ptr;
}
Characteristics:
- Predictable: O(1) allocation
- No fragmentation
- No deallocation support
- Suitable for boot-time allocations
FreeRTOS heap_4
FreeRTOS heap_4 provides general-purpose dynamic memory:
Configuration (FreeRTOSConfig.h):
#define configTOTAL_HEAP_SIZE ((size_t)(32 * 1024))
#define configUSE_MALLOC_FAILED_HOOK 1
Malloc Failed Hook:
void vApplicationMallocFailedHook(void)
{
/* Log error */
log_error("Heap exhausted");
/* Attempt recovery or reset */
system_reset();
}
Usage in Application:
/* Allocate buffer */
uint8_t *buffer = pvPortMalloc(1024);
if (buffer == NULL) {
/* Handle allocation failure */
return ERROR_NO_MEMORY;
}
/* Use buffer */
memset(buffer, 0, 1024);
/* Free when done */
vPortFree(buffer);
Heap Statistics (optional):
size_t xPortGetFreeHeapSize(void);
size_t xPortGetMinimumEverFreeHeapSize(void);
Startup and Initialization
Bare-Metal Startup
/* Reset handler (startup_baremetal.s) */
void Reset_Handler(void)
{
/* Copy .data from flash to SRAM */
extern uint32_t _sdata, _edata, _sidata;
uint32_t *src = &_sidata;
uint32_t *dst = &_sdata;
while (dst < &_edata) {
*dst++ = *src++;
}
/* Zero .bss */
extern uint32_t _sbss, _ebss;
dst = &_sbss;
while (dst < &_ebss) {
*dst++ = 0;
}
/* Initialize system */
SystemInit();
/* Call main */
main();
/* Trap if main returns */
while (1);
}
Main function:
int main(void)
{
/* Hardware init */
clock_init();
gpio_init();
uart_init();
/* System API init */
system_api.init();
/* Application init */
app_init();
/* Main loop */
while (1) {
app_run();
}
}
FreeRTOS Startup
int main(void)
{
/* Hardware init (before scheduler) */
clock_init();
gpio_init();
uart_init();
/* System API init */
system_api.init();
/* Create FreeRTOS tasks */
xTaskCreate(sensor_task, "Sensor", 256, NULL, 2, NULL);
xTaskCreate(control_task, "Control", 512, NULL, 3, NULL);
xTaskCreate(telemetry_task, "Telemetry", 256, NULL, 1, NULL);
/* Create queues/semaphores */
sensor_queue = xQueueCreate(10, sizeof(sensor_reading_t));
spi_mutex = xSemaphoreCreateMutex();
/* Application init */
app_init();
/* Start scheduler (does not return) */
vTaskStartScheduler();
/* Should never reach here */
while (1);
}
Task Functions:
void sensor_task(void *params)
{
TickType_t xLastWakeTime = xTaskGetTickCount();
while (1) {
/* Read sensor */
sensor_reading_t reading = read_sensor();
/* Post to queue */
xQueueSend(sensor_queue, &reading, pdMS_TO_TICKS(10));
/* Delay until next period (100ms) */
vTaskDelayUntil(&xLastWakeTime, pdMS_TO_TICKS(100));
}
}
void control_task(void *params)
{
sensor_reading_t reading;
while (1) {
/* Wait for sensor data */
if (xQueueReceive(sensor_queue, &reading, portMAX_DELAY) == pdPASS) {
/* Process and control */
process_control_loop(&reading);
}
}
}
Interrupt Routing
Bare-Metal ISR
void UART_IRQHandler(void)
{
/* Direct handling */
if (UART->SR & UART_SR_RXNE) {
uint8_t data = UART->DR;
uart_rx_buffer[uart_rx_head++] = data;
uart_rx_head %= UART_RX_BUFFER_SIZE;
}
}
FreeRTOS ISR
void UART_IRQHandler(void)
{
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
if (UART->SR & UART_SR_RXNE) {
uint8_t data = UART->DR;
/* Post to queue from ISR */
xQueueSendFromISR(uart_rx_queue, &data, &xHigherPriorityTaskWoken);
}
/* Yield if necessary */
portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
}
Using abstraction layer:
void UART_IRQHandler(void)
{
bool woken = false;
if (UART->SR & UART_SR_RXNE) {
event_t ev = {
.type = EVENT_UART_RX,
.data = UART->DR
};
/* Works for both bare-metal and FreeRTOS */
event_api.post_event_from_isr(&ev, &woken);
}
/* FreeRTOS will yield if woken=true, bare-metal ignores */
if (woken) {
/* Context switch will occur after ISR */
}
}
Build System Integration
The build system selects RTOS backend, startup file, and linker script.
CMake Example
set(RTOS_IMPL "FREERTOS" CACHE STRING "RTOS implementation")
# Common sources
set(COMMON_SOURCES
src/main.c
src/app.c
src/drivers/gpio.c
src/drivers/spi.c
src/drivers/uart.c
src/hal/hal.c
)
# RTOS-specific configuration
if(RTOS_IMPL STREQUAL "FREERTOS")
add_definitions(-DUSE_FREERTOS)
set(RTOS_SOURCES
rtos/freertos/rtos_port.c
rtos/freertos/heap_4.c
rtos/freertos/port.c
rtos/freertos/queue.c
rtos/freertos/tasks.c
rtos/freertos/timers.c
)
set(STARTUP_ASM rtos/freertos/startup_stm32.s)
set(LINKER_SCRIPT "${CMAKE_CURRENT_SOURCE_DIR}/rtos/freertos/linker_stm32.ld")
else() # Bare-metal
add_definitions(-DUSE_BAREMETAL)
set(RTOS_SOURCES
rtos/baremetal/rtos_port.c
)
set(STARTUP_ASM rtos/baremetal/startup_bm.s)
set(LINKER_SCRIPT "${CMAKE_CURRENT_SOURCE_DIR}/rtos/baremetal/linker_bm.ld")
endif()
# Create firmware target
add_executable(firmware
${COMMON_SOURCES}
${RTOS_SOURCES}
${STARTUP_ASM}
)
# Set linker script
target_link_options(firmware PRIVATE
"-T${LINKER_SCRIPT}"
-Wl,-Map=firmware.map
)
# Include paths
target_include_directories(firmware PRIVATE
src/
rtos/${RTOS_IMPL}/include/
)
Makefile Example
RTOS ?= FREERTOS
# Common sources
COMMON_SRC = \
src/main.c \
src/app.c \
src/drivers/gpio.c \
src/drivers/uart.c
# RTOS-specific
ifeq ($(RTOS),FREERTOS)
DEFINES += -DUSE_FREERTOS
RTOS_SRC = \
rtos/freertos/rtos_port.c \
rtos/freertos/heap_4.c \
rtos/freertos/tasks.c
STARTUP = rtos/freertos/startup_stm32.s
LDSCRIPT = rtos/freertos/linker_stm32.ld
else
DEFINES += -DUSE_BAREMETAL
RTOS_SRC = rtos/baremetal/rtos_port.c
STARTUP = rtos/baremetal/startup_bm.s
LDSCRIPT = rtos/baremetal/linker_bm.ld
endif
SOURCES = $(COMMON_SRC) $(RTOS_SRC) $(STARTUP)
firmware.elf: $(SOURCES)
$(CC) $(CFLAGS) $(DEFINES) -T$(LDSCRIPT) -o $@ $^
FreeRTOSConfig.h: Production Settings
We standardize FreeRTOSConfig.h across boards:
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
/* Scheduler configuration */
#define configUSE_PREEMPTION 1
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
#define configUSE_TICKLESS_IDLE 0
#define configCPU_CLOCK_HZ SystemCoreClock
#define configTICK_RATE_HZ 1000
#define configMAX_PRIORITIES 8
#define configMINIMAL_STACK_SIZE 128
#define configMAX_TASK_NAME_LEN 16
/* Memory allocation */
#define configTOTAL_HEAP_SIZE ((size_t)(32 * 1024))
#define configUSE_MALLOC_FAILED_HOOK 1
/* Safety features */
#define configCHECK_FOR_STACK_OVERFLOW 2
#define configQUEUE_REGISTRY_SIZE 8
/* Interrupt priorities */
#define configPRIO_BITS 4
#define configMAX_SYSCALL_INTERRUPT_PRIORITY (5 << (8 - configPRIO_BITS))
#define configKERNEL_INTERRUPT_PRIORITY (15 << (8 - configPRIO_BITS))
/* Optional features */
#define configUSE_MUTEXES 1
#define configUSE_RECURSIVE_MUTEXES 1
#define configUSE_COUNTING_SEMAPHORES 1
#define configUSE_QUEUE_SETS 0
#define configUSE_TIMERS 1
#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES - 1)
#define configTIMER_QUEUE_LENGTH 10
#define configTIMER_TASK_STACK_DEPTH 256
/* Debug assertions */
#define configASSERT(x) \
if ((x) == 0) { \
taskDISABLE_INTERRUPTS(); \
for(;;); \
}
/* Hook functions */
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
/* Co-routine configuration (rarely used) */
#define configUSE_CO_ROUTINES 0
/* Software timer definitions */
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_xTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_xTaskGetCurrentTaskHandle 1
#endif /* FREERTOS_CONFIG_H */
Key Production Settings:
- Stack Overflow Checking: configCHECK_FOR_STACK_OVERFLOW = 2 (method 2, more thorough)
- Malloc Failed Hook: Catches heap exhaustion
- configASSERT: Traps on assertion failures
- Interrupt Priorities: Properly segregated for RTOS-aware ISRs
Case Study: Adding New MCU to Platform
When adding a new MCU family (STM32, nRF52, ESP32-S3), we follow this sequence:
Step 1: Hardware Bring-Up
- Configure clock tree
- Initialize power rails
- Enable GPIO, UART for debug output
- Verify memory map
Step 2: Bare-Metal Boot
- Write minimal startup code (Reset_Handler)
- Configure vector table
- Implement SysTick for timing
- Validate with simple UART printf
void main(void)
{
clock_init();
uart_init();
printf("Bare-metal boot OK\r\n");
while (1) {
printf("Tick: %lu\r\n", systick_counter);
delay_ms(1000);
}
}
Step 3: FreeRTOS Integration
- Add FreeRTOS port files for architecture
- Create FreeRTOSConfig.h
- Configure interrupt priorities
- Test basic scheduler
void task1(void *params)
{
while (1) {
printf("Task 1\r\n");
vTaskDelay(pdMS_TO_TICKS(500));
}
}
void task2(void *params)
{
while (1) {
printf("Task 2\r\n");
vTaskDelay(pdMS_TO_TICKS(1000));
}
}
int main(void)
{
clock_init();
uart_init();
xTaskCreate(task1, "T1", 128, NULL, 1, NULL);
xTaskCreate(task2, "T2", 128, NULL, 1, NULL);
vTaskStartScheduler();
}
Step 4: Abstraction Layer Validation
- Implement system_api backend
- Implement event_api backend
- Run unified test suite
/* Same test runs on bare-metal and FreeRTOS */
void test_event_system(void)
{
event_t ev = {.type = EVENT_TEST, .data = 0x1234};
/* Should work regardless of RTOS */
assert(event_api.post_event(&ev) == true);
system_api.delay_ms(10);
/* Verify event received */
assert(last_event.type == EVENT_TEST);
assert(last_event.data == 0x1234);
}
Step 5: Platform Certification
- Run full application logic
- Stress test scheduler (FreeRTOS)
- Validate interrupt handling
- Test recovery paths
- Measure timing and determinism
Certification Criteria:
- All unit tests pass
- No stack overflows
- No heap exhaustion
- Timing requirements met
- Recovery works correctly
Results
1. Code Reuse
- 70 to 90 percent shared between bare-metal and FreeRTOS
- Single HAL/driver implementation
- Application logic unchanged
2. Faster Prototyping
- New MCU onboarding: 3 to 5 days (vs 2 to 3 weeks previously)
- Bare-metal first validates hardware quickly
- FreeRTOS adds multi-tasking without code rewrite
3. Consistent Behavior
- Same event handling across RTOSes
- Unified logging and telemetry
- Predictable recovery paths
4. Reduced Maintenance
- Single HAL to maintain
- No duplicated drivers
- Bug fixes apply to all platforms
5. Flexible Product Line
- Simple nodes: bare-metal (low power, low cost)
- Complex nodes: FreeRTOS (rich features, scalability)
- Same firmware architecture
Takeaways
- Real product lines require multiple RTOS approaches for different constraints
- FreeRTOS provides robust multi-tasking with minimal overhead
- Abstraction layers enable RTOS independence at application level
- Each RTOS needs dedicated linker script, heap model, and startup code
- Interrupt handling requires careful priority management in FreeRTOS
- Build system selects RTOS backend at compile time
- Result: Single codebase supporting bare-metal and FreeRTOS across multiple MCU families
Cross-RTOS support is not about supporting more operating systems for the sake of it. It is about building a platform that can scale from simple, power-constrained sensors to complex, feature-rich gateways without fragmenting the codebase. At Hoomanely, this architecture has enabled us to rapidly deploy across diverse hardware while maintaining code quality and reliability.
Understanding RTOS fundamentals and FreeRTOS specifically has been critical to our success. The principles outlined here (task decomposition, priority management, ISR handling, memory management) form the foundation of robust embedded systems.
For technical questions or collaboration, contact the Hoomanely engineering team.