La programación embebida con C++ combina la potencia del lenguaje C++ con las restricciones y particularidades de los sistemas embebidos.
Un sistema embebido es un sistema de computación diseñado para realizar una o unas pocas funciones dedicadas, frecuentemente en tiempo real.
Precaución: No todas las características de C++ son adecuadas para sistemas embebidos. Algunas pueden consumir demasiados recursos o ser impredecibles.
Característica | C++ Estándar | C++ Embedido |
---|---|---|
Memoria dinámica | Uso común de new/delete | Evitado o uso controlado |
Excepciones | Ampliamente usadas | Generalmente deshabilitadas |
STL | Uso completo | Uso selectivo (vector, array) |
RTTI | Disponible | Generalmente deshabilitado |
# Ejemplo de Makefile para ARM Cortex-M
CC = arm-none-eabi-g++
CFLAGS = -mcpu=cortex-m4 -mthumb -Os -fno-exceptions -fno-rtti
LDFLAGS = -T linker_script.ld -nostartfiles
SRCS = main.cpp drivers/gpio.cpp
OBJS = $(SRCS:.cpp=.o)
firmware.elf: $(OBJS)
$(CC) $(LDFLAGS) -o $@ $^
%.o: %.cpp
$(CC) $(CFLAGS) -c -o $@ $^
// Tipos enteros de tamaño fijo (cstdint)
#include <cstdint>
uint8_t byte = 0xFF; // Entero sin signo de 8 bits
int16_t value = -1024; // Entero con signo de 16 bits
uint32_t address = 0x20000000;
// Tipos para acceso a registros
volatile uint32_t* const reg = reinterpret_cast<uint32_t*>(0x40021000);
// Uso común en sistemas embebidos
if (status_reg & 0x01) {
// Bit 0 está activo
} else {
// Bit 0 está inactivo
}
// Bucles con tiempo crítico
for (uint32_t i = 0; i < 1000; ++i) {
// Operación con timing preciso
*timer_reg = i;
}
while (!(status_reg & READY_FLAG)) {
// Espera ocupada (busy-wait)
}
// Asignación estática (preferida en sistemas embebidos)
uint8_t buffer[1024]; // En la pila (stack)
// Asignación dinámica (usar con precaución)
void* dynamic_mem = malloc(256); // En el heap
if (dynamic_mem != nullptr) {
// Usar memoria
free(dynamic_mem); // No olvidar liberar!
}
// Alternativa mejor: pool de memoria estática
class MemoryPool {
static constexpr size_t POOL_SIZE = 1024;
static uint8_t pool[POOL_SIZE];
static size_t next_free;
public:
static void* allocate(size_t size) {
if (next_free + size > POOL_SIZE) return nullptr;
void* ptr = &pool[next_free];
next_free += size;
return ptr;
}
};
// Colocar variable en sección específica (depende de compilador)
__attribute__((section(".fast_mem"))) uint32_t high_speed_buffer[64];
// Variable en memoria no inicializada (bss)
static uint8_t zero_init_buffer[256];
// Variable constante en flash (solo lectura)
const uint32_t lookup_table[] = {0x00, 0x01, 0x02};
// Ejemplo para un puerto GPIO
struct GPIO_Type {
volatile uint32_t MODER; // Mode register
volatile uint32_t OTYPER; // Output type register
volatile uint32_t OSPEEDR; // Output speed register
volatile uint32_t PUPDR; // Pull-up/pull-down register
volatile uint32_t IDR; // Input data register
volatile uint32_t ODR; // Output data register
volatile uint32_t BSRR; // Bit set/reset register
volatile uint32_t LCKR; // Configuration lock register
volatile uint32_t AFR[2]; // Alternate function registers
};
#define GPIOA_BASE 0x40020000
#define GPIOA ((GPIO_Type*)GPIOA_BASE)
void configure_led() {
// Configurar pin 5 como salida
GPIOA->MODER &= ~(0b11 << (5 * 2)); // Clear bits
GPIOA->MODER |= (0b01 << (5 * 2)); // Output mode
// Configurar velocidad alta
GPIOA->OSPEEDR |= (0b11 << (5 * 2));
// Encender LED
GPIOA->BSRR = (1 << 5); // Set bit 5
}
template <typename T, uintptr_t Addr>
struct Register {
static constexpr uintptr_t address = Addr;
// Operador de asignación
void operator=(T value) {
*reinterpret_cast<volatile T*>(address) = value;
}
// Operador de conversión
operator T() const {
return *reinterpret_cast<volatile T*>(address);
}
// Operaciones bit a bit
void set_bits(T mask) {
*reinterpret_cast<volatile T*>(address) |= mask;
}
void clear_bits(T mask) {
*reinterpret_cast<volatile T*>(address) &= ~mask;
}
};
// Uso:
Register<uint32_t, 0x40021000> RCC_CR;
RCC_CR.set_bits(0x00000001); // Activar HSI
// Tabla de vectores de interrupción (Cortex-M)
extern "C" {
void Reset_Handler();
void NMI_Handler();
void HardFault_Handler();
// ... otros handlers
}
// Atributo para colocar en la sección correcta
__attribute__((section(".isr_vector")))
void (* const vector_table[])() = {
reinterpret_cast<void(*)()>(STACK_TOP), // Stack pointer
Reset_Handler,
NMI_Handler,
HardFault_Handler,
// ... resto de vectores
};
// Handler para TIM2 (Cortex-M)
extern "C" void TIM2_IRQHandler() {
// Verificar flag de interrupción
if (TIM2->SR & TIM_SR_UIF) {
// Limpiar flag
TIM2->SR &= ~TIM_SR_UIF;
// Procesar interrupción
static uint32_t counter = 0;
counter++;
// Toggle LED
GPIOA->ODR ^= (1 << 5);
}
}
template <typename T>
class InterruptHandler {
public:
using HandlerFunc = void (*)(T*);
static void register_handler(T* obj, HandlerFunc func) {
instance = obj;
handler = func;
}
static void handle_interrupt() {
if (handler && instance) {
handler(instance);
}
}
private:
static T* instance;
static HandlerFunc handler;
};
// Uso:
class Timer {
public:
void handle_interrupt() {
// Procesar interrupción
}
};
Timer my_timer;
InterruptHandler<Timer>::register_handler(&my_timer, &Timer::handle_interrupt);
class Gpio {
public:
enum class Port { A, B, C, D };
enum class Mode { Input, Output, Alternate, Analog };
enum class Pull { None, Up, Down };
enum class Speed { Low, Medium, High, VeryHigh };
Gpio(Port port, uint8_t pin) : port(port), pin(pin) {}
void init(Mode mode, Pull pull = Pull::None, Speed speed = Speed::Low) {
GPIO_Type* gpio = get_gpio_port(port);
// Configurar modo
gpio->MODER &= ~(0b11 << (pin * 2));
gpio->MODER |= (static_cast<uint32_t>(mode) << (pin * 2));
// Configurar pull-up/pull-down
gpio->PUPDR &= ~(0b11 << (pin * 2));
gpio->PUPDR |= (static_cast<uint32_t>(pull) << (pin * 2));
// Configurar velocidad
gpio->OSPEEDR &= ~(0b11 << (pin * 2));
gpio->OSPEEDR |= (static_cast<uint32_t>(speed) << (pin * 2));
}
void set() { get_gpio_port(port)->BSRR = (1 << pin); }
void clear() { get_gpio_port(port)->BSRR = (1 << (pin + 16)); }
void toggle() { get_gpio_port(port)->ODR ^= (1 << pin); }
bool read() { return (get_gpio_port(port)->IDR & (1 << pin)); }
private:
Port port;
uint8_t pin;
GPIO_Type* get_gpio_port(Port port) {
switch (port) {
case Port::A: return GPIOA;
case Port::B: return GPIOB;
case Port::C: return GPIOC;
case Port::D: return GPIOD;
default: return nullptr;
}
}
};
// Uso:
Gpio led(Gpio::Port::A, 5);
led.init(Gpio::Mode::Output);
led.set();
class Uart {
public:
Uart(USART_TypeDef* uart) : uart(uart) {}
void init(uint32_t baudrate) {
// Habilitar reloj para el periférico
if (uart == USART1) RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
else if (uart == USART2) RCC->APB1ENR |= RCC_APB1ENR_USART2EN;
// Configurar baudrate (simplificado)
uart->BRR = SystemCoreClock / baudrate;
// Habilitar UART
uart->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE;
}
void send(uint8_t data) {
while (!(uart->ISR & USART_ISR_TXE)); // Esperar buffer vacío
uart->TDR = data;
}
uint8_t receive() {
while (!(uart->ISR & USART_ISR_RXNE)); // Esperar dato recibido
return uart->RDR;
}
void send(const char* str) {
while (*str) {
send(*str++);
}
}
private:
USART_TypeDef* uart;
};
// Uso:
Uart uart1(USART1);
uart1.init(115200);
uart1.send("Hola mundo!\r\n");
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
// Cola para comunicación entre tareas
QueueHandle_t xQueue = xQueueCreate(10, sizeof(uint32_t));
// Tarea productora
void vProducerTask(void* pvParameters) {
uint32_t value = 0;
while (true) {
// Enviar valor a la cola
xQueueSend(xQueue, &value, portMAX_DELAY);
value++;
// Esperar 500ms
vTaskDelay(pdMS_TO_TICKS(500));
}
}
// Tarea consumidora
void vConsumerTask(void* pvParameters) {
uint32_t received_value;
while (true) {
// Recibir valor de la cola
if (xQueueReceive(xQueue, &received_value, portMAX_DELAY) == pdPASS) {
// Procesar valor
printf("Received: %lu\r\n", received_value);
}
}
}
int main() {
// Crear tareas
xTaskCreate(vProducerTask, "Producer", 128, NULL, 2, NULL);
xTaskCreate(vConsumerTask, "Consumer", 128, NULL, 1, NULL);
// Iniciar scheduler
vTaskStartScheduler();
// Nunca deberíamos llegar aquí
while (true);
}
constexpr
para cálculos en tiempo de compilaciónconstexpr uint32_t calculate_crc32_table_entry(uint32_t index) {
uint32_t value = index;
for (int i = 0; i < 8; ++i) {
value = (value & 1) ? (0xEDB88320 ^ (value >> 1)) : (value >> 1);
}
return value;
}
template <size_t... Indices>
constexpr auto generate_crc32_table(std::index_sequence<Indices...>) {
return std::array<uint32_t, sizeof...(Indices)>{
calculate_crc32_table_entry(Indices)...
};
}
constexpr auto crc32_table = generate_crc32_table(
std::make_index_sequence<256>{});
uint32_t compute_crc32(const uint8_t* data, size_t length) {
uint32_t crc = 0xFFFFFFFF;
for (size_t i = 0; i < length; ++i) {
uint8_t index = (crc ^ data[i]) & 0xFF;
crc = (crc >> 8) ^ crc32_table[index];
}
return crc ^ 0xFFFFFFFF;
}
class SystemClock {
public:
static SystemClock& instance() {
static SystemClock clock;
return clock;
}
void init(uint32_t freq) {
frequency = freq;
// Configurar hardware
}
uint32_t get_frequency() const { return frequency; }
private:
SystemClock() = default;
~SystemClock() = default;
uint32_t frequency = 0;
};
// Uso:
SystemClock::instance().init(16000000);
auto freq = SystemClock::instance().get_frequency();
class StateMachine {
public:
enum class State { Idle, Running, Error };
void process_event(Event event) {
switch (current_state) {
case State::Idle:
if (event == Event::Start) {
start_operation();
current_state = State::Running;
}
break;
case State::Running:
if (event == Event::Stop) {
stop_operation();
current_state = State::Idle;
} else if (event == Event::Error) {
handle_error();
current_state = State::Error;
}
break;
case State::Error:
if (event == Event::Reset) {
reset_system();
current_state = State::Idle;
}
break;
}
}
private:
State current_state = State::Idle;
void start_operation() { /* ... */ }
void stop_operation() { /* ... */ }
void handle_error() { /* ... */ }
void reset_system() { /* ... */ }
};
// Framework simple de pruebas
#define TEST(condition) \
do { \
if (!(condition)) { \
printf("Test failed at %s:%d: %s\r\n", __FILE__, __LINE__, #condition); \
return false; \
} \
} while (0)
bool test_gpio() {
Gpio pin(Gpio::Port::A, 0);
pin.init(Gpio::Mode::Output);
pin.set();
TEST(pin.read() == true);
pin.clear();
TEST(pin.read() == false);
pin.toggle();
TEST(pin.read() == true);
return true;
}
void run_tests() {
printf("Running tests...\r\n");
if (test_gpio()) {
printf("GPIO tests passed\r\n");
} else {
printf("GPIO tests failed\r\n");
}
// Más pruebas...
}
// Implementación básica de printf para sistemas embebidos
extern "C" {
int _write(int file, char *ptr, int len) {
// Implementación dependiente de la plataforma
// Ejemplo para UART:
for (int i = 0; i < len; i++) {
while (!(USART1->ISR & USART_ISR_TXE));
USART1->TDR = *ptr++;
}
return len;
}
}
// Uso:
printf("Valor del sensor: %d\r\n", sensor_value);
class PwmController {
public:
PwmController(TIM_TypeDef* timer, uint32_t channel)
: timer(timer), channel(channel) {}
void init(uint32_t frequency) {
// Configurar reloj para el timer
enable_timer_clock(timer);
// Configurar base de tiempo
timer->PSC = SystemCoreClock / (frequency * 1000) - 1;
timer->ARR = 1000 - 1; // Resolución de 1000 pasos
// Configurar canal PWM
switch (channel) {
case 1:
timer->CCMR1 |= TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1;
timer->CCER |= TIM_CCER_CC1E;
break;
// Canales 2-4 similares...
}
// Habilitar timer
timer->CR1 |= TIM_CR1_CEN;
}
void set_duty_cycle(float duty) {
duty = std::clamp(duty, 0.0f, 1.0f);
uint32_t compare_value = static_cast<uint32_t>(duty * 1000);
switch (channel) {
case 1: timer->CCR1 = compare_value; break;
case 2: timer->CCR2 = compare_value; break;
case 3: timer->CCR3 = compare_value; break;
case 4: timer->CCR4 = compare_value; break;
}
}
private:
TIM_TypeDef* timer;
uint32_t channel;
void enable_timer_clock(TIM_TypeDef* timer) {
if (timer == TIM1) RCC->APB2ENR |= RCC_APB2ENR_TIM1EN;
else if (timer == TIM2) RCC->APB1ENR |= RCC_APB1ENR_TIM2EN;
// Otros timers...
}
};
// Uso:
PwmController motor_pwm(TIM2, 1);
motor_pwm.init(1000); // 1 kHz
motor_pwm.set_duty_cycle(0.75f); // 75% duty cycle
class I2CSensor {
public:
I2CSensor(I2C_TypeDef* i2c, uint8_t address)
: i2c(i2c), address(address) {}
bool read_register(uint8_t reg, uint8_t* value, uint32_t timeout = 100) {
for (int attempt = 0; attempt < 3; ++attempt) {
if (try_read_register(reg, value, timeout)) {
return true;
}
delay_ms(10);
}
return false;
}
bool write_register(uint8_t reg, uint8_t value, uint32_t timeout = 100) {
for (int attempt = 0; attempt < 3; ++attempt) {
if (try_write_register(reg, value, timeout)) {
return true;
}
delay_ms(10);
}
return false;
}
private:
I2C_TypeDef* i2c;
uint8_t address;
bool try_read_register(uint8_t reg, uint8_t* value, uint32_t timeout) {
// Implementación de lectura I2C con timeout
// ...
}
bool try_write_register(uint8_t reg, uint8_t value, uint32_t timeout) {
// Implementación de escritura I2C con timeout
// ...
}
void delay_ms(uint32_t ms) {
// Implementación de delay
// ...
}
};
// Uso:
I2CSensor temp_sensor(I2C1, 0x48);
uint8_t temp_value;
if (temp_sensor.read_register(0x00, &temp_value)) {
printf("Temperature: %dC\r\n", temp_value);
} else {
printf("Sensor read failed\r\n");
}