模块参考:系统
battery_simulator
Source: modules/simulation/battery_simulator
描述
用法
battery_simulator <command> [arguments...]
wind_estimator <command> [arguments...]
Commands:
start
stop
status 打印状态信息
battery_status
Source: modules/battery_status
描述
模块提供的功能包括:
- 从 ADC 驱动读取电池状态(通过 ioctl 接口),并且发布到主题
battery_status
。
实现
模块运行在它自己的线程中,并轮询当前选定的陀螺仪主题。
用法
battery_status <command> [arguments...]
wind_estimator <command> [arguments...]
Commands:
start
stop
status 打印状态信息
camera_feedback
Source: modules/camera_feedback
描述
The camera_feedback module publishes CameraCapture
UORB topics when image capture has been triggered.
If camera capture is enabled, then trigger information from the camera capture pin is published; otherwise trigger information at the point the camera was commanded to trigger is published (from the camera_trigger
module).
The CAMERA_IMAGE_CAPTURED
message is then emitted (by streaming code) following CameraCapture
updates. CameraCapture
topics are also logged and can be used for geotagging.
实现
CameraTrigger
topics are published by the camera_trigger
module (feedback
field set false
) when image capture is triggered, and may also be published by the camera_capture
driver (with feedback
field set true
) if the camera capture pin is activated.
The camera_feedback
module subscribes to CameraTrigger
. It discards topics from the camera_trigger
module if camera capture is enabled. For the topics that are not discarded it creates a CameraCapture
topic with the timestamp information from the CameraTrigger
and position information from the vehicle.
用法
camera_feedback <command> [arguments...]
wind_estimator <command> [arguments...]
Commands:
start
stop
status 打印状态信息
cdcacm_autostart
Source: drivers/cdcacm_autostart
描述
This module listens on USB and auto-configures the protocol depending on the bytes received. The supported protocols are: MAVLink, nsh, and ublox serial passthrough. If the parameter SYS_USB_AUTO=2 the module will only try to start mavlink as long as the USB VBUS is detected. Otherwise it will spin and continue to check for VBUS and start mavlink once it is detected.
描述
cdcacm_autostart <command> [arguments...]
mc_att_control <command> [arguments...]
Commands:
start
stop
status 打印状态信息
commander
Source: modules/commander
描述
该模块包含飞行模式切换和失效保护状态机。
用法
commander <command> [arguments...]
Commands:
start
[-h] Enable HIL mode
calibrate Run sensor calibration
mag|baro|accel|gyro|level|esc|airspeed Calibration type
quick Quick calibration (accel only, not recommended)
check Run preflight checks
arm
[-f] Force arming (do not run preflight checks)
disarm
[-f] Force disarming (disarm in air)
takeoff
land
transition VTOL transition
mode Change flight mode
manual|acro|offboard|stabilized|altctl|posctl|position:slow|auto:mission|au
to:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1
Flight mode
pair
lockdown
on|off Turn lockdown on or off
set_ekf_origin
lat, lon, alt Origin Latitude, Longitude, Altitude
lat|lon|alt Origin latitude longitude altitude
poweroff Power off board (if supported)
stop
status print status info
dataman
Source: modules/dataman
示例
该模块通过基于C语言的API以简单数据库的形式为系统的其他部分提供持续性存储功能。 支持多种后端:
- a file (eg. on the SD card)
- FLASH(需要飞控板支持)
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. 每种类型的数据都有一个特定的类型和一个固定的最大存储条目的数量,因此可以实现对数据的快速随机访问。
描述
单个数据的读取和写入是原子操作。
描述
dataman <command> [arguments...]
dataman <command> [arguments...]
Commands:
start
[-f <val>] Storage file
values: <file>
[-r] Use RAM backend (NOT persistent)
[-i] Use FLASH backend
The options -f, -r and -i are mutually exclusive. If nothing is specified, a
file 'dataman' is used
poweronrestart Restart dataman (on power on)
inflightrestart Restart dataman (in flight)
stop
status print status info If nothing is specified, a file
'dataman' is used
stop
status print status info
dmesg
Source: systemcmds/dmesg
描述
用于显示启动控制台消息的命令行工具 需要注意的是,NuttX系统的工作队列和系统日志输出都未被捕捉到。
示例
持续在后台打印所有消息。
dmesg -f &
描述
dmesg <command> [arguments...]
Commands:
[-f] Follow: wait for new messages
esc_battery
Source: modules/esc_battery
描述
Background process running periodically with 1 Hz on the LP work queue to calculate the CPU load and RAM usage and publish the cpuload
topic.
描述
esc_battery <command> [arguments...]
mc_att_control <command> [arguments...]
Commands:
start
stop
status 打印状态信息
gyro_calibration
Source: modules/gyro_calibration
描述
用法
gyro_calibration <command> [arguments...]
mc_att_control <command> [arguments...]
Commands:
start
stop
status 打印状态信息
heater
Source: modules/gyro_fft
描述
实现
gyro_fft <command> [arguments...]
land_detector <command> [arguments...]
Commands:
start 启动后台任务
fixedwing|multicopter|vtol|ugv 选择飞机类型
stop
status 打印状态信息
land_detector
Source: drivers/heater
用法
This task can be started at boot from the startup scripts by setting SENS_EN_THERMAL or via CLI.
用法
heater <command> [arguments...]
replay <command> [arguments...]
Commands:
start Start replay, using log file from ENV variable 'replay'
trystart Same as 'start', but silently exit if no log file given
tryapplyparams Try to apply the parameters from the log file
stop
status print status info
i2c_launcher
Source: systemcmds/i2c_launcher
描述
Daemon that starts drivers based on found I2C devices.
实现
i2c_launcher <command> [arguments...]
Commands:
start
-b <val> Bus number
stop
status print status info
load_mon
Source: modules/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. 当检测到 ground_contact 状态时,位置控制器将关闭机体 x 方向和 y 方向上的推力设定值。
用法
Every type is implemented in its own class with a common base class. 触发时间由变量 MAYBE_LAND_TRIGGER_TIME 定义。 当检测到 maybe_landed 状态时,位置控制器会将推理设定值设置为零。 A hysteresis and a fixed priority of each internal state determines the actual land_detector state.
多旋翼的 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.
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
:
用法
land_detector <command> [arguments...]
load_mon <command> [arguments...]
Commands:
start 启动后台任务
stop
status 打印状态信息
logger
Source: modules/load_mon
参数描述
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.
实现
load_mon <command> [arguments...]
Commands:
start Start the background task
stop
status print status info
logger
Source: modules/logger
用法
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:
- 文件:写入 ULog 文件到文件系统中(SD 卡)
- MAVLink: 通过 MAVLink 将 ULog 数据流传输到客户端上(需要客户端支持此方式)
模块的实现使用了两个线程:
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. 缓冲区应大到可以避免出现数据溢出。 It can be enabled and configured via SDLOG_MISSION parameter. The normal log is always a superset of the mission log.
Implementation
立刻开始记录日志的典型用法:
- The main thread, running at a fixed rate (or polling on a topic if started with -p) and checking for data updates
- 写入线程,将数据写入文件中、
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.
参数描述
Typical usage to start logging immediately:
logger on
Or if already running:
logger on
参数描述
logger <command> [arguments...]
Commands:
start
[-m <val>] Backend mode
values: file|mavlink|all, default: all
[-x] Enable/disable logging via Aux1 RC channel
[-a] Log 1st armed until shutdown
[-e] Enable logging right after start until disarm (otherwise only
when armed)
[-f] Log until shutdown (implies -e)
[-t] Use date/time for naming log directories and files
[-r <val>] Log rate in Hz, 0 means unlimited rate
default: 280
[-b <val>] Log buffer size in KiB
default: 12
[-p <val>] Poll on a topic instead of running with fixed rate (Log rate
and topic intervals are ignored if this is set)
values: <topic_name>
[-c <val>] Log rate factor (higher is faster)
default: 1.0
on start logging now, override arming (logger must be running)
off stop logging now, override arming (logger must be running)
trigger_watchdog manually trigger the watchdog now
stop
status print status info
mag_bias_estimator
Source: modules/mag_bias_estimator
Description
Online magnetometer bias estimator.
用法
mag_bias_estimator <command> [arguments...]
wind_estimator <command> [arguments...]
Commands:
start
stop
status 打印状态信息
replay
Source: modules/manual_control
Description
Module consuming manual_control_inputs publishing one manual_control_setpoint.
Usage
manual_control <command> [arguments...]
Commands:
start
stop
status print status info
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
用法
netman <command> [arguments...]
Commands:
show Display the current persistent network settings to the console.
update Check SD card for net.cfg and update network persistent network
settings.
save Save the current network parameters to the SD card.
[-i <val>] Set the interface name
default: eth0
pwm_input
Source: drivers/pwm_input
参数描述
Measures the PWM input on AUX5 (or MAIN5) via a timer capture ISR and publishes via the uORB 'pwm_input` message.
Usage
pwm_input <command> [arguments...]
Commands:
start
stop
status print status info
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
rc_update <command> [arguments...]
Commands:
start
stop
status print status info
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
: 指定 EKF2 回放模式。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
replay <command> [arguments...]
Commands:
start Start replay, using log file from ENV variable 'replay'
trystart Same as 'start', but silently exit if no log file given
tryapplyparams Try to apply the parameters from the log file
stop
status print status info
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
send_event <command> [arguments...]
Commands:
start Start the background task
stop
status print status info
sensor_arispeed_sim
Source: modules/simulation/sensor_airspeed_sim
Description
Usage
sensor_arispeed_sim <command> [arguments...]
Commands:
start
stop
status print status info
sensor_baro_sim
Source: modules/simulation/sensor_baro_sim
Description
实现
sensor_baro_sim <command> [arguments...]
Commands:
start
stop
status print status info
sensor_gps_sim
Source: modules/simulation/sensor_gps_sim
描述
Usage
sensor_gps_sim <command> [arguments...]
Commands:
start
stop
status print status info
sensor_mag_sim
Source: modules/simulation/sensor_mag_sim
Description
Usage
sensor_mag_sim <command> [arguments...]
Commands:
start
stop
status print status info
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.). 如果存在多个同类型传感器,那个模块将进行投票和容错处理。 然后应用飞控板的旋转和温度校正(如果被启用)。 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. 传感器驱动使用 ioctl 接口获取参数更新。 为了使这一功能正常运行,当sensors
模块启动时传感器驱动必须已经处于运行状态。 - 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
sensors <command> [arguments...]
Commands:
start
[-h] Start in HIL mode
stop
status print status info
tattu_can
Source: drivers/tattu_can
Description
Driver for reading data from the Tattu 12S 16000mAh smart battery.
Usage
tattu_can <command> [arguments...]
wind_estimator <command> [arguments...]
Commands:
start
stop
status 打印状态信息
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
temperature_compensation <command> [arguments...]
Commands:
start Start the module, which monitors the sensors and updates the
sensor_correction topic
calibrate Run temperature calibration process
[-a] calibrate the accel
[-g] calibrate the gyro
[-m] calibrate the mag
[-b] calibrate the baro (if none of these is given, all will be
calibrated)
stop
status print status info
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/release/1.15/src/lib/tunes/tune_definition.desc
Examples
Play system tune #2:
tune_control play -t 2
Usage
tune_control <command> [arguments...]
Commands:
play Play system tune or single note.
error Play error tune
[-t <val>] Play predefined system tune
default: 1
[-f <val>] Frequency of note in Hz (0-22kHz)
[-d <val>] Duration of note in us
[-s <val>] Volume level (loudness) of the note (0-100)
default: 40
[-m <val>] Melody in string form
values: <string> - e.g. "MFT200e8a8a"
libtest Test library
stop Stop playback (use for repeated tunes)
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
uxrce_dds_client start -t serial -d /dev/ttyS3 -b 921600
uxrce_dds_client start -t udp -h 127.0.0.1 -p 15555
Usage
uxrce_dds_client <command> [arguments...]
Commands:
start
[-t <val>] Transport protocol
values: serial|udp, default: udp
[-d <val>] serial device
values: <file:dev>
[-b <val>] Baudrate (can also be p:<param_name>)
default: 0
[-h <val>] Agent IP. If not provided, defaults to UXRCE_DDS_AG_IP
values: <IP>
[-p <val>] Agent listening port. If not provided, defaults to
UXRCE_DDS_PRT
[-n <val>] Client DDS namespace
stop
status print status info
work_queue
Source: systemcmds/work_queue
Description
Command-line tool to show work queue status.
Usage
work_queue <command> [arguments...]
Commands:
start
stop
status print status info