Drivers

Subcategories:

MCP23009

Source: drivers/gpio/mcp23009

Usage

MCP23009 <command> [arguments...]
 Commands:
   start
     [-I]        Internal I2C bus(es)
     [-X]        External I2C bus(es)
     [-b <val>]  board-specific bus (default=all) (external SPI: n-th bus
                 (default=1))
     [-f <val>]  bus frequency in kHz
     [-q]        quiet startup (no message if no device found)
     [-a <val>]  I2C address
                 default: 37
     [-D <val>]  Direction
                 default: 0
     [-O <val>]  Output
                 default: 0
     [-P <val>]  Pullups
                 default: 0
     [-U <val>]  Update Interval [ms]
                 default: 0

   stop

   status        print status info

adc

Source: drivers/adc/board_adc

Description

ADC driver.

Usage

ads1115

Source: drivers/adc/ads1115

Description

Driver to enable an external ADS1115 ADC connected via I2C.

The driver is included by default in firmware for boards that do not have an internal analog to digital converter, such as PilotPi or CUAV Nora (search for CONFIG_DRIVERS_ADC_ADS1115 in board configuration files).

It is enabled/disabled using the ADC_ADS1115_EN parameter, and is disabled by default. If enabled, internal ADCs are not used.

Usage

atxxxx

Source: drivers/osd/atxxxx

Description

OSD driver for the ATXXXX chip that is mounted on the OmnibusF4SD board for example.

It can be enabled with the OSD_ATXXXX_CFG parameter.

Usage

batmon

Source: drivers/smart_battery/batmon

Description

Driver for SMBUS Communication with BatMon enabled smart-battery Setup/usage information: https://rotoye.com/batmon-tutorial/

Examples

To start at address 0x0B, on bus 4

Usage

batt_smbus

Source: drivers/batt_smbus

Description

Smart battery driver for the BQ40Z50 fuel gauge IC.

Examples

To write to flash to set parameters. address, number_of_bytes, byte0, ... , byteN

Usage

bst

Source: drivers/telemetry/bst

Usage

crsf_rc

Source: drivers/rc/crsf_rc

Description

This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data

Usage

dshot

Source: drivers/dshot

Description

This is the DShot output driver. It is similar to the fmu driver, and can be used as drop-in replacement to use DShot as ESC communication protocol instead of PWM.

On startup, the module tries to occupy all available pins for DShot output. It skips all pins already in use (e.g. by a camera trigger module).

It supports:

  • DShot150, DShot300, DShot600, DShot1200

  • telemetry via separate UART and publishing as esc_status message

  • sending DShot commands via CLI

Examples

Permanently reverse motor 1:

After saving, the reversed direction will be regarded as the normal one. So to reverse again repeat the same commands.

Usage

fake_gps

Source: examples/fake_gps

Description

Usage

fake_imu

Source: examples/fake_imu

Description

Usage

fake_magnetometer

Source: examples/fake_magnetometer

Description

Publish the earth magnetic field as a fake magnetometer (sensor_mag). Requires vehicle_attitude and vehicle_gps_position.

Usage

gimbal

Source: modules/gimbal

Description

Mount/gimbal Gimbal control driver. It maps several different input methods (eg. RC or MAVLink) to a configured output (eg. AUX channels or MAVLink).

Documentation how to use it is on the gimbal_control page.

Examples

Test the output by setting a angles (all omitted axes are set to 0):

Usage

gps

Source: drivers/gps

Description

GPS driver module that handles the communication with the device and publishes the position via uORB. It supports multiple protocols (device vendors) and by default automatically selects the correct one.

The module supports a secondary GPS device, specified via -e parameter. The position will be published on the second uORB topic instance, but it's currently not used by the rest of the system (however the data will be logged, so that it can be used for comparisons).

Implementation

There is a thread for each device polling for data. The GPS protocol classes are implemented with callbacks so that they can be used in other projects as well (eg. QGroundControl uses them too).

Examples

Starting 2 GPS devices (the main GPS on /dev/ttyS3 and the secondary on /dev/ttyS4):

Initiate warm restart of GPS device

Usage

gz_bridge

Source: modules/simulation/gz_bridge

Description

Usage

ina220

Source: drivers/power_monitor/ina220

Description

Driver for the INA220 power monitor.

Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address.

For example, one instance can run on Bus 2, address 0x41, and one can run on Bus 2, address 0x43.

If the INA220 module is not powered, then by default, initialization of the driver will fail. To change this, use the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver.

Usage

ina226

Source: drivers/power_monitor/ina226

Description

Driver for the INA226 power monitor.

Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address.

For example, one instance can run on Bus 2, address 0x41, and one can run on Bus 2, address 0x43.

If the INA226 module is not powered, then by default, initialization of the driver will fail. To change this, use the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver.

Usage

ina228

Source: drivers/power_monitor/ina228

Description

Driver for the INA228 power monitor.

Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address.

For example, one instance can run on Bus 2, address 0x45, and one can run on Bus 2, address 0x45.

If the INA228 module is not powered, then by default, initialization of the driver will fail. To change this, use the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver.

Usage

ina238

Source: drivers/power_monitor/ina238

Description

Driver for the INA238 power monitor.

Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address.

For example, one instance can run on Bus 2, address 0x45, and one can run on Bus 2, address 0x45.

If the INA238 module is not powered, then by default, initialization of the driver will fail. To change this, use the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without this flag set, the battery must be plugged in before starting the driver.

Usage

iridiumsbd

Source: drivers/telemetry/iridiumsbd

Description

IridiumSBD driver.

Creates a virtual serial port that another module can use for communication (e.g. mavlink).

Usage

irlock

Source: drivers/irlock

Usage

linux_pwm_out

Source: drivers/linux_pwm_out

Description

Linux PWM output driver with board-specific backend implementation.

Usage

lsm303agr

Source: drivers/magnetometer/lsm303agr

Usage

Source: drivers/actuators/modal_io

Description

This module is responsible for...

Implementation

By default the module runs on a work queue with a callback on the uORB actuator_controls topic.

Examples

It is typically started with:

Usage

msp_osd

Source: drivers/osd/msp_osd

Description

MSP telemetry streamer

Implementation

Converts uORB messages to MSP telemetry packets

Examples

CLI usage example:

Usage

newpixel

Source: drivers/lights/neopixel

Description

This module is responsible for driving interfasing to the Neopixel Serial LED

Examples

It is typically started with:

To drive all available leds.

Usage

paa3905

Source: drivers/optical_flow/paa3905

Usage

paw3902

Source: drivers/optical_flow/paw3902

Usage

pca9685_pwm_out

Source: drivers/pca9685_pwm_out

Description

This module is responsible for generate pwm pulse with PCA9685 chip.

It listens on the actuator_controls topics, does the mixing and writes the PWM outputs.

Implementation

This module depends on ModuleBase and OutputModuleInterface. IIC communication is based on CDev::I2C

Examples

It is typically started with:

The number X can be acquired by executing pca9685_pwm_out status when this driver is running.

Usage

pmw3901

Source: drivers/optical_flow/pmw3901

Usage

pps_capture

Source: drivers/pps_capture

Description

This implements capturing PPS information from the GNSS module and calculates the drift between PPS and Real-time clock.

Usage

pwm_out

Source: drivers/pwm_out

Description

This module is responsible for driving the output pins. For boards without a separate IO chip (eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the px4io driver is used for main ones.

Usage

pwm_out_sim

Source: modules/simulation/pwm_out_sim

Description

Driver for simulated PWM outputs.

Its only function is to take actuator_control uORB messages, mix them with any loaded mixer and output the result to the actuator_output uORB topic.

It is used in SITL and HITL.

Usage

px4flow

Source: drivers/optical_flow/px4flow

Usage

px4io

Source: drivers/px4io

Description

Output driver communicating with the IO co-processor.

Usage

rc_input

Source: drivers/rc_input

Description

This module does the RC input parsing and auto-selecting the method. Supported methods are:

  • PPM

  • SBUS

  • DSM

  • SUMD

  • ST24

  • TBS Crossfire (CRSF)

Usage

rgbled

Source: drivers/lights/rgbled_ncp5623c

Usage

rgbled_is31fl3195

Source: drivers/lights/rgbled_is31fl3195

Usage

rgbled_lp5562

Source: drivers/lights/rgbled_lp5562

Description

Driver for LP5562 LED driver connected via I2C.

This used in some GPS modules by Holybro for PX4 status notification

The driver is included by default in firmware (KConfig key DRIVERS_LIGHTS_RGBLED_LP5562) and is always enabled.

Usage

safety_button

Source: drivers/safety_button

Description

This module is responsible for the safety button. Pressing the safety button 3 times quickly will trigger a GCS pairing request.

Usage

sht3x

Source: drivers/hygrometer/sht3x

Description

SHT3x Temperature and Humidity Sensor Driver by Senserion.

Examples

CLI usage example:

Start the sensor driver on the external bus

Print driver status

Print last measured values

Reinitialize senzor, reset flags

Usage

tap_esc

Source: drivers/tap_esc

Description

This module controls the TAP_ESC hardware via UART. It listens on the actuator_controls topics, does the mixing and writes the PWM outputs.

Implementation

Currently the module is implemented as a threaded version only, meaning that it runs in its own thread instead of on the work queue.

Example

The module is typically started with:

Usage

tone_alarm

Source: drivers/tone_alarm

Description

This module is responsible for the tone alarm.

Usage

uwb

Source: drivers/uwb/uwb_sr150

Description

Driver for NXP UWB_SR150 UWB positioning system. This driver publishes a uwb_distance message whenever the UWB_SR150 has a position measurement available.

Example

Start the driver with a given device:

Usage

voxlpm

Source: drivers/power_monitor/voxlpm

Usage

Last updated