Documentation Index
Fetch the complete documentation index at: https://mintlify.com/PX4/PX4-Autopilot/llms.txt
Use this file to discover all available pages before exploring further.
PX4 drivers are loadable modules that read from hardware peripherals and publish data onto the uORB message bus. Every driver follows the same core contract: produce well-typed uORB topics that the rest of the flight stack consumes. You do not need to implement a file-system interface, callbacks, or any other framework — publishing the correct uORB topic is the only mandatory pattern.
Driver framework overview
PX4 uses two complementary layers for device access:
- Device library (
src/lib/drivers/device) — provides base classes for I2C, SPI, and UART peripherals, handles bus locking, retry logic, and device registration.
- uORB publish/subscribe — the only inter-module communication mechanism. Drivers publish sensor readings; estimators, controllers, and loggers subscribe.
PX4 identifies every sensor instance with a 24-bit Device ID that encodes the bus type, bus number, bus address, and device class. This ID is stored in calibration parameters so the system can re-associate calibration data after a reboot regardless of enumeration order.
struct DeviceStructure {
enum DeviceBusType bus_type : 3; // I2C=1, SPI=2, UAVCAN=3
uint8_t bus : 5; // bus instance number
uint8_t address; // I2C address or SPI CS slot
uint8_t devtype; // class-specific device type code
};
A driver does not need to own a file descriptor or implement ioctl. The global device registry is used only for enumeration and configuration; all real-time data flows through uORB.
Driver directory layout
Drivers live under src/drivers/, organized by sensor class and then by manufacturer or chip family:
src/drivers/
├── imu/
│ ├── invensense/
│ │ ├── icm42688p/
│ │ │ ├── CMakeLists.txt
│ │ │ ├── Kconfig
│ │ │ ├── icm42688p_main.cpp ← module entry point
│ │ │ ├── ICM42688P.cpp ← driver implementation
│ │ │ ├── ICM42688P.hpp
│ │ │ └── InvenSense_ICM42688P_registers.hpp
│ │ └── ...
│ └── bosch/
├── magnetometer/
├── barometer/
├── distance_sensor/
└── ...
Start every new driver by copying the closest existing driver. The src/drivers/imu/invensense/icm42688p/ driver is a well-structured reference for SPI IMU devices.
Minimal driver skeleton
The following files are the minimum required for a new sensor driver.
my_sensor_main.cpp
MySensor.hpp
MySensor.cpp
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include "MySensor.hpp"
extern "C" __EXPORT int my_sensor_main(int argc, char *argv[]);
int my_sensor_main(int argc, char *argv[])
{
return MySensor::main(argc, argv);
}
The _main entry point is the executable name PX4 uses to start and stop the driver from the NuttX shell or SITL console.#pragma once
#include <drivers/device/i2c.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/sensor_accel.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
class MySensor : public device::I2C,
public ModuleBase<MySensor>,
public px4::ScheduledWorkItem
{
public:
MySensor(const I2CSPIDriverConfig &config);
~MySensor() override = default;
static void print_usage();
void RunImpl() override;
private:
uORB::PublicationMulti<sensor_accel_s> _sensor_accel_pub{ORB_ID(sensor_accel)};
bool read_measurement(sensor_accel_s &report);
};
#include "MySensor.hpp"
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
MySensor::MySensor(const I2CSPIDriverConfig &config)
: I2C(config),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default)
{
}
void MySensor::RunImpl()
{
sensor_accel_s report{};
if (read_measurement(report)) {
report.timestamp = hrt_absolute_time();
report.device_id = get_device_id();
_sensor_accel_pub.publish(report);
}
ScheduleDelayed(1000); // reschedule in 1 ms
}
bool MySensor::read_measurement(sensor_accel_s &report)
{
uint8_t buf[6];
if (transfer(nullptr, 0, buf, sizeof(buf)) != PX4_OK) {
return false;
}
report.x = (int16_t)((buf[1] << 8) | buf[0]) * 0.001f;
report.y = (int16_t)((buf[3] << 8) | buf[2]) * 0.001f;
report.z = (int16_t)((buf[5] << 8) | buf[4]) * 0.001f;
return true;
}
Registering the driver in CMakeLists.txt
Every driver module requires a CMakeLists.txt that calls px4_add_module. This is the only required build-system file.
px4_add_module(
MODULE drivers__my_sensor
MAIN my_sensor
SRCS
my_sensor_main.cpp
MySensor.cpp
MySensor.hpp
DEPENDS
px4_work_queue
drivers_accelerometer
)
MODULE must follow the drivers__<subpath> naming convention, using double underscores for path separators.
MAIN is the command name available in the NuttX shell and used in startup scripts.
DEPENDS lists PX4 library targets the module links against. Common entries are px4_work_queue, drivers_accelerometer, drivers_gyroscope, and modules__uORB.
To enable verbose PX4_DEBUG output during development, add -DDEBUG_BUILD to a COMPILE_FLAGS block inside px4_add_module. Remove this flag before merging.
Enabling the driver per board
Drivers are opt-in per board using Kconfig. You must do two things: declare the option in the driver’s Kconfig file, and enable it in the target board’s .px4board config file.
Driver Kconfig:
menuconfig DRIVERS_MY_SENSOR
bool "MySensor accelerometer"
default n
---help---
Enable driver for the MySensor I2C accelerometer.
Board config (boards/<vendor>/<board>/default.px4board):
CONFIG_DRIVERS_MY_SENSOR=y
The .px4board files use the same format as Linux kernel .config files. Each line is a CONFIG_<KEY>=y or # CONFIG_<KEY> is not set entry. You can also run make <board> menuconfig to toggle options interactively.
Bus configuration patterns
// In the driver's I2CSPIDriverConfig, set the bus and address.
// The framework resolves the physical I2C bus from board config.
I2CSPIDriverConfig config{};
config.bus_option = I2CSPIBusOption::All; // try all I2C buses
config.i2c_address = 0x68; // sensor I2C address
config.frequency = 400000; // 400 kHz fast-mode
// SPI drivers inherit from device::SPI.
// CS, bus, and frequency are resolved from the board's SPI bus table.
I2CSPIDriverConfig config{};
config.bus_option = I2CSPIBusOption::SPI;
config.spi_devid = DRV_IMU_DEVTYPE_ICM42688P;
config.spi_mode = SPIDEV_MODE3;
config.frequency = 24000000; // 24 MHz
// UART drivers open a serial port directly.
// Use the CONFIG_BOARD_SERIAL_* entries from the board config
// to determine the port path (e.g. /dev/ttyS0).
int fd = ::open(port, O_RDWR | O_NOCTTY);
struct termios uart_config{};
tcgetattr(fd, &uart_config);
cfsetspeed(&uart_config, B115200);
tcsetattr(fd, TCSANOW, &uart_config);
Testing a driver in SITL
You can test driver logic in the Software-In-The-Loop simulator without physical hardware by building a SITL target and loading your driver.
Build the SITL target
make px4_sitl gazebo-classic
Start the PX4 SITL shell
SITL exposes the same NuttX-style shell. In the running console, start your driver:The -X flag tells the driver to use the external I2C bus. Use my_sensor status to confirm the driver is running and publishing. Subscribe to the uORB topic
pxh> listener sensor_accel
You should see timestamped accelerometer samples stream to the console if the driver is publishing correctly.Run the unit tests
make tests TESTFILTER=drivers
This runs any gtest-based unit tests registered under src/drivers/. Add a test_my_sensor.cpp to your driver directory and register it with px4_add_unit_gtest in CMakeLists.txt.
You can also enable DEBUG_BUILD logging at runtime in SITL by passing -DDEBUG_BUILD in COMPILE_FLAGS and rebuilding. Debug log lines appear in the SITL console with a D prefix.