A Guided Tour of the PX4 Codebase

PX4 is one of the most widely used open-source autopilot stacks in both academia and industry. It powers fixed-wing aircraft, multirotors, rovers, and underwater vehicles, and runs on everything from a $10 microcontroller breakout board to a full Linux companion computer. If you have just cloned the repository for the first time and opened the folder tree, the scale of the project can be disorienting. This post walks through the architectural skeleton of PX4, explains how its modules are organized, and tells you exactly where to start reading.

The Big Picture: A Publish–Subscribe System

Before looking at any individual directory, the single most important concept to internalize is how PX4 modules talk to each other. The framework is built around a middleware layer called uORB (Micro Object Request Broker), a lightweight, in-process publish–subscribe message bus. Every module — whether it is reading a sensor, running a control law, or logging to a SD card — communicates exclusively through uORB topics. A module never calls another module’s functions directly.

This design has a practical consequence: you can understand any single module in isolation by knowing only which topics it subscribes to (its inputs) and which topics it advertises (its outputs). The dependency graph is data-driven, not call-stack-driven.

The message definitions themselves live in msg/. Each .msg file declares a C-struct-like schema. At build time, the PX4 build system auto-generates C++ headers from these definitions, so the types are always in sync with the bus.

Directory Structure at a Glance

The top-level repository is organized as follows. Only the directories most relevant to understanding the runtime behavior are described here; build tooling, simulation, and test infrastructure are omitted for brevity.

src/All flight-critical source code
drivers/Hardware abstraction — IMUs, barometers, GPS, ESCs
modules/Flight logic — estimators, controllers, planners
lib/Shared math, filters, and utility libraries
platforms/OS adaptation layer — NuttX, Linux, SITL
msg/uORB message definitions
boards/Per-board hardware configuration (Pixhawk, etc.)
ROMFS/Startup scripts and default parameters

The Four Conceptual Layers

It helps to think of the PX4 software stack as four loosely defined horizontal layers. Data generally flows upward from hardware and downward from planning.

Layer 1 — Hardware Drivers (src/drivers/)

Drivers are responsible for one task: reading raw data from a physical peripheral and publishing it as a uORB topic, or subscribing to a command topic and actuating a peripheral accordingly. A barometer driver, for instance, reads pressure over I²C and publishes a sensor_baro message. An ESC driver subscribes to actuator_outputs and converts normalized thrust commands into the appropriate PWM signals or UAVCAN frames.

Each driver lives in its own subdirectory and is compiled only when the target board’s configuration includes it. This is managed through CMakeLists.txt files and the board-specific default.px4board files under boards/.

If you are debugging a sensor that is not appearing correctly, this is the layer to start in.

Layer 2 — State Estimation (src/modules/ekf2/, src/modules/local_position_estimator/)

State estimation modules fuse raw sensor data into a coherent estimate of the vehicle’s pose and velocity. The primary estimator in modern PX4 is EKF2, an Extended Kalman Filter that fuses IMU, GPS, magnetometer, barometer, optical flow, and range-finder data. It subscribes to the raw sensor topics published by the drivers and advertises high-level state topics such as vehicle_local_position, vehicle_global_position, and vehicle_attitude.

The EKF2 code itself is mostly self-contained under src/modules/ekf2/EKF/, and the mathematics follow a fairly standard inertial navigation filter formulation. If you have taken a course on probabilistic robotics or Kalman filtering, the structure will feel familiar.

Layer 3 — Control (src/modules/mc_att_control/, src/modules/fw_att_control/, etc.)

Controllers translate state estimates and setpoints into actuator commands. PX4 separates attitude control from position control, and separates multicopter from fixed-wing logic. The typical cascade for a multicopter is:

\[\text{Position Setpoint} \xrightarrow{\text{mc\_pos\_control}} \text{Attitude Setpoint} \xrightarrow{\text{mc\_att\_control}} \text{Actuator Commands}\]

mc_att_control subscribes to vehicle_attitude_setpoint and vehicle_attitude, runs a PID-based rate controller, and publishes actuator\_controls. The separation of the cascade into discrete modules is intentional: you can swap out the position controller without touching attitude control, because they share no code — only uORB topics.

The navigator module implements high-level behaviors: takeoff, land, loiter, waypoint following, return-to-home. It consumes the vehicle’s estimated position and publishes position setpoints consumed by the position controller below it. MAVLink, the communication protocol used to interface with ground control stations such as QGroundControl, is implemented as its own module and translates between the external wire protocol and internal uORB messages.

The Module Pattern

Every PX4 module follows a consistent structural pattern. Understanding this pattern once lets you read any module cold. A module is, at its core, a class that inherits from ModuleBase<T> and ModuleParams. Its lifecycle looks like this:

// Instantiate and register the module
MyModule::task_spawn(argc, argv);

// The main work loop
void MyModule::Run() {
    // 1. Check for new parameter updates
    if (_parameter_update_sub.updated()) { /* reload params */ }

    // 2. Check for new input data
    if (_vehicle_attitude_sub.updated()) {
        vehicle_attitude_s att;
        _vehicle_attitude_sub.copy(&att);
        /* process att */
    }

    // 3. Compute outputs and publish
    _my_output_pub.publish(output_msg);
}

The ModuleParams base class provides automatic parameter synchronization with the global parameter server, so a module only needs to declare its parameters and they are updated at runtime without manual polling.

Where to Start

If you are new to the codebase, the following reading order is recommended.

Step 1 — Read a message definition. Open msg/vehicle_attitude.msg. It is ten lines long. This tells you what an attitude estimate looks like on the bus, and it will appear again in almost every module you subsequently read.

Step 2 — Read a simple driver. src/drivers/ms5611/ (the MS5611 barometer) is a good choice. It is self-contained, has no complex math, and clearly demonstrates the publish pattern.

Step 3 — Read the attitude controller. Open src/modules/mc_att_control/MulticopterAttitudeControl.cpp. Follow the Run() method. Identify every subscription and every publication. Sketch the data flow on paper.

Step 4 — Run SITL. PX4 ships a Software-In-The-Loop simulator. Running make px4_sitl gazebo-classic launches the full flight stack against a simulated vehicle. You can insert PX4_INFO("value: %f", (double)val) print statements anywhere and observe live data.

Step 5 — Inspect a topic at runtime. In the SITL shell, listener vehicle_attitude prints live attitude data to the console at whatever rate the estimator publishes. This is the fastest way to verify that a module is running and producing sensible output.

Parameter System

PX4 exposes nearly every tunable constant through a centralized parameter server. Parameters are declared with a macro at the top of a module:

DEFINE_PARAMETERS(
    (ParamFloat<px4::params::MC_ROLL_P>) _roll_p,
    (ParamFloat<px4::params::MC_PITCH_P>) _pitch_p
)

The naming convention MC_ROLL_P maps directly to what you see in QGroundControl’s parameter panel. Parameters are stored in non-volatile memory on the flight controller and survive power cycles. If you are tuning controller gains, you are interacting with this system.

Startup Sequence

The startup sequence is controlled by shell scripts under ROMFS/px4fmu_common/init.d/. When the flight controller boots, NuttX (the RTOS used on Pixhawk-class hardware) runs rcS, which in turn runs the appropriate airframe init script based on the SYS_AUTOSTART parameter. These scripts call module start commands that launch each module as a separate task. Reading the init script for your airframe type is a fast way to understand which modules are active on a given vehicle configuration.

Summary

The PX4 architecture is disciplined in its design: all runtime communication flows through uORB, all modules follow the same structural pattern, and the stack is cleanly partitioned from hardware to mission planning. This discipline is what makes a codebase of this scale readable in parts — you do not need to understand the whole system before you can meaningfully contribute to one layer of it. Start with the message definitions, follow the data, and use SITL aggressively. The rest will follow.