Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/Ardupilot/ardupilot/llms.txt

Use this file to discover all available pages before exploring further.

The Hardware Abstraction Layer (HAL) is the boundary between ArduPilot’s vehicle and library code and the underlying operating system or bare-metal hardware. Every peripheral — serial ports, SPI buses, I2C devices, GPIO pins, RC inputs, RC outputs, storage — is accessed exclusively through HAL interfaces. This means the same ArduCopter/, ArduPlane/, and libraries/ code compiles and runs correctly on an STM32-based flight controller, a Linux single-board computer, an ESP32, and the SITL simulator without any platform-specific conditionals in shared code.

HAL interface overview

The top-level HAL object is AP_HAL::HAL, declared in libraries/AP_HAL/HAL.h. It holds pointers to every subsystem driver:
class AP_HAL::HAL {
public:
    AP_HAL::I2CDeviceManager* i2c_mgr;
    AP_HAL::SPIDeviceManager* spi;
    AP_HAL::WSPIDeviceManager* wspi;
    AP_HAL::AnalogIn*   analogin;
    AP_HAL::Storage*    storage;
    AP_HAL::UARTDriver* console;
    AP_HAL::GPIO*       gpio;
    AP_HAL::RCInput*    rcin;
    AP_HAL::RCOutput*   rcout;
    AP_HAL::Scheduler*  scheduler;
    AP_HAL::Util*       util;
    AP_HAL::OpticalFlow* opticalflow;
    AP_HAL::Flash*      flash;

    // Access serial ports by SERIALn index
    UARTDriver* serial(uint8_t sernum) const;
};
The global hal instance is declared as extern const AP_HAL::HAL& hal; and defined once per platform by the corresponding HAL implementation.

HAL implementations

AP_HAL_ChibiOS

Targets STM32 microcontrollers running ChibiOS. Used by Pixhawk, CubeBlack, and the majority of supported flight controllers.

AP_HAL_Linux

Targets Linux boards such as Raspberry Pi, NAVIO2, and BeagleBone. Uses standard POSIX APIs and /dev device nodes.

AP_HAL_ESP32

Targets the ESP32 SoC. Enables low-cost WiFi-connected autopilot builds.

AP_HAL_SITL

Used during Software-In-The-Loop simulation. Replaces hardware drivers with software models driven by the physics backend.

Using the HAL in library code

Any .cpp file that needs hardware access declares the global hal reference at file scope and then calls through it:
#include <AP_HAL/AP_HAL.h>

extern const AP_HAL::HAL& hal;

void MyLibrary::init()
{
    // Serial port 0 is the console/USB port
    hal.serial(0)->begin(115200);

    // Configure GPIO pin 15 as output and drive it high
    hal.gpio->pinMode(15, HAL_GPIO_OUTPUT);
    hal.gpio->write(15, 1);

    // Delay 100 ms
    hal.scheduler->delay(100);
}
Never use platform-specific headers (e.g., <stm32f4xx.h>, <pigpio.h>) inside libraries/. All hardware access must go through the HAL interfaces. Platform-specific code belongs only inside the corresponding AP_HAL_* directory.

Key HAL interfaces

Access serial ports by their SERIALn index (0–9). Port 0 is the console/USB; ports 1 and 2 are the primary telemetry links; ports 3 and 4 are typically GPS.
AP_HAL::UARTDriver* uart = hal.serial(1);  // SERIAL1 / telem1
uart->begin(57600);
uart->write('A');
int c = uart->read();   // returns -1 if no data
uint32_t avail = uart->available();
The hal.gpio interface provides pinMode(), read(), write(), and toggle().
// Set pin 14 as input, read its state
hal.gpio->pinMode(14, HAL_GPIO_INPUT);
uint8_t state = hal.gpio->read(14);

// Set pin 15 as output and toggle it
hal.gpio->pinMode(15, HAL_GPIO_OUTPUT);
hal.gpio->toggle(15);
Constants: HAL_GPIO_INPUT = 0, HAL_GPIO_OUTPUT = 1, HAL_GPIO_ALT = 2.
hal.scheduler->delay(50);                  // block for 50 ms
hal.scheduler->delay_microseconds(500);    // block for 500 µs

// Register a function to run at timer interrupt rate (~1 kHz)
hal.scheduler->register_timer_process(
    FUNCTOR_BIND_MEMBER(&MyClass::timer_update, void));

// Register a low-priority I/O task
hal.scheduler->register_io_process(
    FUNCTOR_BIND_MEMBER(&MyClass::io_update, void));
Use AP_HAL::millis() and AP_HAL::micros() for non-blocking time checks instead of delay() inside hot loops.
// Acquire a device on I2C bus 0 at address 0x77
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev =
    hal.i2c_mgr->get_device(0, 0x77);

uint8_t reg = 0xD0;
uint8_t val = 0;
dev->read_registers(reg, &val, 1);
uint8_t buf[16];
hal.storage->read_block(buf, 0, sizeof(buf));   // read from offset 0
hal.storage->write_block(0, buf, sizeof(buf));  // write to offset 0
// Read RC channel 0 (µs)
uint16_t pwm = hal.rcin->read(0);

// Write PWM to output channel 0 (µs)
hal.rcout->write(0, 1500);

// Enable output channel before writing
hal.rcout->enable_ch(0);

The AP_HAL_MAIN macro

Every ArduPilot binary defines its entry point with the AP_HAL_MAIN() macro from libraries/AP_HAL/AP_HAL_Main.h. This macro wraps setup() and loop() in a HAL::FunCallbacks object and calls hal.run(), which is implemented differently on each platform:
#include <AP_HAL/AP_HAL.h>

// Declared by the active HAL implementation at link time
extern const AP_HAL::HAL& hal;

void setup()
{
    hal.console->begin(115200);
    hal.console->printf("Hello from ArduPilot\n");
}

void loop()
{
    hal.scheduler->delay(1000);
    hal.console->printf("tick\n");
}

// Expands to a platform-appropriate main() or app entry point
AP_HAL_MAIN();
On ChibiOS this becomes an RTOS entry point; on Linux it becomes a standard main(); in SITL it hooks into the simulation event loop.

Time functions

Always use the HAL time functions instead of platform-specific calls:
uint32_t now_ms  = AP_HAL::millis();    // milliseconds since boot
uint32_t now_us  = AP_HAL::micros();    // microseconds since boot
uint64_t now_ms64 = AP_HAL::millis64(); // 64-bit milliseconds
uint64_t now_us64 = AP_HAL::micros64(); // 64-bit microseconds
These are defined in libraries/AP_HAL/system.h and resolve to the correct platform implementation at link time.

Design rules

  • No platform headers in shared libraries. All hardware access must go through hal.* interfaces.
  • No direct printf or cout. Use hal.console->printf() for debug output during development, or GCS_SEND_TEXT() for operator-visible messages.
  • No std::chrono or POSIX time. Use AP_HAL::millis() / AP_HAL::micros().
  • Use CLASS_NO_COPY(). Most HAL objects and library classes should be non-copyable singletons.
  • Feature guards. Wrap optional hardware features in #if AP_<FEATURE>_ENABLED to allow builds on resource-constrained boards.

Build docs developers (and LLMs) love