System
battery_simulator
Source: modules/simulation/battery_simulator
Description
Usage
battery_status
Source: modules/battery_status
Description
The provided functionality includes:
Read the output from the ADC driver (via ioctl interface) and publish
battery_status
.
Implementation
It runs in its own thread and polls on the currently selected gyro topic.
Usage
camera_feedback
Source: modules/camera_feedback
Description
Usage
commander
Source: modules/commander
Description
The commander module contains the state machine for mode switching and failsafe behavior.
Usage
dataman
Source: modules/dataman
Description
Module to provide persistent storage for the rest of the system in form of a simple database through a C API. Multiple backends are supported:
a file (eg. on the SD card)
RAM (this is obviously not persistent)
It is used to store structured data of different types: mission waypoints, mission state and geofence polygons. Each type has a specific type and a fixed maximum amount of storage items, so that fast random access is possible.
Implementation
Reading and writing a single item is always atomic.
DM_KEY_FENCE_POINTS and DM_KEY_SAFE_POINTS items: the first data element is a mission_stats_entry_s
struct, which stores the number of items for these types. These items are always updated atomically in one transaction (from the mavlink mission manager).
Usage
dmesg
Source: systemcmds/dmesg
Description
Command-line tool to show bootup console messages. Note that output from NuttX's work queues and syslog are not captured.
Examples
Keep printing all messages in the background:
Usage
esc_battery
Source: modules/esc_battery
Description
This implements using information from the ESC status and publish it as battery status.
Usage
gyro_calibration
Source: modules/gyro_calibration
Description
Simple online gyroscope calibration.
Usage
gyro_fft
Source: modules/gyro_fft
Description
Usage
heater
Source: drivers/heater
Description
Background process running periodically on the LP work queue to regulate IMU temperature at a setpoint.
This task can be started at boot from the startup scripts by setting SENS_EN_THERMAL or via CLI.
Usage
land_detector
Source: modules/land_detector
Description
Module to detect the freefall and landed state of the vehicle, and publishing the vehicle_land_detected
topic. Each vehicle type (multirotor, fixedwing, vtol, ...) provides its own algorithm, taking into account various states, such as commanded thrust, arming state and vehicle motion.
Implementation
Every type is implemented in its own class with a common base class. The base class maintains a state (landed, maybe_landed, ground_contact). Each possible state is implemented in the derived classes. A hysteresis and a fixed priority of each internal state determines the actual land_detector state.
Multicopter Land Detector
ground_contact: thrust setpoint and velocity in z-direction must be below a defined threshold for time GROUND_CONTACT_TRIGGER_TIME_US. When ground_contact is detected, the position controller turns off the thrust setpoint in body x and y.
maybe_landed: it requires ground_contact together with a tighter thrust setpoint threshold and no velocity in the horizontal direction. The trigger time is defined by MAYBE_LAND_TRIGGER_TIME. When maybe_landed is detected, the position controller sets the thrust setpoint to zero.
landed: it requires maybe_landed to be true for time LAND_DETECTOR_TRIGGER_TIME_US.
The module runs periodically on the HP work queue.
Usage
load_mon
Source: modules/load_mon
Description
Background process running periodically on the low priority work queue to calculate the CPU load and RAM usage and publish the cpuload
topic.
On NuttX it also checks the stack usage of each process and if it falls below 300 bytes, a warning is output, which will also appear in the log file.
Usage
logger
Source: modules/logger
Description
System logger which logs a configurable set of uORB topics and system printf messages (PX4_WARN
and PX4_ERR
) to ULog files. These can be used for system and flight performance evaluation, tuning, replay and crash analysis.
It supports 2 backends:
Files: write ULog files to the file system (SD card)
MAVLink: stream ULog data via MAVLink to a client (the client must support this)
Both backends can be enabled and used at the same time.
The file backend supports 2 types of log files: full (the normal log) and a mission log. The mission log is a reduced ulog file and can be used for example for geotagging or vehicle management. It can be enabled and configured via SDLOG_MISSION parameter. The normal log is always a superset of the mission log.
Implementation
The implementation uses two threads:
The main thread, running at a fixed rate (or polling on a topic if started with -p) and checking for data updates
The writer thread, writing data to the file
In between there is a write buffer with configurable size (and another fixed-size buffer for the mission log). It should be large to avoid dropouts.
Examples
Typical usage to start logging immediately:
Or if already running:
Usage
mag_bias_estimator
Source: modules/mag_bias_estimator
Description
Online magnetometer bias estimator.
Usage
manual_control
Source: modules/manual_control
Description
Module consuming manual_control_inputs publishing one manual_control_setpoint.
Usage
netman
Source: systemcmds/netman
Description
Network configuration manager saves the network settings in non-volatile memory. On boot the update
option will be run. If a network configuration does not exist. The default setting will be saved in non-volatile and the system rebooted.
update
netman update
is run automatically by a startup script. When run, the update
option will check for the existence of net.cfg
in the root of the SD Card. It then saves the network settings from net.cfg
in non-volatile memory, deletes the file and reboots the system.
save
The save
option will save settings from non-volatile memory to a file named net.cfg
on the SD Card filesystem for editing. Use this to edit the settings. Save does not immediately apply the network settings; the user must reboot the flight stack. By contrast, the update
command is run by the start-up script, commits the settings to non-volatile memory, and reboots the flight controller (which will then use the new settings).
show
The show
option will display the network settings in net.cfg
to the console.
Examples
$ netman save # Save the parameters to the SD card. $ netman show # display current settings. $ netman update -i eth0 # do an update
Usage
pwm_input
Source: drivers/pwm_input
Description
Measures the PWM input on AUX5 (or MAIN5) via a timer capture ISR and publishes via the uORB 'pwm_input` message.
Usage
rc_update
Source: modules/rc_update
Description
The rc_update module handles RC channel mapping: read the raw input channels (input_rc
), then apply the calibration, map the RC channels to the configured channels & mode switches and then publish as rc_channels
and manual_control_input
.
Implementation
To reduce control latency, the module is scheduled on input_rc publications.
Usage
replay
Source: modules/replay
Description
This module is used to replay ULog files.
There are 2 environment variables used for configuration: replay
, which must be set to an ULog file name - it's the log file to be replayed. The second is the mode, specified via replay_mode
:
replay_mode=ekf2
: specific EKF2 replay mode. It can only be used with the ekf2 module, but allows the replay to run as fast as possible.Generic otherwise: this can be used to replay any module(s), but the replay will be done with the same speed as the log was recorded.
The module is typically used together with uORB publisher rules, to specify which messages should be replayed. The replay module will just publish all messages that are found in the log. It also applies the parameters from the log.
The replay procedure is documented on the System-wide Replay page.
Usage
send_event
Source: modules/events
Description
Background process running periodically on the LP work queue to perform housekeeping tasks. It is currently only responsible for tone alarm on RC Loss.
The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.).
Usage
sensor_arispeed_sim
Source: modules/simulation/sensor_airspeed_sim
Description
Usage
sensor_baro_sim
Source: modules/simulation/sensor_baro_sim
Description
Usage
sensor_gps_sim
Source: modules/simulation/sensor_gps_sim
Description
Usage
sensor_mag_sim
Source: modules/simulation/sensor_mag_sim
Description
Usage
sensors
Source: modules/sensors
Description
The sensors module is central to the whole system. It takes low-level output from drivers, turns it into a more usable form, and publishes it for the rest of the system.
The provided functionality includes:
Read the output from the sensor drivers (
SensorGyro
, etc.). If there are multiple of the same type, do voting and failover handling. Then apply the board rotation and temperature calibration (if enabled). And finally publish the data; one of the topics isSensorCombined
, used by many parts of the system.Make sure the sensor drivers get the updated calibration parameters (scale & offset) when the parameters change or on startup. The sensor drivers use the ioctl interface for parameter updates. For this to work properly, the sensor drivers must already be running when
sensors
is started.Do sensor consistency checks and publish the
SensorsStatusImu
topic.
Implementation
It runs in its own thread and polls on the currently selected gyro topic.
Usage
tattu_can
Source: drivers/tattu_can
Description
Driver for reading data from the Tattu 12S 16000mAh smart battery.
Usage
temperature_compensation
Source: modules/temperature_compensation
Description
The temperature compensation module allows all of the gyro(s), accel(s), and baro(s) in the system to be temperature compensated. The module monitors the data coming from the sensors and updates the associated sensor_correction topic whenever a change in temperature is detected. The module can also be configured to perform the coeffecient calculation routine at next boot, which allows the thermal calibration coeffecients to be calculated while the vehicle undergoes a temperature cycle.
Usage
tune_control
Source: systemcmds/tune_control
Description
Command-line tool to control & test the (external) tunes.
Tunes are used to provide audible notification and warnings (e.g. when the system arms, gets position lock, etc.). The tool requires that a driver is running that can handle the tune_control uorb topic.
Information about the tune format and predefined system tunes can be found here: https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/tunes/tune_definition.desc
Examples
Play system tune #2:
Usage
uxrce_dds_client
Source: modules/uxrce_dds_client
Description
UXRCE-DDS Client used to communicate uORB topics with an Agent over serial or UDP.
Examples
Usage
work_queue
Source: systemcmds/work_queue
Description
Command-line tool to show work queue status.
Usage
Last updated