Compare commits

..

2 Commits

Author SHA1 Message Date
Hamish Willee 92459409b5 Signing minor subedit 2026-04-09 11:12:14 +10:00
Ramon Roche ae4d1894fd fix(mavlink): align signing with MAVLink spec and fix performance regression
Remove the non-standard MAV_SIGN_CFG parameter and align the signing
implementation with the MAVLink specification.

Key changes:
- Remove MAV_SIGN_CFG parameter that conflicted with GCS implementations
- Only enable signing when a valid key is present on the SD card
- Accept SETUP_SIGNING on any link, not just USB
- Reject SETUP_SIGNING while the vehicle is armed
- Allow disabling signing via signed all-zero key SETUP_SIGNING message
- Propagate key changes to all mavlink instances
- Zero CPU/bandwidth overhead when signing is not active

Fixes #26893

Signed-off-by: Ramon Roche <mrpollo@gmail.com>
2026-03-31 17:01:02 -07:00
427 changed files with 4075 additions and 62705 deletions
+1 -8
View File
@@ -240,15 +240,8 @@ if(NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE ${PX4_BUILD_TYPE} CACHE STRING "Build type" FORCE)
endif()
if(CONFIG_BOARD_SUPPORT_FORTIFIED_TOOLCHAIN)
set(PX4_DEBUG_OPT_LEVEL -Og)
message(STATUS "fortified toolchain support enabled: PX4_DEBUG_OPT_LEVEL=${PX4_DEBUG_OPT_LEVEL}")
else()
set(PX4_DEBUG_OPT_LEVEL -O0)
endif()
if((CMAKE_BUILD_TYPE STREQUAL "Debug") OR (CMAKE_BUILD_TYPE STREQUAL "Coverage"))
set(MAX_CUSTOM_OPT_LEVEL ${PX4_DEBUG_OPT_LEVEL})
set(MAX_CUSTOM_OPT_LEVEL -O0)
elseif(CMAKE_BUILD_TYPE MATCHES "Sanitizer")
set(MAX_CUSTOM_OPT_LEVEL -O1)
elseif(CMAKE_BUILD_TYPE MATCHES "Release")
-10
View File
@@ -67,16 +67,6 @@ menu "Toolchain"
help
Enables Cmake Release for -O3 optimization
config BOARD_SUPPORT_FORTIFIED_TOOLCHAIN
bool "Fortified toolchain support"
default n
help
Enable compatibility with toolchains that define
_FORTIFY_SOURCE.
This switches PX4_DEBUG_OPT_LEVEL from -O0 to -Og. Keep this
disabled unless the fortified toolchain requires optimization.
config BOARD_ROMFSROOT
string "ROMFSROOT"
default "px4fmu_common"
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#! /bin/bash
# exit when any command fails
set -e
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
if [[ $# -eq 0 ]] ; then
exit 0
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# Flash PX4 to a device running AuterionOS in the local network
if [ "$1" == "-h" ] || [ "$1" == "--help" ] || [ $# -lt 2 ]; then
echo "Usage: $0 -f <firmware.px4|.elf> [-c <configuration_dir>] -d <IP/Device> [-u <user>] [-p <ssh_port>] [--revert]"
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# This script is meant to be used by the build_all.yml workflow in a github runner
# Please only modify if you know what you are doing
set -e
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#! /bin/bash
# Copy a git diff between two commits if msg versioning is added
DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
mkdir artifacts
cp **/**/*.px4 artifacts/ 2>/dev/null || true
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# This script runs the fuzz tests from a given binary for a certain amount of time
set -e
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#! /bin/bash
# Copy msgs and the message translation node into a ROS workspace directory
DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#! /bin/bash
if [ -z ${PX4_DOCKER_REPO+x} ]; then
PX4_DOCKER_REPO="px4io/px4-dev:v1.17.0-beta1"
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# Script to run ShellCheck (a static analysis tool for shell scripts) over a
# script directory
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
GREEN='\033[0;32m'
NO_COLOR='\033[0m' # No Color
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
#
# Setup environment to make PX4 visible to Gazebo.
#
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# run multiple instances of the 'px4' binary, with the gazebo SITL simulation
# It assumes px4 is already built, with 'make px4_sitl_default sitl_gazebo-classic'
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# Run multiple instances of the 'px4' binary, without starting an external simulator.
# It assumes px4 is already built with the specified build target.
#
@@ -25,14 +25,7 @@ CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
# CONFIG_EKF2_AUX_GLOBAL_POSITION is not set
# CONFIG_EKF2_AUXVEL is not set
# CONFIG_EKF2_BARO_COMPENSATION is not set
# CONFIG_EKF2_DRAG_FUSION is not set
# CONFIG_EKF2_EXTERNAL_VISION is not set
# CONFIG_EKF2_GNSS_YAW is not set
# CONFIG_EKF2_OPTICAL_FLOW is not set
# CONFIG_EKF2_RANGE_FINDER is not set
# CONFIG_EKF2_SIDESLIP is not set
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_LAND_DETECTOR=y
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# Run this from the px4 project top level directory
docker run -it --rm --privileged -v `pwd`:/usr/local/workspace px4io/px4-dev-nuttx-focal:2022-08-12
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
set -e
# Create px4-* symlinks from px4-alias.sh
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
set -e
# Stop voxl-px4 service if running
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
echo "*** Starting unified VOXL2 build (apps + SLPI) ***"
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
echo "*** Starting unified VOXL2 build (apps + SLPI) ***"
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
echo "*** Starting qurt slpi build ***"
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# Clean out the build artifacts
# source /home/build-env.sh
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# Push slpi image to voxl2
adb push build/modalai_voxl2_slpi/platforms/qurt/libpx4.so /usr/lib/rfsa/adsp
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# Push slpi image to voxl2
adb push build/modalai_voxl2_slpi/platforms/qurt/libpx4.so /usr/lib/rfsa/adsp
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
cd Tools/simulation/gazebo-classic/sitl_gazebo-classic/src
patch < ../../../../../boards/modalai/voxl2/gazebo-docker/patch/mavlink_interface.patch
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# Run this from the px4 project top level directory
docker run -it --rm -v `pwd`:/usr/local/workspace rb5-flight-px4-build-docker
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
################################################################################
# Copyright 2023 ModalAI Inc.
#
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
CONFIG_FILE="/etc/modalai/voxl-px4.conf"
+1 -1
View File
@@ -1,4 +1,4 @@
#!/usr/bin/env bash
#!/bin/bash
# Make sure that the SLPI DSP test signature is there otherwise px4 cannot run
# on the DSP
-2
View File
@@ -31,8 +31,6 @@ CONFIG_MODULES_EKF2=y
# CONFIG_EKF2_DRAG_FUSION is not set
# CONFIG_EKF2_EXTERNAL_VISION is not set
# CONFIG_EKF2_GNSS_YAW is not set
# CONFIG_EKF2_OPTICAL_FLOW is not set
# CONFIG_EKF2_RANGE_FINDER is not set
# CONFIG_EKF2_SIDESLIP is not set
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_LAND_DETECTOR=y
+4 -4
View File
@@ -52,10 +52,10 @@ endif()
# add code coverage build type
if (("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang") OR ("${CMAKE_CXX_COMPILER_ID}" MATCHES "AppleClang"))
set(CMAKE_C_FLAGS_COVERAGE "--coverage -ftest-coverage -fdiagnostics-absolute-paths ${PX4_DEBUG_OPT_LEVEL} -fprofile-arcs -fno-inline-functions"
set(CMAKE_C_FLAGS_COVERAGE "--coverage -ftest-coverage -fdiagnostics-absolute-paths -O0 -fprofile-arcs -fno-inline-functions"
CACHE STRING "Flags used by the C compiler during coverage builds" FORCE)
set(CMAKE_CXX_FLAGS_COVERAGE "--coverage -ftest-coverage -fdiagnostics-absolute-paths ${PX4_DEBUG_OPT_LEVEL} -fprofile-arcs -fno-inline-functions -fno-elide-constructors"
set(CMAKE_CXX_FLAGS_COVERAGE "--coverage -ftest-coverage -fdiagnostics-absolute-paths -O0-fprofile-arcs -fno-inline-functions -fno-elide-constructors"
CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE)
set(CMAKE_EXE_LINKER_FLAGS_COVERAGE "-ftest-coverage -fdiagnostics-absolute-paths"
@@ -63,11 +63,11 @@ if (("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang") OR ("${CMAKE_CXX_COMPILER_ID}"
else()
# Add -fprofile-abs-path for GCC v8/9 later on
set(CMAKE_C_FLAGS_COVERAGE "--coverage -ftest-coverage -fprofile-arcs ${PX4_DEBUG_OPT_LEVEL} -fno-default-inline -fno-inline"
set(CMAKE_C_FLAGS_COVERAGE "--coverage -ftest-coverage -fprofile-arcs -O0 -fno-default-inline -fno-inline"
CACHE STRING "Flags used by the C compiler during coverage builds" FORCE)
# Add -fprofile-abs-path for GCC v8/9 later on
set(CMAKE_CXX_FLAGS_COVERAGE "--coverage -ftest-coverage -fprofile-arcs ${PX4_DEBUG_OPT_LEVEL} -fno-default-inline -fno-inline -fno-elide-constructors"
set(CMAKE_CXX_FLAGS_COVERAGE "--coverage -ftest-coverage -fprofile-arcs -O0 -fno-default-inline -fno-inline -fno-elide-constructors"
CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE)
set(CMAKE_EXE_LINKER_FLAGS_COVERAGE "--coverage -ftest-coverage -lgcov"
+2 -11
View File
@@ -31,15 +31,6 @@
#
############################################################################
# Attach only matching test binaries to `test_results` when TESTFILTER is set.
# `ctest -R` filters execution only; without this helper the build still
# compiles every gtest target before running the filtered subset.
function(add_filtered_test_dependencies TESTNAME)
if(NOT TESTFILTER OR "${TESTNAME}" MATCHES "${TESTFILTER}")
add_dependencies(test_results ${TESTNAME})
endif()
endfunction()
#=============================================================================
#
# px4_add_unit_gtest
@@ -83,7 +74,7 @@ function(px4_add_unit_gtest)
WORKING_DIRECTORY ${PX4_BINARY_DIR})
# attach it to the unit test target
add_filtered_test_dependencies(${TESTNAME})
add_dependencies(test_results ${TESTNAME})
endif()
endfunction()
@@ -142,6 +133,6 @@ function(px4_add_functional_gtest)
COMMAND ${PX4_BINARY_DIR}/${TESTNAME})
# attach it to the unit test target
add_filtered_test_dependencies(${TESTNAME})
add_dependencies(test_results ${TESTNAME})
endif()
endfunction()
Binary file not shown.

After

Width:  |  Height:  |  Size: 8.8 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 73 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.2 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 118 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 25 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 30 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 18 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

-3
View File
@@ -566,8 +566,6 @@
- [DistanceSensorModeChangeRequest](msg_docs/DistanceSensorModeChangeRequest.md)
- [DronecanNodeStatus](msg_docs/DronecanNodeStatus.md)
- [Ekf2Timestamps](msg_docs/Ekf2Timestamps.md)
- [EscEepromRead](msg_docs/EscEepromRead.md)
- [EscEepromWrite](msg_docs/EscEepromWrite.md)
- [EscReport](msg_docs/EscReport.md)
- [EscStatus](msg_docs/EscStatus.md)
- [EstimatorAidSource1d](msg_docs/EstimatorAidSource1d.md)
@@ -758,7 +756,6 @@
- [VehicleLocalPositionV0](msg_docs/VehicleLocalPositionV0.md)
- [VehicleStatusV0](msg_docs/VehicleStatusV0.md)
- [VehicleStatusV1](msg_docs/VehicleStatusV1.md)
- [VehicleStatusV2](msg_docs/VehicleStatusV2.md)
- [MAVLink Messaging](mavlink/index.md)
- [Adding Messages](mavlink/adding_messages.md)
- [Streaming Messages](mavlink/streaming_messages.md)
+1 -1
View File
@@ -91,7 +91,7 @@ For FMUv6S, you need to route the PPS signal separately:
For ARK FMUv6X on the Jetson carrier board:
1. Connect your GNSS module using either the 10-pin or 6-pin GPS connector: [ARK PAB GPS1 Interface](../flight_controller/ark_pab.md#gps1)
1. Connect your GNSS module using either the 10-pin or 6-pin GPS connector: [ARK PAB GPS1 Interface](../flight_controller/ark_pab#gps1)
2. Connect the PPS signal to the **FMU_CAP** pin: [ARK PAB ADIO Interface](../flight_controller/ark_pab.md#adio)
## Verification
+1 -1
View File
@@ -160,7 +160,7 @@ After the bootloader has updated you can [Load PX4 Firmware](../config/firmware.
## FMUv2 Bootloader Update
If _QGroundControl_ installs the FMUv2 target (see console during installation), and you have a newer board, you may need to update the bootloader in order to access all the memory on your flight controller.
This example explains how you can use [QGC Bootloader Update](#qgc-bootloader-update-sys-bl-update) to update the bootloader.
This example explains how you can use [QGC Bootloader Update](qgc-bootloader-update-sys-bl-update) to update the bootloader.
::: info
Early FMUv2 [Pixhawk-series](../flight_controller/pixhawk_series.md#fmu_versions) flight controllers had a [hardware issue](../flight_controller/silicon_errata.md#fmuv2-pixhawk-silicon-errata) that restricted them to using 1MB of flash memory.
@@ -21557,49 +21557,6 @@ Maximum vertical drift speed to use GPS.
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.1 | 1.5 | | 0.2 | m/s |
### EKF2_RNGBC_CTRL (`INT32`) {#EKF2_RNGBC_CTRL}
Ranging beacon fusion control.
Enable/disable ranging beacon fusion.
**Values:**
- `0`: Disable ranging beacon fusion
- `1`: Enable ranging beacon fusion
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | | | | 0 | |
### EKF2_RNGBC_DELAY (`FLOAT`) {#EKF2_RNGBC_DELAY}
Ranging beacon measurement delay relative to IMU measurements.
| Reboot | minValue | maxValue | increment | default | unit |
| ------- | -------- | -------- | --------- | ------- | ---- |
| &check; | 0 | 1000 | | 0 | ms |
### EKF2_RNGBC_GATE (`FLOAT`) {#EKF2_RNGBC_GATE}
Gate size for ranging beacon fusion.
Sets the number of standard deviations used by the innovation consistency test.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 1.0 | | | 5.0 | SD |
### EKF2_RNGBC_NOISE (`FLOAT`) {#EKF2_RNGBC_NOISE}
Measurement noise for ranging beacon fusion.
Used to lower bound or replace the uncertainty included in the message
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.1 | 500.0 | | 30.0 | m |
### EKF2_RNG_A_HMAX (`FLOAT`) {#EKF2_RNG_A_HMAX}
Maximum height above ground allowed for conditional range aid mode.
@@ -40123,16 +40080,6 @@ This value is usually about few percent of the maximum thrust force.
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.0 | | 0.05 | 0.1 | Nm |
### SIH_RNGBC_NOISE (`FLOAT`) {#SIH_RNGBC_NOISE}
Ranging beacon measurement noise standard deviation.
Gaussian noise added to simulated ranging beacon measurements. Set to 0 to disable noise.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.0 | 100.0 | | 30.0 | m |
### SIH_T_MAX (`FLOAT`) {#SIH_T_MAX}
Max propeller thrust force.
+2 -2
View File
@@ -37,7 +37,7 @@ The wiring for CAN networks is the same for both DroneCAN and Cyphal/CAN (in fac
Devices within a network are connected in a _daisy-chain_ in any order (this differs from UARTs peripherals, where you attach just one component per port).
:::warning Don't connect each CAN peripheral to a separate CAN port!
Unlike UARTs, CAN peripherals are designed to be daisy chained, with additional ports such as `CAN2` used for [redundancy](#redundancy).
Unlike UARTs, CAN peripherals are designed to be daisy chained, with additional ports such as `CAN2` used for [redundancy](redundancy).
:::
At either end of the chain, a 120Ω termination resistor should be connected between the two data lines.
@@ -83,7 +83,7 @@ You only _need_ one CAN port to support an arbitrary number of CAN devices using
Don't connect each CAN peripheral to a separate CAN port!
:::
Generally you'll daisy all CAN peripherals off a single port, and if there is more than one CAN port, use the second one for [redundancy](#redundancy).
Generally you'll daisy all CAN peripherals off a single port, and if there is more than one CAN port, use the second one for [redundancy](redundancy).
If three are three ports, you might use the remaining network for devices that support another CAN protocol.
The documentation for your flight controller should indicate which ports are supported/enabled.
+7 -7
View File
@@ -76,13 +76,13 @@ You might have to adjust the per-motor pole count (`DSHOT_MOT_POL1``DSHOT_MOT
The following parameters should be set to enable and configure dynamic notch filters:
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------ |
| <a id="IMU_GYRO_DNF_EN"></a>[IMU_GYRO_DNF_EN](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_EN) | Enable IMU gyro dynamic notch filtering. `0`: ESC RPM, `1`: Onboard FFT. |
| <a id="IMU_GYRO_FFT_EN"></a>[IMU_GYRO_FFT_EN](../advanced_config/parameter_reference.md#IMU_GYRO_FFT_EN) | Enable onboard FFT (required if `IMU_GYRO_DNF_EN` is set to `1`). |
| <a id="IMU_GYRO_DNF_MIN"></a>[IMU_GYRO_DNF_MIN](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_MIN) | Minimum dynamic notch frequency in Hz. |
| <a id="IMU_GYRO_DNF_BW"></a>[IMU_GYRO_DNF_BW](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_BW) | Bandwidth for each notch filter in Hz. |
| <a id="IMU_GYRO_DNF_HMC"></a>[IMU_GYRO_DNF_HMC](../advanced_config/parameter_reference.md#IMU_GYRO_NF0_BW) | Number of harmonics to filter. |
| Parameter | Description |
| ------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------ |
| <a href="IMU_GYRO_DNF_EN"></a>[IMU_GYRO_DNF_EN](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_EN) | Enable IMU gyro dynamic notch filtering. `0`: ESC RPM, `1`: Onboard FFT. |
| <a href="IMU_GYRO_FFT_EN"></a>[IMU_GYRO_FFT_EN](../advanced_config/parameter_reference.md#IMU_GYRO_FFT_EN) | Enable onboard FFT (required if `IMU_GYRO_DNF_EN` is set to `1`). |
| <a href="IMU_GYRO_DNF_MIN"></a>[IMU_GYRO_DNF_MIN](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_MIN) | Minimum dynamic notch frequency in Hz. |
| <a href="IMU_GYRO_DNF_BW"></a>[IMU_GYRO_DNF_BW](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_BW) | Bandwidth for each notch filter in Hz. |
| <a href="IMU_GYRO_DNF_HMC"></a>[IMU_GYRO_DNF_HMC](../advanced_config/parameter_reference.md#IMU_GYRO_NF0_BW) | Number of harmonics to filter. |
### Low-pass Filter
+1 -1
View File
@@ -25,7 +25,7 @@ See the debug probe documentation for details on how to setup your debug connect
- [SEGGER J-Link](probe_jlink.md): commercial probe, no built-in serial console, requires adapter.
- [Black Magic Probe](probe_bmp.md): integrated GDB server and serial console, requires adapter.
- [STLink](probe_stlink.md): best value, integrated serial console, adapter must be soldered.
- [STLink](probe_stlink): best value, integrated serial console, adapter must be soldered.
We recommend using the J-Link with the Pixhawk Debug Adapter or the STLinkv3-MINIE with a soldered custom cable.
+9 -9
View File
@@ -5,7 +5,7 @@ PX4 runs on ARM Cortex-M microcontrollers, which contain dedicated hardware for
The SWD debug interface allows direct, low-level, hardware access to the microcontroller's processor and peripherals, so it does not depend on any software on the device.
Therefore it can be used to debug bootloaders and operating systems such as NuttX.
## Debug Signals {#debug-signals}
## Debug Signals
Four signals are required for debugging (in bold) while the rest is recommended.
@@ -29,7 +29,7 @@ They are usually not accessible and are typically only used to debug very specif
## Autopilot Debug Ports {#debug-ports}
Flight controllers commonly provide a single debug port that exposes both the [SWD Interface](#debug-signals) and [System Console](system_console.md).
Flight controllers commonly provide a single debug port that exposes both the [SWD Interface](#debug-signals) and [System Console](system_console).
The [Pixhawk Connector Standards](#pixhawk-standard-debug-ports) formalize the port that must be used in each FMU version.
However there are still many boards that use different pinouts or connectors, so we recommend you check the [documentation for your autopilot](../flight_controller/index.md) to confirm port location and pinout.
@@ -91,7 +91,7 @@ There FMU and Pixhawk versions are (only) consistent after FMUv5X.
### Pixhawk Debug Mini
The [Pixhawk Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) defines the _Pixhawk Debug Mini_, a _6-Pin SH Debug Port_ that provides access to both SWD pins and the [System Console](system_console.md).
The [Pixhawk Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) defines the _Pixhawk Debug Mini_, a _6-Pin SH Debug Port_ that provides access to both SWD pins and the [System Console](system_console).
This is used in FMUv4 and FMUv5.
@@ -122,7 +122,7 @@ You can connect to the debug port using a [cable like this one](https://www.digi
### Pixhawk Debug Full
The [Pixhawk Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) defines _Pixhawk Debug Full_, a _10-Pin SH Debug Port_ that provides access to both SWD pins and the [System Console](system_console.md).
The [Pixhawk Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) defines _Pixhawk Debug Full_, a _10-Pin SH Debug Port_ that provides access to both SWD pins and the [System Console](system_console).
This essentially moves the solder pads from beside the [Pixhawk Debug Mini](#pixhawk-debug-mini) into the connector, and also adds an SWO pin.
This port is specified for use in FMUv5x, FMUv6, FMUv6x.
@@ -154,14 +154,14 @@ You can connect to the debug port using a [cable like this one](https://www.digi
## Debug Probes for PX4 Hardware {#debug-probes}
Flight controllers commonly provide a [single debug port](#autopilot-debug-ports) that exposes both the [SWD Interface](#debug-signals) and [System Console](system_console.md).
Flight controllers commonly provide a [single debug port](#autopilot-debug-ports) that exposes both the [SWD Interface](#debug-signals) and [System Console](system_console).
There are several debug probes that are tested and supported for connecting to one or both of these interfaces:
- [SEGGER J-Link](../debug/probe_jlink.md): commercial probe, no built-in serial console, requires adapter.
- [Black Magic Probe](../debug/probe_bmp.md): integrated GDB server and serial console, requires adapter.
- [STLink](../debug/probe_stlink.md): best value, integrated serial console, adapter must be soldered.
- [MCU-Link](../debug/probe_mculink.md): best value, integrated serial console, requires adapter.
- [STLink](../debug/probe_stlink): best value, integrated serial console, adapter must be soldered.
- [MCU-Link](../debug/probe_mculink): best value, integrated serial console, requires adapter.
An adapter to connect to the debug port may come with your flight controller or debug probe.
Other options are given below.
@@ -199,7 +199,7 @@ Probes that are known to come with connectors are listed below:
### Board-specific Adapters
Some manufacturers provide cables to make it easy to connect the SWD interface and [System Console](../debug/system_console.md).
Some manufacturers provide cables to make it easy to connect the SWD interface and [System Console](../debug/system_console).
- [CUAV V5nano](../flight_controller/cuav_v5_nano.md#debug_port) and [CUAV V5+](../flight_controller/cuav_v5_plus.md#debug-port) include this debug cable:
@@ -213,7 +213,7 @@ You can also create custom cables for connecting to different boards or probes:
- Connect the VREF pin, if supported by the debug probe.
- Connect the remaining pins, if present.
See the [STLinkv3-MINIE](probe_stlink.md) for a guide on how to solder a custom cable.
See the [STLinkv3-MINIE](probe_stlink) for a guide on how to solder a custom cable.
:::tip
Where possible, we highly recommend that you create or obtain an adapter board rather than custom cables for connecting to SWD/JTAG debuggers and computers.
+1 -1
View File
@@ -1,7 +1,7 @@
# Arch Linux Development Environment
:::warning
This development environment is [community supported and maintained](../advanced/community_supported_dev_env.md).
This development environment is [community supported and maintained](../advanced/community_supported_dev_env).
It may or may not work with current versions of PX4.
See [Toolchain Installation](../dev_setup/dev_env.md) for information about the environments and tools supported by the core development team.
+1 -1
View File
@@ -84,7 +84,7 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if
- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
- If using [Moving Baseline & GPS Heading](#setting-up-moving-baseline-gps-heading), set [SENS_GPS_PRIME](../advanced_config/parameter_reference.md#SENS_GPS_PRIME) to the CAN node ID of the _Moving Base_ module. The moving base is preferred because the rover receiver in a moving baseline configuration can experience degraded navigation rate and increased data latency when corrections are intermittent.
- If using [Moving Baseline & GPS Heading](#setting-up-moving-baseline--gps-heading), set [SENS_GPS_PRIME](../advanced_config/parameter_reference.md#SENS_GPS_PRIME) to the CAN node ID of the _Moving Base_ module. The moving base is preferred because the rover receiver in a moving baseline configuration can experience degraded navigation rate and increased data latency when corrections are intermittent.
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
- The parameters [SENS_GPS0_OFFX](../advanced_config/parameter_reference.md#SENS_GPS0_OFFX), [SENS_GPS0_OFFY](../advanced_config/parameter_reference.md#SENS_GPS0_OFFY) and [SENS_GPS0_OFFZ](../advanced_config/parameter_reference.md#SENS_GPS0_OFFZ) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity.
+1 -1
View File
@@ -5,7 +5,7 @@ PX4 supports DroneCAN compliant ESCs.
## Supported ESC
:::info
[Supported ESCs](../peripherals/esc_motors.md#supported-esc) in _ESCs & Motors_ may include additional devices that are not listed below.
[Supported ESCs](../peripherals/esc_motors#supported-esc) in _ESCs & Motors_ may include additional devices that are not listed below.
:::
The following articles have specific hardware/firmware information:
+1 -1
View File
@@ -5,7 +5,7 @@ PX4 does not manufacture this (or any) autopilot.
Contact the [manufacturer](https://arkelectron.com/contact-us/) for hardware support or compliance issues.
:::
The USA-built [ARKV6X](https://arkelectron.gitbook.io/ark-documentation/flight-controllers/arkv6x) flight controller is based on the [FMUV6X and Pixhawk Autopilot Bus open source standards](https://github.com/pixhawk/Pixhawk-Standards).
The USA-built [ARKV6X](<(https://arkelectron.gitbook.io/ark-documentation/flight-controllers/arkv6x)>) flight controller is based on the [FMUV6X and Pixhawk Autopilot Bus open source standards](https://github.com/pixhawk/Pixhawk-Standards).
With triple synced IMUs, data averaging, voting, and filtering is possible.
The Pixhawk Autopilot Bus (PAB) form factor enables the ARKV6X to be used on any [PAB-compatible carrier board](../flight_controller/pixhawk_autopilot_bus.md), such as the [ARK Pixhawk Autopilot Bus Carrier](../flight_controller/ark_pab.md).
+8 -8
View File
@@ -13,14 +13,14 @@ The mission is typically created and uploaded with a Ground Control Station (GCS
The following commands can be used in missions at time of writing (PX4 v1.16):
| QGC mission item | Command | Description |
| ------------------- | ------------------------------------------- | ------------------------------------------------- |
| Mission start | [MAV_CMD_MISSION_START] | Starts the mission. |
| Waypoint | [MAV_CMD_NAV_WAYPOINT] | Navigate to waypoint. |
| Return to launch | [MAV_CMD_NAV_RETURN_TO_LAUNCH] | Return to the launch location. |
| Change speed | [MAV_CMD_DO_CHANGE_SPEED] | Change the speed setpoint |
| Set launch location | [MAV_CMD_DO_SET_HOME] | Changes launch location to specified coordinates. |
| Jump to item (all) | [MAV_CMD_DO_JUMP] (and other jump commands) | Jump to specified mission item. |
| QGC mission item | Command | Description |
| ------------------- | ------------------------------------------------------------ | ------------------------------------------------- |
| Mission start | [MAV_CMD_MISSION_START](MAV_CMD_MISSION_START) | Starts the mission. |
| Waypoint | [MAV_CMD_NAV_WAYPOINT](MAV_CMD_NAV_WAYPOINT) | Navigate to waypoint. |
| Return to launch | [MAV_CMD_NAV_RETURN_TO_LAUNCH][MAV_CMD_NAV_RETURN_TO_LAUNCH] | Return to the launch location. |
| Change speed | [MAV_CMD_DO_CHANGE_SPEED][MAV_CMD_DO_CHANGE_SPEED] | Change the speed setpoint |
| Set launch location | [MAV_CMD_DO_SET_HOME](MAV_CMD_DO_SET_HOME) | Changes launch location to specified coordinates. |
| Jump to item (all) | [MAV_CMD_DO_JUMP][MAV_CMD_DO_JUMP] (and other jump commands) | Jump to specified mission item. |
[MAV_CMD_MISSION_START]: https://mavlink.io/en/messages/common.html#MAV_CMD_MISSION_START
[MAV_CMD_NAV_WAYPOINT]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT
+1 -1
View File
@@ -68,7 +68,7 @@ The following manual and assisted modes are currently supported on BlueROV2 Heav
## Joystick Stick Mode
BlueROV2 supports two joystick mappings for manual control, selected using the
[UUV_STICK_MODE](../advanced_config/parameter_reference.md#UUV_STICK_MODE) parameter.
[UUV_STICK_MODE](../advanced_config/parameter_reference.md#uuv_stick_mode) parameter.
By default, `UUV_STICK_MODE` is set to `0`, which enables the UUV stick mapping intended for vectored underwater vehicles.
+45 -47
View File
@@ -14,52 +14,50 @@ This section describes the VTOL types and configurations supported by PX4, and p
## VTOL Types
PX4 supports the three most important/main VTOL types: [Standard VTOL](standardvtol.md), [Tiltrotor](tiltrotor.md), and [Tailsitter](tailsitter.md).
PX4 supports the three most important/main VTOL types.
:::: tabs
::: tab Standard VTOL
Separate rotors/flight controls for multicopter and forward flight.
Takes off and lands on belly.
![Vertical Technologies: Deltaquad](../../assets/airframes/vtol/vertical_technologies_deltaquad/hero_small.png)
- Additional weight from separate hover/forward flight propulsion systems
- Easiest to control due to dedicated hover/forward flight actuators
- Can hover
- Fuel engines can be used for forward flight propulsion
:::
::: tab Tailsitter
Rotors permanently in fixed-wing position.
Takes off and lands on tail. Whole vehicle tilts forward to enter forward flight.
![wingtraone](../../assets/airframes/vtol/wingtraone/hero.jpg)
- Simple and robust
- Minimal set of actuators
- Can be hard to control, particularly in wind
- Tradeoff between efficiency in hover and forward flight, as same actuators are used
:::
::: tab Tiltrotor
Rotors swivel 90 degrees to transition from multicopter to forward flight orientation.
Takes off and lands on belly.
![Eflight Confvergence](../../assets/airframes/vtol/eflite_convergence_pixfalcon/hero.jpg)
- Additional actuators for motor tilts
- Mechanically complex tilting mechanism
- Easier to control in hover than tailsitters due to more control authority
:::
::::
<div class="grid_wrapper three_column">
<div class="grid_item">
<div class="grid_item_heading"><a href="tailsitter.html" title="Tailsitter"><big>Tailsitter</big></a></div>
<div class="grid_text">
Rotors permanently in fixed-wing position.
Takes off and lands on tail. Whole vehicle tilts forward to enter forward flight.
<img src="../../assets/airframes/vtol/wingtraone/hero.jpg" title="wingtraone" />
<ul>
<li>Simple and robust</li>
<li>Minimal set of actuators</li>
<li>Can be hard to control, particularly in wind</li>
<li>Tradeoff between efficiency in hover and forward flight, as same actuators are used</li>
</ul>
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><a href="tiltrotor.html" title="Tiltrotor"><big>Tiltrotor</big></a></div>
Rotors swivel 90 degrees to transition from multicopter to forward flight orientation.
Takes off and lands on belly.
<div class="grid_text">
<img src="../../assets/airframes/vtol/eflite_convergence_pixfalcon/hero.jpg" title="Eflight Confvergence" />
<ul>
<li>Additional actuators for motor tilts</li>
<li>Mechanically complex tilting mechanism</li>
<li>Easier to control in hover than tailsitters due to more control authority</li>
</ul>
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><a href="standardvtol.html" title="Standard VTOL"><big>Standard VTOL</big></a></div>
<div class="grid_text">
Separate rotors/flight controls for multicopter and forward flight. Takes off and lands on belly.
<img src="../../assets/airframes/vtol/vertical_technologies_deltaquad/hero_small.png" title="Vertical Technologies: Deltaquad" />
<ul>
<li>Additional weight from separate hover/forward flight propulsion systems</li>
<li>Easiest to control due to dedicated hover/forward flight actuators</li>
<li>Can hover</li>
<li>Fuel engines for forward flight propulsion can be used</li>
</ul>
</div>
</div>
</div>
In general, as mechanical complexity increases the vehicles are easier to fly, but the cost and weight increase.
Each type has advantages and disadvantages, and there are successful commercial ventures based on all of them.
@@ -127,7 +125,7 @@ VTOL Control & Airspeed Fault Detection (PX4 Developer Summit 2019)
<!-- 20190704 -->
### Tailsitter {#tailsitter_video}
### Tailsitter
[UAV Works VALAQ Patrol Tailsitter](https://www.valaqpatrol.com/valaq_patrol_technical_data/)
@@ -137,7 +135,7 @@ VTOL Control & Airspeed Fault Detection (PX4 Developer Summit 2019)
<lite-youtube videoid="acG0aTuf3f8" title="PX4 VTOL - Call for Testpilots"/>
### Tiltrotor {#tiltrotor_video}
### Tiltrotor
[Convergence Tiltrotor](../frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md)
+32 -33
View File
@@ -88,36 +88,35 @@ This section contains videos that are specific to Tailsitter VTOL (videos that a
## Gallery
:::: tabs
::: tab WingtraOne
[WingtraOne](https://wingtra.com/mapping-drone-fast-accurate-surveying/)
![Wingtra: WingtraOne VTOL Duo Tailsitter](../../assets/airframes/vtol/wingtraone/hero.jpg)
:::
::: tab Skypull
[Skypull](https://www.skypull.technology/)
![Skypull SP-1 VTOL QuadTailsitter](../../assets/airframes/vtol/skypull/skypull_sp1.jpg)
:::
::: tab TBS Caipiroshka
[TBS Caipiroshka](../frames_vtol/vtol_tailsitter_caipiroshka_pixracer.md)
![TBS Caipiroshka](../../assets/airframes/vtol/caipiroshka/caipiroshka.jpg)
:::
::: tab Woshark
[Woshark](http://uav-cas.ac.cn/WOSHARK/)
![Woshark](../../assets/airframes/vtol/xdwgood_ax1800/hero.jpg)
:::
::: tab VALAQ Patrol Tailsitter
[UAV Works VALAQ Patrol Tailsitter](https://www.valaqpatrol.com/valaq_patrol_technical_data/)
!["UAV Works VALAQ Patrol Tailsitte](../../assets/airframes/vtol/uav_works_valaq_patrol/hero.jpg)
:::
::::
<div class="grid_wrapper three_column">
<div class="grid_item">
<div class="grid_item_heading"><big><a href="https://wingtra.com/mapping-drone-fast-accurate-surveying/">WingtraOne</a></big></div>
<div class="grid_text">
<img src="../../assets/airframes/vtol/wingtraone/hero.jpg" title="Wingtra: WingtraOne VTOL Duo Tailsitter" alt="wingtraone" />
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><big><a href="https://www.skypull.technology/">Skypull</a></big></div>
<div class="grid_text">
<img title="Skypull SP-1 VTOL QuadTailsitter" src="../../assets/airframes/vtol/skypull/skypull_sp1.jpg" />
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><big><a href="../frames_vtol/vtol_tailsitter_caipiroshka_pixracer.html">TBS Caipiroshka</a></big></div>
<div class="grid_text">
<img title="TBS Caipiroshka" src="../../assets/airframes/vtol/caipiroshka/caipiroshka.jpg" />
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><big><a href="http://uav-cas.ac.cn/WOSHARK/">Woshark</a></big></div>
<div class="grid_text">
<img title="Woshark" src="../../assets/airframes/vtol/xdwgood_ax1800/hero.jpg" />
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><big><a href="https://www.valaqpatrol.com/valaq_patrol_technical_data/">UAV Works VALAQ Patrol Tailsitter</a></big></div>
<div class="grid_text">
<img title="UAV Works VALAQ Patrol Tailsitter" src="../../assets/airframes/vtol/uav_works_valaq_patrol/hero.jpg" />
</div>
</div>
</div>
+2 -2
View File
@@ -159,7 +159,7 @@ Runs after the package is installed. Common tasks:
- Board-specific setup (e.g., DSP signature generation)
```bash
#!/usr/bin/env bash
#!/bin/bash
set -e
# Create px4-* symlinks
@@ -185,7 +185,7 @@ fi
Runs before the package is removed:
```bash
#!/usr/bin/env bash
#!/bin/bash
set -e
# Stop the service
-16
View File
@@ -70,19 +70,3 @@ The command line and GUI interfaces are shown below.
### menuconfig Command Line Interface
![menuconfig command line interface](../../assets/hardware/kconfig-guiconfig.png)
## Fortified Toolchain Compatibility
Some toolchains define `_FORTIFY_SOURCE` by default. Those toolchains generally require some optimization, which means PX4 configurations that use `-O0` may fail.
PX4 keeps the default debug optimization unchanged unless you explicitly opt in. To switch `PX4_DEBUG_OPT_LEVEL` from `-O0` to `-Og`, enable:
- `Toolchain > Fortified toolchain support`
This is the Kconfig symbol:
```sh
CONFIG_BOARD_SUPPORT_FORTIFIED_TOOLCHAIN=y
```
You can set it either in `boardconfig`/`boardguiconfig` or directly in your board's `*.px4board` file.
+92 -34
View File
@@ -12,25 +12,37 @@ When signing is enabled, PX4 appends a 13-byte [signature](https://mavlink.io/en
Incoming messages are checked against the shared secret key, and unsigned or incorrectly signed messages are rejected (with [exceptions for safety-critical messages](#unsigned-message-allowlist)).
The signing implementation is built into the MAVLink module and is always available no special build flags are required.
It is enabled and disabled at runtime through the [MAV_SIGN_CFG](../advanced_config/parameter_reference.md#MAV_SIGN_CFG) parameter.
The signing implementation is built into the MAVLink module and is always available, with no special build flags required.
The key is stored in an SD card:
- **No key on SD card**:
Signing is disabled.
All messages are sent unsigned and all incoming messages are accepted.
- **Valid key on SD card**:
Signing is active on **all links** (including USB).
Outgoing messages are signed.
Incoming messages must be signed (with [exceptions](#unsigned-message-allowlist)).
## Enable/Disable Signing
The [MAV_SIGN_CFG](../advanced_config/parameter_reference.md#MAV_SIGN_CFG) parameter controls whether signing is active:
Signing is controlled using the standard MAVLink [SETUP_SIGNING](https://mavlink.io/en/messages/common.html#SETUP_SIGNING) message (as per the [MAVLink signing specification](https://mavlink.io/en/guide/message_signing.html)):
| Value | Mode | Description |
| ----- | ------------------ | ------------------------------------------------------------------------------------------------------ |
| 0 | Disabled (default) | No signing. All messages are accepted regardless of signature. |
| 1 | Non-USB | Signing is enabled on all links **except** USB serial connections. USB links accept unsigned messages. |
| 2 | Always | Signing is enforced on all links, including USB. |
- To **enable** signing, send a `SETUP_SIGNING` message with a valid key on any link when no key is currently provisioned (see [Key Provisioning](#key-provisioning)).
- To **disable** signing via MAVLink, send a `SETUP_SIGNING` message with an all-zero key and timestamp.
This message **must be signed with the current active key**.
An unsigned blank-key message is rejected.
- To **change** the signing key, send a `SETUP_SIGNING` message with the new key on any link.
When signing is already active, the message must be signed with the current key.
::: warning
Setting `MAV_SIGN_CFG` alone does not enable signing — a secret key must also be present (see [Key Provisioning](#key-provisioning) below).
If no key has been set (or the key is all zeros with a zero timestamp), all messages are accepted regardless of this parameter.
Signing key changes (enable, disable, or rotate) are **rejected while the vehicle is armed**.
The vehicle must be disarmed before signing configuration can be changed.
:::
To **disable** signing, set `MAV_SIGN_CFG` to zero.
::: tip
If the signing key is lost, you can still disable signing if you have physical access to the vehicle.
Either delete the key file (`/mavlink/mavlink-signing-key.bin`) from the SD card and reboot, or remove the SD card entirely.
:::
## Key Provisioning
@@ -40,11 +52,13 @@ This message contains:
- A 32-byte secret key
- A 64-bit initial timestamp
::: warning
For security, PX4 only accepts `SETUP_SIGNING` messages received on a **USB** connection.
The message is silently ignored on all other link types (telemetry radios, network, and so on).
This ensures that an attacker cannot remotely change the signing key.
:::
PX4 accepts `SETUP_SIGNING` on **any link** (USB, telemetry radio, network, and so on).
When signing is **not active** (no key provisioned), the first `SETUP_SIGNING` with a valid key enables signing.
When signing is **already active**, key changes (including disabling) require that the `SETUP_SIGNING` message is signed with the current key.
Note that `SETUP_SIGNING` is rejected while the vehicle is armed (disarm before provisioning or changing keys).
As per the MAVLink specification, `SETUP_SIGNING` is never forwarded to other links.
## Key Storage
@@ -64,7 +78,7 @@ The file is a 40-byte binary file:
The file is created with mode `0600` (owner read/write only), and the containing `/mavlink/` directory is created with mode `0700` (owner only).
On startup, PX4 reads the key from this file.
If the file exists and contains a non-zero key or timestamp, signing is initialized automatically.
If the file exists and contains a non-zero key or timestamp, signing is activated automatically.
::: info
The timestamp in the file is set when `SETUP_SIGNING` is received.
@@ -73,7 +87,7 @@ A graceful shutdown also writes the current timestamp back, but in practice most
::: info
Storage of the key on the SD card means that signing can be disabled by removing the card.
Note that this requires physical access to the vehicle, and therefore provides the same level of security as allowing signing to be modified via the USB channel.
Note that this requires physical access to the vehicle.
:::
## How It Works
@@ -82,45 +96,89 @@ Note that this requires physical access to the vehicle, and therefore provides t
1. The MAVLink module calls `MavlinkSignControl::start()` during startup.
2. The `/mavlink/` directory is created if it doesn't exist.
3. The `mavlink-signing-key.bin` file is opened (or created empty).
4. If a valid key is found (non-zero key or timestamp), signing is marked as initialized.
5. The `accept_unsigned` callback is registered with the MAVLink library.
3. The `mavlink-signing-key.bin` file is opened if it exists.
4. If a valid key is found (non-zero key or timestamp), signing is activated: the signing struct is wired into the MAVLink library and outgoing messages are signed.
5. If no valid key is found, the signing struct is left disconnected, and the MAVLink library operates with zero signing overhead.
### Outgoing Messages
When signing is initialized, the `MAVLINK_SIGNING_FLAG_SIGN_OUTGOING` flag is set, which causes the MAVLink library to automatically append a [SHA-256 based signature](https://mavlink.io/en/guide/message_signing.html#signature) to every outgoing MAVLink 2 message.
When signing is active (valid key present), the `MAVLINK_SIGNING_FLAG_SIGN_OUTGOING` flag is set, which causes the MAVLink library to automatically append a [SHA-256 based signature](https://mavlink.io/en/guide/message_signing.html#signature) to every outgoing MAVLink 2 message.
When no key is present, signing is completely bypassed with no CPU or bandwidth overhead.
### Incoming Messages
For each incoming message, the MAVLink library checks whether a valid signature is present.
If the message is unsigned or has an invalid signature, the library calls the `accept_unsigned` callback, which decides whether to accept or reject the message based on:
1. **Signing not initialized** If no key has been loaded, all messages are accepted.
2. **Allowlisted message** Certain [safety-critical messages](#unsigned-message-allowlist) are always accepted.
3. **Sign mode** — The `MAV_SIGN_CFG` parameter determines behavior:
- Mode 0 (disabled): All unsigned messages are accepted.
- Mode 1 (non-USB): Unsigned messages are accepted only on USB links.
- Mode 2 (always): Unsigned messages are rejected on all links.
1. **Signing not active**: If no key has been loaded, all messages are accepted.
2. **Allowlisted message**: Certain [safety-critical messages](#unsigned-message-allowlist) are always accepted.
## Unsigned Message Allowlist
The following messages are **always** accepted unsigned, regardless of the signing mode.
The following messages are **always** accepted unsigned, regardless of the signing state.
These are safety-critical messages that may originate from systems that don't support signing:
| Message | ID | Reason |
| ----------------------------------------------------------------------- | --- | -------------------------------------------------------- |
| [HEARTBEAT](https://mavlink.io/en/messages/common.html#HEARTBEAT) | 0 | System discovery and liveness detection |
| [RADIO_STATUS](https://mavlink.io/en/messages/common.html#RADIO_STATUS) | 109 | Radio link status from SiK radios and other radio modems |
| [ADSB_VEHICLE](https://mavlink.io/en/messages/common.html#ADSB_VEHICLE) | 246 | ADS-B traffic information for collision avoidance |
| [COLLISION](https://mavlink.io/en/messages/common.html#COLLISION) | 247 | Collision threat warnings |
## Security Considerations
- **Physical access required for key setup**: The `SETUP_SIGNING` message is only accepted over USB, so an attacker must have physical access to the vehicle to provision or change the key.
### Signing is enforced on all links
When signing is active, **all links require signed messages**.
This means:
- An attacker cannot send unsigned commands on any link.
- Changing or disabling the key requires sending a `SETUP_SIGNING` message **signed with the current key**.
- Signing can be disabled via MAVLink by sending a signed `SETUP_SIGNING` with an all-zero key.
### Armed guard
`SETUP_SIGNING` is rejected while the vehicle is armed.
This prevents the signing configuration from being changed during flight, whether by accident or by an attacker who has obtained the key.
### Lost key recovery
If the signing key is lost on the GCS side and no device has the current key:
- **Remove the SD card** and delete `/mavlink/mavlink-signing-key.bin`, then reboot.
- **Reflash via SWD/JTAG** if the SD card is not accessible.
::: warning
There is no software-only recovery path for a lost key.
This is intentional: any MAVLink-based recovery mechanism would also be available to an attacker.
Physical access to the SD card or debug port is required.
:::
### Other considerations
- **Initial key provisioning**: When no key is provisioned, `SETUP_SIGNING` is accepted unsigned on any link.
Once a key is active, subsequent changes require a signed message.
Provision the initial key over a trusted connection, such as USB.
- **Key not exposed via parameters**: The secret key is stored in a separate file on the SD card, not as a MAVLink parameter, so it cannot be read back through the parameter protocol.
- **SD card access**: Anyone with physical access to the SD card can read or modify the `mavlink-signing-key.bin` file, or just remove the card.
- **SD card access**: Anyone with physical access to the SD card can read or modify the `mavlink-signing-key.bin` file, or remove the card entirely to disable signing.
Ensure physical security of the vehicle if signing is used as a security control.
- **Replay protection**: The MAVLink signing protocol includes a timestamp that prevents replay attacks.
The on-disk timestamp is updated when a new key is provisioned via `SETUP_SIGNING`.
A graceful shutdown also persists the current timestamp, but since most vehicles are powered off by pulling the battery, the timestamp will typically reset to the value from the last key provisioning on reboot.
- **No encryption**: Message signing provides authentication and integrity, but messages are still sent in plaintext.
An eavesdropper can read message contents but cannot forge or modify them without the key.
A graceful shutdown also persists the current timestamp, but since most vehicles are powered off by pulling the battery, the on-disk timestamp will typically remain at the value from the last key provisioning on reboot.
- **No encryption**: Message signing provides **authentication and integrity only**.
Messages are still sent in plaintext.
An eavesdropper can read all message contents (telemetry, commands, parameters, missions) but cannot forge or modify them without the key.
- **Allowlisted messages bypass signing**: A small set of [safety-critical messages](#unsigned-message-allowlist) are always accepted unsigned.
An attacker can spoof these specific messages (e.g. fake `ADSB_VEHICLE` traffic) even when signing is active.
### What signing does NOT protect against
| Attack | Why |
| ----------------------------------------------------- | ------------------------------------------------------- |
| Eavesdropping | Messages are not encrypted |
| SD card extraction | Key file is readable by anyone with physical access |
| Spoofed `HEARTBEAT`/`RADIO_STATUS`/`ADSB`/`COLLISION` | These are allowlisted unsigned |
| Lost key without SD card access | Requires SWD reflash |
| Key rotation | No automatic mechanism; manual re-provisioning required |
| In-flight key changes | `SETUP_SIGNING` rejected while armed |
+33 -13
View File
@@ -37,22 +37,32 @@ See [Message Signing](message_signing.md) for full details.
Steps:
1. Connect the vehicle via **USB** (key provisioning only works over USB).
2. Provision a 32-byte secret key using the [SETUP_SIGNING](https://mavlink.io/en/messages/common.html#SETUP_SIGNING) message.
3. Set [MAV_SIGN_CFG](../advanced_config/parameter_reference.md#MAV_SIGN_CFG) to **1** (signing enabled on all links except USB) or **2** (signing on all links including USB).
4. Provision the same key on all ground control stations and companion computers that need to communicate with the vehicle.
5. Verify that unsigned messages from unknown sources are rejected.
1. Connect to the vehicle over a **trusted link** (USB or other secure connection).
2. Provision a 32-byte secret key using the [SETUP_SIGNING](https://mavlink.io/en/messages/common.html#SETUP_SIGNING) message. This works on any link, but use a trusted one for initial provisioning.
3. Provision the same key on all ground control stations and companion computers that need to communicate with the vehicle.
4. Verify that unsigned messages from unknown sources are rejected.
::: info
`MAV_SIGN_CFG=1` is recommended for most deployments.
This enforces signing on telemetry radios and network links while allowing unsigned access over USB for maintenance.
USB connections require physical access to the vehicle, which provides equivalent security to physical key access.
Once a key is provisioned, signing is enforced automatically on **all links** (including USB).
Changing or disabling the key requires a signed `SETUP_SIGNING` message.
Signing changes are rejected while the vehicle is armed.
Signing can also be disabled by physically removing the key file from the SD card.
:::
### 2. Secure Physical Access
- Protect access to the SD card. The signing key is stored at `/mavlink/mavlink-signing-key.bin` and can be read or removed by anyone with physical access.
- USB connections bypass signing when `MAV_SIGN_CFG=1`. Ensure USB ports are not exposed in deployed configurations.
- **SD card**: The signing key is stored at `/mavlink/mavlink-signing-key.bin`.
Anyone with physical access to the SD card can read, modify, or remove the key file.
- **USB ports**: USB follows the same signing rules as all other links.
When signing is active, USB requires signed messages.
- **Debug ports (SWD/JTAG)**: If exposed, [Debug Ports](../debug/swd_debug.md) allow full firmware reflash and bypass all software security.
Not all vehicles expose debug connectors.
::: warning
Signing protects all MAVLink links.
The primary physical attack surface is the SD card (key file extraction or deletion).
If your threat model includes physical access, secure the SD card slot and debug ports.
:::
### 3. Secure Network Links
@@ -63,9 +73,19 @@ USB connections require physical access to the vehicle, which provides equivalen
### 4. Understand the Limitations
- **No encryption**: Message signing provides authentication and integrity, but messages are sent in plaintext. An eavesdropper can read telemetry and commands but cannot forge them.
- **Allowlisted messages**: A small set of [safety-critical messages](message_signing.md#unsigned-message-allowlist) (RADIO_STATUS, ADSB_VEHICLE, COLLISION) are always accepted unsigned.
- **Key management**: There is no automatic key rotation. Keys must be reprovisioned manually via USB if compromised.
- **No encryption**:
Message signing provides authentication and integrity, but messages are sent in plaintext.
An eavesdropper can read telemetry and commands but cannot forge them.
- **Allowlisted messages**:
A small set of [safety-critical messages](message_signing.md#unsigned-message-allowlist) (`HEARTBEAT`, `RADIO_STATUS`, `ADSB_VEHICLE`, `COLLISION`) are always accepted unsigned on all links.
An attacker could spoof these specific messages.
- **Key management**:
There is no automatic key rotation.
Keys must be reprovisioned manually via a signed `SETUP_SIGNING` message.
- **Lost key recovery**:
If the signing key is lost on all GCS devices, the only recovery is physical: remove the SD card and delete the key file, or reflash via SWD/JTAG.
There is no software-only recovery path.
See [Message Signing: Lost Key Recovery](message_signing.md#lost-key-recovery) for details.
## Integrator Responsibility
+197 -198
View File
@@ -95,206 +95,205 @@ They are not build into the module, and hence are neither published or subscribe
::: details See messages
- [HomePositionV0](../msg_docs/HomePositionV0.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [GainCompression](../msg_docs/GainCompression.md)
- [VehicleStatusV2](../msg_docs/VehicleStatusV2.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [EscEepromRead](../msg_docs/EscEepromRead.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [LedControl](../msg_docs/LedControl.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [SensorTemp](../msg_docs/SensorTemp.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [Mission](../msg_docs/Mission.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [RaptorStatus](../msg_docs/RaptorStatus.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [DeviceInformation](../msg_docs/DeviceInformation.md)
- [Gripper](../msg_docs/Gripper.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [EscReport](../msg_docs/EscReport.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [Event](../msg_docs/Event.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [RaptorInput](../msg_docs/RaptorInput.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [EventV0](../msg_docs/EventV0.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [Ping](../msg_docs/Ping.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [EscEepromWrite](../msg_docs/EscEepromWrite.md)
- [BatteryInfo](../msg_docs/BatteryInfo.md)
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [InputRc](../msg_docs/InputRc.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [Vtx](../msg_docs/Vtx.md)
- [RangingBeacon](../msg_docs/RangingBeacon.md)
- [NeuralControl](../msg_docs/NeuralControl.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [Rpm](../msg_docs/Rpm.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [Mission](../msg_docs/Mission.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [BatteryInfo](../msg_docs/BatteryInfo.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [LedControl](../msg_docs/LedControl.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [EventV0](../msg_docs/EventV0.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
- [VehicleStatusV2](../msg_docs/VehicleStatusV2.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [InputRc](../msg_docs/InputRc.md)
- [Event](../msg_docs/Event.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [RaptorInput](../msg_docs/RaptorInput.md)
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [RaptorStatus](../msg_docs/RaptorStatus.md)
- [Ping](../msg_docs/Ping.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [EscEepromRead](../msg_docs/EscEepromRead.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [HomePositionV0](../msg_docs/HomePositionV0.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [Gripper](../msg_docs/Gripper.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [GainCompression](../msg_docs/GainCompression.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [Rpm](../msg_docs/Rpm.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [EscReport](../msg_docs/EscReport.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [NeuralControl](../msg_docs/NeuralControl.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [EscEepromWrite](../msg_docs/EscEepromWrite.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [DeviceInformation](../msg_docs/DeviceInformation.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [SensorTemp](../msg_docs/SensorTemp.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [Vtx](../msg_docs/Vtx.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
:::
+2 -2
View File
@@ -4,7 +4,7 @@ pageClass: is-wide-page
# EstimatorAidSource1d (UORB message)
**TOPICS:** estimator_aid_src_baro_hgt estimator_aid_src_ev_hgt estimator_aid_src_gnss_hgt estimator_aid_src_rng_hgt estimator_aid_src_ranging_beacon estimator_aid_src_airspeed estimator_aid_src_sideslip estimator_aid_src_fake_hgt estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw
**TOPICS:** estimator_aid_src_baro_hgt estimator_aid_src_ev_hgt estimator_aid_src_gnss_hgt estimator_aid_src_rng_hgt estimator_aid_src_airspeed estimator_aid_src_sideslip estimator_aid_src_fake_hgt estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw
## Fields
@@ -55,7 +55,7 @@ float32 test_ratio_filtered # signed filtered test ratio
bool innovation_rejected # true if the observation has been rejected
bool fused # true if the sample was successfully fused
# TOPICS estimator_aid_src_baro_hgt estimator_aid_src_ev_hgt estimator_aid_src_gnss_hgt estimator_aid_src_rng_hgt estimator_aid_src_ranging_beacon
# TOPICS estimator_aid_src_baro_hgt estimator_aid_src_ev_hgt estimator_aid_src_gnss_hgt estimator_aid_src_rng_hgt
# TOPICS estimator_aid_src_airspeed estimator_aid_src_sideslip
# TOPICS estimator_aid_src_fake_hgt
# TOPICS estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw
-72
View File
@@ -1,72 +0,0 @@
---
pageClass: is-wide-page
---
# RangingBeacon (UORB message)
Ranging beacon measurement data (e.g. LoRa, UWB).
**TOPICS:** ranging_beacon
## Fields
| Name | Type | Unit [Frame] | Range/Enum | Description |
| ---------------- | --------- | ------------ | --------------------- | ------------------------------------------- |
| timestamp | `uint64` | us | | time since system start |
| timestamp_sample | `uint64` | us | | the timestamp of the raw data |
| beacon_id | `uint8` | | |
| range | `float32` | m | | Range measurement |
| lat | `float64` | deg | | Latitude |
| lon | `float64` | deg | | Longitude |
| alt | `float32` | m | | Beacon altitude (frame defined in alt_type) |
| alt_type | `uint8` | | [ALT_TYPE](#ALT_TYPE) | Altitude frame for alt field |
| hacc | `float32` | m | | Groundbeacon horizontal accuracy |
| vacc | `float32` | m | | Groundbeacon vertical accuracy |
| sequence_nr | `uint8` | | |
| status | `uint8` | | |
| carrier_freq | `uint16` | MHz | | Carrier frequency |
| range_accuracy | `float32` | m | | Range accuracy estimate |
## Enums
### ALT_TYPE {#ALT_TYPE}
| Name | Type | Value | Description |
| ------------------------------------------- | ------- | ----- | ------------------------------------ |
| <a id="#ALT_TYPE_WGS84"></a> ALT_TYPE_WGS84 | `uint8` | 0 | Altitude above WGS84 ellipsoid |
| <a id="#ALT_TYPE_MSL"></a> ALT_TYPE_MSL | `uint8` | 1 | Altitude above Mean Sea Level (AMSL) |
## Source Message
[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RangingBeacon.msg)
::: details Click here to see original file
```c
# Ranging beacon measurement data (e.g. LoRa, UWB)
uint64 timestamp # [us] time since system start
uint64 timestamp_sample # [us] the timestamp of the raw data
uint8 beacon_id
float32 range # [m] Range measurement
float64 lat # [deg] Latitude
float64 lon # [deg] Longitude
float32 alt # [m] Beacon altitude (frame defined in alt_type)
uint8 alt_type # [@enum ALT_TYPE] Altitude frame for alt field
uint8 ALT_TYPE_WGS84 = 0 # Altitude above WGS84 ellipsoid
uint8 ALT_TYPE_MSL = 1 # Altitude above Mean Sea Level (AMSL)
float32 hacc # [m] Groundbeacon horizontal accuracy
float32 vacc # [m] Groundbeacon vertical accuracy
uint8 sequence_nr
uint8 status
uint16 carrier_freq # [MHz] Carrier frequency
float32 range_accuracy # [m] Range accuracy estimate
# TOPICS ranging_beacon
```
:::
-1
View File
@@ -192,7 +192,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
- [QshellReq](QshellReq.md)
- [QshellRetval](QshellRetval.md)
- [RadioStatus](RadioStatus.md)
- [RangingBeacon](RangingBeacon.md) — Ranging beacon measurement data (e.g. LoRa, UWB).
- [RateCtrlStatus](RateCtrlStatus.md)
- [RcChannels](RcChannels.md)
- [RcParameterMap](RcParameterMap.md)
+1 -1
View File
@@ -13,7 +13,7 @@ This topic shows how to connect and configure DShot ESCs.
## Supported ESC
[ESCs & Motors > Supported ESCs](../peripherals/esc_motors.md#supported-esc) has a list of supported ESC (check "Protocols" column for DShot ESC).
[ESCs & Motors > Supported ESCs](../peripherals/esc_motors#supported-esc) has a list of supported ESC (check "Protocols" column for DShot ESC).
## Wiring/Connections {#wiring}
+2 -8
View File
@@ -487,7 +487,6 @@
- [Plugins](sim_gazebo_gz/plugins.md)
- [Gazebo Models Repository](sim_gazebo_gz/gazebo_models.md)
- [Multi-Vehicle Sim](sim_gazebo_gz/multi_vehicle_simulation.md)
- [SIH Simulation](sim_sih/index.md)
- [Gazebo Classic Simulation](sim_gazebo_classic/index.md)
- [Vehicles](sim_gazebo_classic/vehicles.md)
- [Worlds](sim_gazebo_classic/worlds.md)
@@ -587,8 +586,6 @@
- [DistanceSensorModeChangeRequest](msg_docs/DistanceSensorModeChangeRequest.md)
- [DronecanNodeStatus](msg_docs/DronecanNodeStatus.md)
- [Ekf2Timestamps](msg_docs/Ekf2Timestamps.md)
- [EscEepromRead](msg_docs/EscEepromRead.md)
- [EscEepromWrite](msg_docs/EscEepromWrite.md)
- [EscReport](msg_docs/EscReport.md)
- [EscStatus](msg_docs/EscStatus.md)
- [EstimatorAidSource1d](msg_docs/EstimatorAidSource1d.md)
@@ -779,7 +776,6 @@
- [VehicleLocalPositionV0](msg_docs/VehicleLocalPositionV0.md)
- [VehicleStatusV0](msg_docs/VehicleStatusV0.md)
- [VehicleStatusV1](msg_docs/VehicleStatusV1.md)
- [VehicleStatusV2](msg_docs/VehicleStatusV2.md)
- [MAVLink Messaging](mavlink/index.md)
- [Adding Messages](mavlink/adding_messages.md)
- [Streaming Messages](mavlink/streaming_messages.md)
@@ -874,9 +870,8 @@
- [jMAVSim 다중 차량 시뮬레이션](sim_jmavsim/multi_vehicle.md)
- [JSBSim Simulation](sim_jsbsim/index.md)
- [AirSim Simulation](sim_airsim/index.md)
- [Hardware Simulation](simulation/hardware.md)
- [HITL Simulation](simulation/hitl.md)
- [SIH on Hardware](sim_sih/hardware.md)
- [HITL Simulation](simulation/hitl.md)
- [Simulation-In-Hardware](sim_sih/index.md)
- [Multi-vehicle simulation](simulation/multi-vehicle-simulation.md)
- [플랫폼 시험과 지속 통합](test_and_ci/index.md)
- [시험 비행](test_and_ci/test_flights.md)
@@ -932,7 +927,6 @@
- [Translation](contribute/translation.md)
- [용어/표기법](contribute/notation.md)
- [라이센스](contribute/licenses.md)
- [SBOM](contribute/sbom.md)
- [출시](releases/index.md)
- [Release Process](releases/release_process.md)
+86
View File
@@ -0,0 +1,86 @@
# Neural Network Module: System Integration
The neural control module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) implements an end-to-end controller utilizing neural networks.
The parts of the module directly concerned with generating the code for the trained neural network and integrating it into the module are covered in [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md).
This page covers the changes that were made to integrate the module into PX4, both within the module, and in larger system configuration.
:::tip
This topic should help you to shape the module to your own needs.
You will need some familiarity with PX4 development.
For more information see the developer [Getting Started](../dev_setup/getting_started.md).
:::
## 자동 실행
A line to autostart the [mc_nn_control](../modules/modules_controller.md#mc-nn-control) module has been added in the [`ROMFS/px4fmu_common/init.d/rc.mc_apps`](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d/rc.mc_apps) startup script.
It checks whether the module is included by looking for the parameter [MC_NN_EN](../advanced_config/parameter_reference.md#MC_NN_EN).
If this is set to `1` (the default value), the module will be started when booting PX4.
Similarly you could create other parameters in the [`mc_nn_control_params.c`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_nn_control/mc_nn_control_params.c) file for other startup script checks.
## Custom Flight Mode
The module creates its own flight mode "Neural Control" which lets you choose it from the flight mode menu in QGC and bind it to a switch on you RC controller.
This is done by using the [ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) internally.
This involves several steps and is visualized here:
:::info
The module does not actually use ROS 2, it just uses the API exposed through uORB topics.
:::
:::info
In some QGC versions the flight mode does not show up, so make sure to update to the newest version.
This only works for some flight controllers, so you might have to use an RC controller to switch to the correct external flight mode.
:::
![neural_mode_registration](../../assets/advanced/neural_mode_registration.png)
1. Publish a [RegisterExtComponentRequest](../msg_docs/RegisterExtComponentRequest.md).
This specifies what you want to create, you can read more about this in the [Control Interface](../ros2/px4_ros2_control_interface.md).
In this case we register an arming check and a mode.
2. Wait for a [RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md).
This will give feedback on wether the mode registration was successful, and what the mode and arming check id is for the new mode.
3. [Optional] With the mode id, publish a [VehicleControlMode](../msg_docs/VehicleControlMode.md) message on the `config_control_setpoints` topic.
Here you can configure what other modules run in parallel.
The example controller replaces everything, so it turns off allocation.
If you want to replace other parts you can enable or disable the modules accordingly.
4. [Optional] With the mode id, publish a [ConfigOverrides](../msg_docs/ConfigOverrides.md) on the `config_overrides_request` topic.
(This is not done in the example module) This will let you defer failsafes or stop it from automatically disarming.
5. When the mode has been registered a [ArmingCheckRequest](../msg_docs/ArmingCheckRequest.md) will be sent, asking if your mode has everything it needs to run.
This message must be answered with a [ArmingCheckReply](../msg_docs/ArmingCheckReply.md) so the mode is not flagged as unresponsive.
In this response it is possible to set what requirements the mode needs to run, like local position.
If any of these requirements are set the commander will stop you from switching to the mode if they are not fulfilled.
It is also important to set health_component_index and num_events to 0 to not get a segmentation fault.
Unless you have a health component or events.
6. Listen to the [VehicleStatus](../msg_docs/VehicleStatus.md) topic.
If the nav_state equals the assigned `mode_id`, then the Neural Controller is activated.
7. When active the module will run the controller and publish to [ActuatorMotors](../msg_docs/ActuatorMotors.md).
If you want to replace a different part of the controller, you should find the appropriate topic to publish to.
To see how the requests are handled you can check out [src/modules/commander/ModeManagement.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/commander/ModeManagement.cpp).
## 로깅
To add module-specific logging a new topic has been added to [uORB](../middleware/uorb.md) called [NeuralControl](../msg_docs/NeuralControl.md).
The message definition is also added in `msg/CMakeLists.txt`, and to [`src/modules/logger/logged_topics.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/logger/logged_topics.cpp) under the debug category.
For these messages to be saved in your logs you need to include `debug` in the [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) parameter.
## Timing
The module has two includes for measuring the inference times.
The first one is a driver that works on the actual flight controller units, but a second one, `chrono`, is loaded for SITL testing.
Which timing library is included and used is based on wether PX4 is built with NUTTX or not.
## Changing the setpoint
The module uses the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages position fields to define its target.
To follow a trajectory, you can send updated setpoints.
For an example of how to do this in a PX4 module, see the [mc_nn_testing](https://github.com/SindreMHegre/PX4-Autopilot-public/tree/main/src/modules/mc_nn_testing) module in this fork.
Note that this is not included in upstream PX4.
To use it, copy the module folder from the linked repository into your workspace, and enable it by adding the following line to your `.px4board` file:
```sh
CONFIG_MODULES_MC_NN_TESTING=y
```
+1 -1
View File
@@ -91,7 +91,7 @@ For FMUv6S, you need to route the PPS signal separately:
For ARK FMUv6X on the Jetson carrier board:
1. Connect your GNSS module using either the 10-pin or 6-pin GPS connector: [ARK PAB GPS1 Interface](../flight_controller/ark_pab.md#gps1)
1. Connect your GNSS module using either the 10-pin or 6-pin GPS connector: [ARK PAB GPS1 Interface](../flight_controller/ark_pab#gps1)
2. Connect the PPS signal to the **FMU_CAP** pin: [ARK PAB ADIO Interface](../flight_controller/ark_pab.md#adio)
## 검증
+77
View File
@@ -0,0 +1,77 @@
# TensorFlow Lite Micro (TFLM)
The PX4 [Multicopter Neural Network](../advanced/neural_networks.md) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) integrates a neural network that uses the [TensorFlow Lite Micro (TFLM)](https://github.com/tensorflow/tflite-micro) inference library.
This is a mature inference library intended for use on embedded devices, and is hence a suitable choice for PX4.
This guide explains how the TFLM library is integrated into the [mc_nn_control](../modules/modules_controller.md#mc-nn-control) module, and the changes you would have to make to use it for your own neural network.
:::tip
For more information, see the [TFLM guide](https://ai.google.dev/edge/litert/microcontrollers/get_started).
:::
## TLMF NN Formats
TFLM uses networks in its own [tflite format](https://ai.google.dev/edge/litert/models/convert).
However, since many microcontrollers do not have native filesystem support, a tflite file can be converted to a C++ source and header file.
This is what is done in `mc_nn_control`.
The tflight neural network is represented in code by the files [`control_net.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_nn_control/control_net.cpp) and [`control_net.hpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_nn_control/control_net.hpp).
### Getting a Network in tflite Format
There are many online resource for generating networks in the `.tflite` format.
For this example we trained the network in the open source [Aerial Gym Simulator](https://ntnu-arl.github.io/aerial_gym_simulator/).
Aerial Gym includes a guide, and supports RL both for control and vision-based navigation tasks.
The project includes conversion code for `PyTorch -> TFLM` in the [resources/conversion](https://github.com/ntnu-arl/aerial_gym_simulator/tree/main/resources/conversion) folder.
### Updating `mc_nn_control` with your own NN
You can convert a `.tflite` network into a `.cc` file in the ubuntu terminal with this command:
```sh
xxd -i converted_model.tflite > model_data.cc
```
You will then have to modify the `control_net.hpp` and `control_net.cpp` to include the data from `model_data.cc`:
- Take the size of the network in the bottom of the `.cc` file and replace the size in `control_net.hpp`.
- Take the data in the model array in the `cc` file, and replace the ones in `control_net.cpp`.
You are now ready to run your own network.
## Code Explanation
This section explains the code used to integrate the NN in `control_net.cpp`.
### Operations and Resolver
Firstly we need to create the resolver and load the needed operators to run inference on the NN.
This is done in the top of `mc_nn_control.cpp`.
The number in `MicroMutableOpResolver<3>` represents how many operations you need to run the inference.
A full list of the operators can be found in the [micro_mutable_op_resolver.h](https://github.com/tensorflow/tflite-micro/blob/main/tensorflow/lite/micro/micro_mutable_op_resolver.h) file.
There are quite a few supported operators, but you will not find the most advanced ones.
In the control example the network is fully connected so we use `AddFullyConnected()`.
Then the activation function is ReLU, and we `AddAdd()` for the bias on each neuron.
### Interpreter
In the `InitializeNetwork()` we start by setting up the model that we loaded from the source and header file.
Next is to set up the interpreter, this code is taken from the TFLM documentation and is thoroughly explained there.
The end state is that the `_control_interpreter` is set up to later run inference with the `Invoke()` member function.
The `_input_tensor` is also defined, it is fetched from `_control_interpreter->input(0)`.
### 입력
The `_input_tensor` is filled in the `PopulateInputTensor()` function.
`_input_tensor` works by accessing the `->data.f` member array and fill in the required inputs for your network.
The inputs used in the control network is covered in [Neural Networks](../advanced/neural_networks.md).
### 출력
For the outputs the approach is fairly similar to the inputs.
After setting the correct inputs, calling the `Invoke()` function the outputs can be found by getting `_control_interpreter->output(0)`.
And from the output tensor you get the `->data.f` array.
+1 -1
View File
@@ -170,7 +170,7 @@ After the bootloader has updated you can [Load PX4 Firmware](../config/firmware.
## FMUv2 Bootloader Update
If _QGroundControl_ installs the FMUv2 target (see console during installation), and you have a newer board, you may need to update the bootloader in order to access all the memory on your flight controller.
This example explains how you can use [QGC Bootloader Update](#qgc-bootloader-update-sys-bl-update) to update the bootloader.
This example explains how you can use [QGC Bootloader Update](qgc-bootloader-update-sys-bl-update) to update the bootloader.
:::info
Early FMUv2 [Pixhawk-series](../flight_controller/pixhawk_series.md#fmu_versions) flight controllers had a [hardware issue](../flight_controller/silicon_errata.md#fmuv2-pixhawk-silicon-errata) that restricted them to using 1MB of flash memory.
@@ -94,28 +94,6 @@ The switch can also be set as part of _QGroundControl_ [Flight Mode](../config/f
| <a id="COM_DISARM_LAND"></a>[COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND) | 착륙후 자동 시동 해제 대기 시간. 기본값: 2s (-1 비활성화). |
| <a id="COM_DISARM_PRFLT"></a>[COM_DISARM_PRFLT](../advanced_config/parameter_reference.md#COM_DISARM_PRFLT) | 이륙 속도가 너무 느리면 자동 시동 해제 시간이 초과됩니다. Default: 10s (<=0 to disable). |
## Auto-Arming on Boot
The vehicle can be configured to arm automatically on boot once all preflight checks pass,
using the `COM_ARM_ON_BOOT` parameter. For safety, PX4 enforces a minimum 5-second delay after boot before attempting to arm.
Once armed this way, the vehicle will not re-arm automatically after a manual disarm.
:::info
The parameter value is read once at boot.
Changing it while the system is running has no effect until the next reboot.
:::
:::warning
Use with caution.
A vehicle that arms automatically can spin up motors and actuators without any operator gesture.
Ensure the vehicle is in a safe state before powering on.
:::
| 매개변수 | 설명 |
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_ARM_ON_BOOT"></a>[COM_ARM_ON_BOOT](../advanced_config/parameter_reference.md#COM_ARM_ON_BOOT) | Arm automatically once preflight checks pass after boot. Default: `0` (Disabled). |
## Pre-Arm Checks
To reduce accidents, vehicles are only allowed to arm certain conditions are met (some of which are configurable).
@@ -0,0 +1,162 @@
# _Pixhawk 4 Mini_ Wiring Quick Start
:::warning
PX4 does not manufacture this (or any) autopilot.
Contact the [manufacturer](https://holybro.com/) for hardware support or compliance issues.
:::
This quick start guide shows how to power the [_Pixhawk<sup>&reg;</sup> 4 Mini_](../flight_controller/pixhawk4_mini.md) flight controller and connect its most important peripherals.
![Pixhawk4 mini](../../assets/flight_controller/pixhawk4mini/pixhawk4mini_iso_1.png)
## 배선 개요
아래의 이미지는 주요 센서와 주변 장치(모터 및 서보 출력 제외)의 연결 방법을 설명합니다.
![Pixhawk 4 Mini Wiring Overview](../../assets/flight_controller/pixhawk4mini/pixhawk4mini_wiring_overview.png)
:::tip
More information about available ports can be found here: [_Pixhawk 4 Mini_ > Interfaces](../flight_controller/pixhawk4_mini.md#interfaces).
:::
## 콘트롤러 장착 및 장착 방향
_Pixhawk 4 Mini_ should be mounted on your frame using vibration-damping foam pads (included in the kit).
차량의 무게 중심에 최대한 가깝운 프레임에 장착하여야 하며, 화살표가 차량의 앞쪽과 위쪽을 향하도록 하여야 합니다.
![Pixhawk 4 Mini Orientation](../../assets/flight_controller/pixhawk4mini/pixhawk4mini_orientation.png)
:::info
If the controller cannot be mounted in the recommended/default orientation (e.g. due to space constraints) you will need to configure the autopilot software with the orientation that you actually used: [Flight Controller Orientation](../config/flight_controller_orientation.md).
:::
## GPS + 나침반 + 부저 + 안전 스위치 + LED
Attach the provided GPS with integrated compass, safety switch, buzzer, and LED to the **GPS MODULE** port. The GPS/Compass should be [mounted on the frame](../assembly/mount_gps_compass.md) as far away from other electronics as possible, with the direction marker towards the front of the vehicle (separating the compass from other electronics will reduce interference).
![Connect compass/GPS to Pixhawk 4](../../assets/flight_controller/pixhawk4mini/pixhawk4mini_gps.png)
:::info
The GPS module's integrated safety switch is enabled _by default_ (when enabled, PX4 will not let you arm the vehicle).
비활성화하려면 안전 스위치를 1초간 길게 누르십시오.
안전 스위치를 다시 눌러 안전 장치를 활성화하고 기체 시동을 끌 수 있습니다.
조종기나 지상국 프로그램에서 기체 시동을 끌 수 없는 상황에서 유용합니다.
:::
## 전원
PMB(Power Management Board)는 배전 보드와 전원 모듈로 사용됩니다.
In addition to providing regulated power to _Pixhawk 4 Mini_ and the ESCs, it sends information to the autopilot about the batterys voltage and current draw.
Connect the output of the PMB that comes with the kit to the **POWER** port of the _Pixhawk 4 Mini_ using a 6-wire cable.
ESC와 서보에 대한 전원 공급 및 신호 연결을 위한 전원관리보드의 연결 방법은 아래의 표에서 설명합니다.
![Pixhawk 4 - Power Management Board](../../assets/flight_controller/pixhawk4mini/pixhawk4mini_power_management.png)
:::info
The image above only shows the connection of a single ESC and a single servo.
나머지 ESC와 서보를 비슷하게 연결합니다.
:::
| 핀 또는 커넥터 | 기능 |
| -------- | -------------------------------------------------------------------------- |
| B+ | ESC에 전원을 공급하기 위해 ESC B +에 연결 |
| GND | ESC 접지에 연결 |
| PWR | JST-GH 6-pin Connector, 5V 3A output<br> connect to _Pixhawk 4 Mini_ POWER |
| BAT | 전원 입력, 2 ~ 12S LiPo 배터리에 연결 |
The pinout of the _Pixhawk 4 Mini_ **POWER** port is shown below.
The `CURRENT` signal should carry an analog voltage from 0-3.3V for 0-120A as default.
The `VOLTAGE` signal should carry an analog voltage from 0-3.3V for 0-60V as default.
VCC 라인은 최소 3A 연속을 제공하여야하며, 기본적으로 5.1V로 설정되어야 합니다. 5V 보다 낮은 전압은 권장되지 않습니다.
| 핀 | 신호 | 전압 |
| --------------------------- | ------- | --------------------- |
| 1(red) | VCC | +5V |
| 2(black) | VCC | +5V |
| 3(black) | CURRENT | +3.3V |
| 4(black) | VOLTAGE | +3.3V |
| 5(black) | GND | GND |
| 6(black) | GND | GND |
:::info
If using a plane or rover, the 8 pin power (+) rail of **MAIN OUT** will need to be separately powered in order to drive servos for rudders, elevons, etc.
전원 레일을 BEC가 장착된 ESC 또는 독립형 5V BEC 또는 2S LiPo 배터리에 연결하여야 합니다.
서보에 제공되는 전압이 적절한 지 체크하십시오.
:::
<!--In the future, when Pixhawk 4 kit is available, add wiring images/videos for different airframes.-->
:::info
Using the Power Module that comes with the kit you will need to configure the _Number of Cells_ in the [Power Settings](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/power.html) but you won't need to calibrate the _voltage divider_.
You will have to update the _voltage divider_ if you are using any other power module (e.g. the one from the Pixracer).
:::
## 무선 조종
A remote control (RC) radio system is required if you want to _manually_ control your vehicle (PX4 does not require a radio system for autonomous flight modes).
You will need to [select a compatible transmitter/receiver](../getting_started/rc_transmitter_receiver.md) and then _bind_ them so that they communicate (read the instructions that come with your specific transmitter/receiver).
The instructions below show how to connect the different types of receivers to _Pixhawk 4 Mini_:
- Spektrum/DSM or S.BUS receivers connect to the **DSM/SBUS RC** input.
![Pixhawk 4 Mini - Radio port for Spektrum receivers](../../assets/flight_controller/pixhawk4mini/pixhawk4mini_rc_dsmsbus.png)
- PPM receivers connect to the **PPM RC** input port.
![Pixhawk 4 Mini - Radio port for PPM receivers](../../assets/flight_controller/pixhawk4mini/pixhawk4mini_rc_ppm.png)
- PPM and PWM receivers that have an _individual wire for each channel_ must connect to the **PPM RC** port _via a PPM encoder_ [like this one](https://www.getfpv.com/radios/radio-accessories/holybro-ppm-encoder-module.html) (PPM-Sum receivers use a single signal wire for all channels).
For more information about selecting a radio system, receiver compatibility, and binding your transmitter/receiver pair, see: [Remote Control Transmitters & Receivers](../getting_started/rc_transmitter_receiver.md).
## Telemetry Radio (Optional)
무선 텔레메트리는 지상국 프로그램에서 비행 차량의 통신/제어에 사용합니다(예 : UAV를 특정 위치로 지시하거나 새 임무를 업로드 할 수 있음).
The vehicle-based radio should be connected to the **TELEM1** port as shown below (if connected to this port, no further configuration is required).
다른 텔레메트리는 일반적으로 지상국 컴퓨터나 모바일 장치에 USB를 통하여 연결됩니다.
![Pixhawk 4 Mini Telemetry](../../assets/flight_controller/pixhawk4mini/pixhawk4mini_telemetry.png)
## micro SD 카드 (선택 사항)
SD cards are highly recommended as they are needed to [log and analyse flight details](../getting_started/flight_reporting.md), to run missions, and to use UAVCAN-bus hardware.
Insert the card (included in the kit) into _Pixhawk 4 Mini_ as shown below.
![Pixhawk 4 Mini SD Card](../../assets/flight_controller/pixhawk4mini/pixhawk4mini_sdcard.png)
:::tip
For more information see [Basic Concepts > SD Cards (Removable Memory)](../getting_started/px4_basic_concepts.md#sd-cards-removable-memory).
:::
## 모터
Motors/servos are connected to the **MAIN OUT** ports in the order specified for your vehicle in the [Airframe Reference](../airframes/airframe_reference.md). See [_Pixhawk 4 Mini_ > Supported Platforms](../flight_controller/pixhawk4_mini.md#supported-platforms) for more information.
:::info
이 참고사항은 모든 지원되는 기체 프레임의 출력 포트의 모터/서보 연결 리스트입니다. 프레임이 참고사항에 기재되어 있지 않다면, 올바른 유형의 "일반" 프레임을 사용하십시오.
:::
:::warning
The mapping is not consistent across frames (e.g. you can't rely on the throttle being on the same output for all plane frames).
가지고 있는 기체의 프레임에 대해 올바르게 모터를 제대로 연결하였는지 다시 한 번 확인하십시오.
:::
## 기타 주변 장치
The wiring and configuration of optional/less common components is covered within the topics for individual [peripherals](../peripherals/index.md).
## 설정
General configuration information is covered in: [Autopilot Configuration](../config/index.md).
QuadPlane specific configuration is covered here: [QuadPlane VTOL Configuration](../config_vtol/vtol_quad_configuration.md)
<!-- Nice to have detailed wiring infographic and instructions for different vehicle types. -->
## 추가 정보
- [_Pixhawk 4 Mini_](../flight_controller/pixhawk4_mini.md)
+2 -2
View File
@@ -38,7 +38,7 @@ Devices within a network are connected in a _daisy-chain_ in any order (this dif
:::warning
Don't connect each CAN peripheral to a separate CAN port!
Unlike UARTs, CAN peripherals are designed to be daisy chained, with additional ports such as `CAN2` used for [redundancy](#redundancy).
Unlike UARTs, CAN peripherals are designed to be daisy chained, with additional ports such as `CAN2` used for [redundancy](redundancy).
:::
At either end of the chain, a 120Ω termination resistor should be connected between the two data lines.
@@ -84,7 +84,7 @@ You only _need_ one CAN port to support an arbitrary number of CAN devices using
Don't connect each CAN peripheral to a separate CAN port!
:::
Generally you'll daisy all CAN peripherals off a single port, and if there is more than one CAN port, use the second one for [redundancy](#redundancy).
Generally you'll daisy all CAN peripherals off a single port, and if there is more than one CAN port, use the second one for [redundancy](redundancy).
If three are three ports, you might use the remaining network for devices that support another CAN protocol.
The documentation for your flight controller should indicate which ports are supported/enabled.
+7 -7
View File
@@ -76,13 +76,13 @@ You might have to adjust the per-motor pole count (`DSHOT_MOT_POL1``DSHOT_MOT
The following parameters should be set to enable and configure dynamic notch filters:
| 매개변수 | 설명 |
| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="IMU_GYRO_DNF_EN"></a>[IMU_GYRO_DNF_EN](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_EN) | Enable IMU gyro dynamic notch filtering. `0`: ESC RPM, `1`: Onboard FFT. |
| <a id="IMU_GYRO_FFT_EN"></a>[IMU_GYRO_FFT_EN](../advanced_config/parameter_reference.md#IMU_GYRO_FFT_EN) | Enable onboard FFT (required if `IMU_GYRO_DNF_EN` is set to `1`). |
| <a id="IMU_GYRO_DNF_MIN"></a>[IMU_GYRO_DNF_MIN](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_MIN) | Minimum dynamic notch frequency in Hz. |
| <a id="IMU_GYRO_DNF_BW"></a>[IMU_GYRO_DNF_BW](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_BW) | Bandwidth for each notch filter in Hz. |
| <a id="IMU_GYRO_DNF_HMC"></a>[IMU_GYRO_DNF_HMC](../advanced_config/parameter_reference.md#IMU_GYRO_NF0_BW) | Number of harmonics to filter. |
| 매개변수 | 설명 |
| ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------- |
| <a href="IMU_GYRO_DNF_EN"></a>[IMU_GYRO_DNF_EN](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_EN) | Enable IMU gyro dynamic notch filtering. `0`: ESC RPM, `1`: Onboard FFT. |
| <a href="IMU_GYRO_FFT_EN"></a>[IMU_GYRO_FFT_EN](../advanced_config/parameter_reference.md#IMU_GYRO_FFT_EN) | Enable onboard FFT (required if `IMU_GYRO_DNF_EN` is set to `1`). |
| <a href="IMU_GYRO_DNF_MIN"></a>[IMU_GYRO_DNF_MIN](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_MIN) | Minimum dynamic notch frequency in Hz. |
| <a href="IMU_GYRO_DNF_BW"></a>[IMU_GYRO_DNF_BW](../advanced_config/parameter_reference.md#IMU_GYRO_DNF_BW) | Bandwidth for each notch filter in Hz. |
| <a href="IMU_GYRO_DNF_HMC"></a>[IMU_GYRO_DNF_HMC](../advanced_config/parameter_reference.md#IMU_GYRO_NF0_BW) | Number of harmonics to filter. |
### Low-pass Filter
-226
View File
@@ -1,226 +0,0 @@
# Software Bill of Materials (SBOM)
PX4 generates a [Software Bill of Materials](https://ntia.gov/SBOM) for every firmware build in [SPDX 2.3](https://spdx.github.io/spdx-spec/v2.3/) JSON format.
## Why SBOM?
- **Regulatory compliance**: The EU Cyber Resilience Act (CRA) requires SBOMs for products with digital elements (reporting obligations begin in September 2026).
- **Supply chain transparency**: SBOMs enumerate every component compiled into firmware, enabling users and integrators to audit dependencies.
- **NTIA minimum elements**: Each SBOM satisfies all seven [NTIA required fields](https://www.ntia.gov/report/2021/minimum-elements-software-bill-materials-sbom): supplier, component name, version, unique identifier, dependency relationship, author, and timestamp.
## Format
PX4 uses SPDX 2.3 JSON.
SPDX is the Linux Foundation's own standard (ISO/IEC 5962), aligning with PX4's position as a Dronecode/LF project.
Zephyr RTOS also uses SPDX.
Each SBOM contains:
- **Primary package**: The PX4 firmware for a specific board target, marked with `primaryPackagePurpose: FIRMWARE`.
- **Git submodules**: All third-party libraries included via git submodules (~33 packages), with SPDX license identifiers and commit hashes.
- **Python build dependencies**: Packages from `Tools/setup/requirements.txt` marked as `BUILD_DEPENDENCY_OF` the firmware.
- **Board-specific modules**: Internal PX4 modules compiled for the target board.
- **Compiler**: The C compiler used for the build.
Typical SBOM size: 70-100 packages, ~500 lines, ~20 KB JSON.
## Generation
SBOMs are generated automatically as part of every CMake build.
The output file is:
```txt
build/<target>/<target>.sbom.spdx.json
```
예:
```txt
build/px4_fmu-v6x_default/px4_fmu-v6x_default.sbom.spdx.json
```
The generator script is `Tools/ci/generate_sbom.py`.
It requires PyYAML (`pyyaml`) for loading license overrides.
### CMake Integration
The `sbom` CMake target is included in the default `ALL` target.
The relevant CMake module is `cmake/sbom.cmake`.
### Disabling SBOM Generation
Set the environment variable before building.
This is checked at CMake configure time, so a clean build or reconfigure is required:
```sh
PX4_SBOM_DISABLE=1 make px4_fmu-v6x_default
```
If the build directory already exists, force a reconfigure:
```sh
PX4_SBOM_DISABLE=1 cmake -B build/px4_fmu-v6x_default .
```
### Manual Generation
You can also run the generator directly:
```sh
python3 Tools/ci/generate_sbom.py \
--source-dir . \
--board px4_fmu-v6x_default \
--modules-file build/px4_fmu-v6x_default/config_module_list.txt \
--compiler arm-none-eabi-gcc \
--output build/px4_fmu-v6x_default/px4_fmu-v6x_default.sbom.spdx.json
```
## Artifacts
SBOMs are available in:
| Location | Path |
| --------------- | ---------------------------------------- |
| Build directory | `build/<target>/<target>.sbom.spdx.json` |
| GitHub Releases | Alongside `.px4` firmware files |
| S3 | Same directory as firmware artifacts |
## Validation
Validate an SBOM against the SPDX JSON schema:
```sh
python3 -c "
import json
doc = json.load(open('build/px4_sitl_default/px4_sitl_default.sbom.spdx.json'))
assert doc['spdxVersion'] == 'SPDX-2.3'
assert doc['dataLicense'] == 'CC0-1.0'
assert len(doc['packages']) > 0
print(f'Valid: {len(doc[\"packages\"])} packages')
"
```
For full schema validation, use the [SPDX online validator](https://tools.spdx.org/app/validate/) or the `spdx-tools` CLI.
## License Detection
Submodule licenses are identified through a combination of auto-detection and manual overrides.
### Auto-Detection
The generator reads the first 100 lines of each submodule's LICENSE or COPYING file
and matches keywords against known patterns.
Copyleft licenses (GPL, LGPL, AGPL) are checked before permissive ones
to prevent false positives.
Supported patterns include:
| SPDX Identifier | Matched Keywords |
| ----------------------------- | ------------------------------------------------------------------ |
| GPL-3.0-only | "GNU GENERAL PUBLIC LICENSE", "Version 3" |
| GPL-2.0-only | "GNU GENERAL PUBLIC LICENSE", "Version 2" |
| LGPL-3.0-only | "GNU LESSER GENERAL PUBLIC LICENSE", "Version 3" |
| LGPL-2.1-only | "GNU Lesser General Public License", "Version 2.1" |
| AGPL-3.0-only | "GNU AFFERO GENERAL PUBLIC LICENSE", "Version 3" |
| Apache-2.0 | "Apache License", "Version 2.0" |
| MIT | "Permission is hereby granted" |
| BSD-3-Clause | "Redistribution and use", "Neither the name" |
| BSD-2-Clause | "Redistribution and use", "THIS SOFTWARE IS PROVIDED" |
| ISC | "Permission to use, copy, modify, and/or distribute" |
| EPL-2.0 | "Eclipse Public License", "2.0" |
| Unlicense | "The Unlicense", "unlicense.org" |
If no pattern matches, the license is set to `NOASSERTION`.
### Override File
When auto-detection fails or returns the wrong result,
add an entry to `Tools/ci/license-overrides.yaml`:
```yaml
overrides:
src/lib/crypto/libtomcrypt:
license: "Unlicense"
comment: "Public domain dedication. Functionally equivalent to Unlicense."
```
Each entry maps a submodule path to its correct SPDX license identifier.
The optional `comment` field is emitted as `licenseComments` in the SBOM,
providing context for auditors reviewing complex licensing situations
(dual licenses, composite LICENSE files, public domain dedications).
### Copyleft Guardrail
The `--verify-licenses` command flags submodules with copyleft licenses
(GPL, LGPL, AGPL) in a dedicated warning section.
This is informational only and does not cause a failure.
It helps maintainers track copyleft obligations when adding new submodules.
### Platform Filtering
Submodules under `platforms/nuttx/` are excluded from POSIX and QURT SBOMs.
The `--platform` argument (set automatically by CMake via `${PX4_PLATFORM}`)
controls which platform-specific submodules are included.
This ensures SITL builds do not list NuttX RTOS packages.
### 검증
Run the verify command to check detection for all submodules:
```sh
python3 Tools/ci/generate_sbom.py --verify-licenses --source-dir .
```
This prints each submodule with its detected license, any override, and the final value.
It exits non-zero if any checked-out submodule resolves to `NOASSERTION` without an override.
Copyleft warnings are printed after the main table.
### Adding a New Submodule
1. Add the submodule normally.
2. Run `--verify-licenses` to confirm the license is detected.
3. If detection fails, add an override to `Tools/ci/license-overrides.yaml`.
4. If the license is not in the SPDX list, use `LicenseRef-<name>`.
### EU CRA Compliance
The EU Cyber Resilience Act requires SBOMs for products with digital elements.
The goal is zero `NOASSERTION` licenses in shipped firmware SBOMs.
Every submodule should have either a detected or overridden license.
The `--verify-licenses` check enforces this in CI.
## What's in an SBOM
This section is for integrators, compliance teams, and anyone reviewing SBOM artifacts.
### Where to Find SBOMs
| Location | Path |
| --------------- | ---------------------------------------- |
| Build directory | `build/<target>/<target>.sbom.spdx.json` |
| GitHub Releases | Alongside `.px4` firmware files |
| S3 | Same directory as firmware artifacts |
### Reading the JSON
Each SBOM is a single JSON document following SPDX 2.3.
Key fields:
- **`packages`**: Array of all components. Each has `name`, `versionInfo`, `licenseConcluded`, and `SPDXID`.
- **`relationships`**: How packages relate. `CONTAINS` means a submodule is compiled into firmware. `BUILD_DEPENDENCY_OF` means a tool used only during build.
- **`licenseConcluded`**: The SPDX license identifier determined for that package.
- **`licenseComments`**: Free-text explanation for complex cases (dual licenses, composite files, public domain).
- **`externalRefs`**: Package URLs (purls) linking to GitHub repos or PyPI.
### Understanding NOASSERTION
`NOASSERTION` means no license could be determined.
For submodules, this happens when:
- The submodule is not checked out (common in CI shallow clones).
- No LICENSE/COPYING file exists.
- The LICENSE file does not match any known pattern and no override is configured.
For shipped firmware, `NOASSERTION` should be resolved by adding an override.
For build-only dependencies (Python packages), `NOASSERTION` is acceptable
since these are not compiled into the firmware binary.
+1 -1
View File
@@ -25,7 +25,7 @@ See the debug probe documentation for details on how to setup your debug connect
- [SEGGER J-Link](probe_jlink.md): commercial probe, no built-in serial console, requires adapter.
- [Black Magic Probe](probe_bmp.md): integrated GDB server and serial console, requires adapter.
- [STLink](probe_stlink.md): best value, integrated serial console, adapter must be soldered.
- [STLink](probe_stlink): best value, integrated serial console, adapter must be soldered.
We recommend using the J-Link with the Pixhawk Debug Adapter or the STLinkv3-MINIE with a soldered custom cable.
+9 -9
View File
@@ -5,7 +5,7 @@ PX4 runs on ARM Cortex-M microcontrollers, which contain dedicated hardware for
The SWD debug interface allows direct, low-level, hardware access to the microcontroller's processor and peripherals, so it does not depend on any software on the device.
Therefore it can be used to debug bootloaders and operating systems such as NuttX.
## Debug Signals {#debug-signals}
## Debug Signals
Four signals are required for debugging (in bold) while the rest is recommended.
@@ -29,7 +29,7 @@ They are usually not accessible and are typically only used to debug very specif
## Autopilot Debug Ports {#debug-ports}
Flight controllers commonly provide a single debug port that exposes both the [SWD Interface](#debug-signals) and [System Console](system_console.md).
Flight controllers commonly provide a single debug port that exposes both the [SWD Interface](#debug-signals) and [System Console](system_console).
The [Pixhawk Connector Standards](#pixhawk-standard-debug-ports) formalize the port that must be used in each FMU version.
However there are still many boards that use different pinouts or connectors, so we recommend you check the [documentation for your autopilot](../flight_controller/index.md) to confirm port location and pinout.
@@ -91,7 +91,7 @@ There FMU and Pixhawk versions are (only) consistent after FMUv5X.
### Pixhawk Debug Mini
The [Pixhawk Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) defines the _Pixhawk Debug Mini_, a _6-Pin SH Debug Port_ that provides access to both SWD pins and the [System Console](system_console.md).
The [Pixhawk Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) defines the _Pixhawk Debug Mini_, a _6-Pin SH Debug Port_ that provides access to both SWD pins and the [System Console](system_console).
This is used in FMUv4 and FMUv5.
@@ -122,7 +122,7 @@ You can connect to the debug port using a [cable like this one](https://www.digi
### Pixhawk Debug Full
The [Pixhawk Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) defines _Pixhawk Debug Full_, a _10-Pin SH Debug Port_ that provides access to both SWD pins and the [System Console](system_console.md).
The [Pixhawk Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) defines _Pixhawk Debug Full_, a _10-Pin SH Debug Port_ that provides access to both SWD pins and the [System Console](system_console).
This essentially moves the solder pads from beside the [Pixhawk Debug Mini](#pixhawk-debug-mini) into the connector, and also adds an SWO pin.
This port is specified for use in FMUv5x, FMUv6, FMUv6x.
@@ -154,14 +154,14 @@ You can connect to the debug port using a [cable like this one](https://www.digi
## Debug Probes for PX4 Hardware {#debug-probes}
Flight controllers commonly provide a [single debug port](#autopilot-debug-ports) that exposes both the [SWD Interface](#debug-signals) and [System Console](system_console.md).
Flight controllers commonly provide a [single debug port](#autopilot-debug-ports) that exposes both the [SWD Interface](#debug-signals) and [System Console](system_console).
There are several debug probes that are tested and supported for connecting to one or both of these interfaces:
- [SEGGER J-Link](../debug/probe_jlink.md): commercial probe, no built-in serial console, requires adapter.
- [Black Magic Probe](../debug/probe_bmp.md): integrated GDB server and serial console, requires adapter.
- [STLink](../debug/probe_stlink.md): best value, integrated serial console, adapter must be soldered.
- [MCU-Link](../debug/probe_mculink.md): best value, integrated serial console, requires adapter.
- [STLink](../debug/probe_stlink): best value, integrated serial console, adapter must be soldered.
- [MCU-Link](../debug/probe_mculink): best value, integrated serial console, requires adapter.
An adapter to connect to the debug port may come with your flight controller or debug probe.
Other options are given below.
@@ -199,7 +199,7 @@ Probes that are known to come with connectors are listed below:
### Board-specific Adapters
Some manufacturers provide cables to make it easy to connect the SWD interface and [System Console](../debug/system_console.md).
Some manufacturers provide cables to make it easy to connect the SWD interface and [System Console](../debug/system_console).
- [CUAV V5nano](../flight_controller/cuav_v5_nano.md#debug_port) and [CUAV V5+](../flight_controller/cuav_v5_plus.md#debug-port) include this debug cable:
@@ -213,7 +213,7 @@ You can also create custom cables for connecting to different boards or probes:
- Connect the VREF pin, if supported by the debug probe.
- Connect the remaining pins, if present.
See the [STLinkv3-MINIE](probe_stlink.md) for a guide on how to solder a custom cable.
See the [STLinkv3-MINIE](probe_stlink) for a guide on how to solder a custom cable.
:::tip
Where possible, we highly recommend that you create or obtain an adapter board rather than custom cables for connecting to SWD/JTAG debuggers and computers.
+1 -1
View File
@@ -282,7 +282,7 @@ make [VENDOR_][MODEL][_VARIANT] [VIEWER_MODEL_DEBUGGER_WORLD]
- **VENDOR:** The manufacturer of the board: `px4`, `aerotenna`, `airmind`, `atlflight`, `auav`, `beaglebone`, `intel`, `nxp`, etc.
The vendor name for Pixhawk series boards is `px4`.
- **MODEL:** The _board model_ "model": `sitl`, `fmu-v2`, `fmu-v3`, `fmu-v4`, `fmu-v5`, `navio2`, etc.
- **VARIANT:** Indicates particular configurations: e.g. `bootloader`, `cyphal`, `sih`, which add or remove components to/from the `default` configuration.
- **VARIANT:** Indicates particular configurations: e.g. `bootloader`, `cyphal`, which contain components that are not present in the `default` configuration.
Most commonly this is `default`, and may be omitted.
:::tip
+1 -1
View File
@@ -1,7 +1,7 @@
# Arch Linux 개발 환경
:::warning
This development environment is [community supported and maintained](../advanced/community_supported_dev_env.md).
This development environment is [community supported and maintained](../advanced/community_supported_dev_env).
It may or may not work with current versions of PX4.
See [Toolchain Installation](../dev_setup/dev_env.md) for information about the environments and tools supported by the core development team.
+1 -1
View File
@@ -84,7 +84,7 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if
- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
- If using [Moving Baseline & GPS Heading](#setting-up-moving-baseline-gps-heading), set [SENS_GPS_PRIME](../advanced_config/parameter_reference.md#SENS_GPS_PRIME) to the CAN node ID of the _Moving Base_ module. The moving base is preferred because the rover receiver in a moving baseline configuration can experience degraded navigation rate and increased data latency when corrections are intermittent.
- If using [Moving Baseline & GPS Heading](#setting-up-moving-baseline--gps-heading), set [SENS_GPS_PRIME](../advanced_config/parameter_reference.md#SENS_GPS_PRIME) to the CAN node ID of the _Moving Base_ module. The moving base is preferred because the rover receiver in a moving baseline configuration can experience degraded navigation rate and increased data latency when corrections are intermittent.
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
- The parameters [SENS_GPS0_OFFX](../advanced_config/parameter_reference.md#SENS_GPS0_OFFX), [SENS_GPS0_OFFY](../advanced_config/parameter_reference.md#SENS_GPS0_OFFY) and [SENS_GPS0_OFFZ](../advanced_config/parameter_reference.md#SENS_GPS0_OFFZ) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity.
+1 -1
View File
@@ -5,7 +5,7 @@ PX4 supports DroneCAN compliant ESCs.
## Supported ESC
:::info
[Supported ESCs](../peripherals/esc_motors.md#supported-esc) in _ESCs & Motors_ may include additional devices that are not listed below.
[Supported ESCs](../peripherals/esc_motors#supported-esc) in _ESCs & Motors_ may include additional devices that are not listed below.
:::
The following articles have specific hardware/firmware information:
+1 -1
View File
@@ -5,7 +5,7 @@ PX4 does not manufacture this (or any) autopilot.
Contact the [manufacturer](https://arkelectron.com/contact-us/) for hardware support or compliance issues.
:::
The USA-built [ARKV6X](https://arkelectron.gitbook.io/ark-documentation/flight-controllers/arkv6x) flight controller is based on the [FMUV6X and Pixhawk Autopilot Bus open source standards](https://github.com/pixhawk/Pixhawk-Standards).
The USA-built [ARKV6X](\(https://arkelectron.gitbook.io/ark-documentation/flight-controllers/arkv6x\)) flight controller is based on the [FMUV6X and Pixhawk Autopilot Bus open source standards](https://github.com/pixhawk/Pixhawk-Standards).
With triple synced IMUs, data averaging, voting, and filtering is possible.
The Pixhawk Autopilot Bus (PAB) form factor enables the ARKV6X to be used on any [PAB-compatible carrier board](../flight_controller/pixhawk_autopilot_bus.md), such as the [ARK Pixhawk Autopilot Bus Carrier](../flight_controller/ark_pab.md).
+7
View File
@@ -0,0 +1,7 @@
# DroPix Flight Controller (Discontinued)
<Badge type="info" text="Discontinued" />
The Drotek<sup>&reg;</sup> _DroPix autopilot_ is no longer available on the Drotek website, and is assumed to be discontinued.
See [PX4 v1.13 Documentation > DroPix Flight Controller](https://docs.px4.io/v1.13/en/flight_controller/dropix.html) for documentation.
+8 -8
View File
@@ -100,14 +100,14 @@ To launch in this mode:
The _launch detector_ is affected by the following parameters:
| 매개변수 | 설명 |
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------- |
| <a id="FW_LAUN_DETCN_ON"></a>[FW_LAUN_DETCN_ON](../advanced_config/parameter_reference.md#FW_LAUN_DETCN_ON) | Enable automatic launch detection. If disabled motors spin up on arming already |
| <a id="FW_LAUN_AC_THLD"></a>[FW_LAUN_AC_THLD](../advanced_config/parameter_reference.md#FW_LAUN_AC_THLD) | Acceleration threshold (norm of acceleration must be above this value) |
| <a id="FW_LAUN_AC_T"></a>[FW_LAUN_AC_T](../advanced_config/parameter_reference.md#FW_LAUN_AC_T) | Trigger time (acceleration must be above threshold for this amount of seconds) |
| <a id="FW_LAUN_MOT_DEL"></a>[FW_LAUN_MOT_DEL](../advanced_config/parameter_reference.md#FW_LAUN_MOT_DEL) | Delay from launch detection to motor spin up |
| <a id="FW_LAUN_CS_LK_DY"></a>[FW_LAUN_CS_LK_DY](../advanced_config/parameter_reference.md#FW_LAUN_CS_LK_DY) | Delay from launch detection to unlocking the control surfaces |
| <a id="CA_CS_LAUN_LK"></a>[CA_CS_LAUN_LK](../advanced_config/parameter_reference.md#CA_CS_LAUN_LK) | Bitmask to select which control surfaces are to be locked during launch |
| 매개변수 | 설명 |
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------- |
| <a id="FW_LAUN_DETCN_ON"></a>[FW_LAUN_DETCN_ON](../advanced_config/parameter_reference.md#FW_LAUN_DETCN_ON) | Enable automatic launch detection. If disabled motors spin up on arming already |
| <a id="FW_LAUN_AC_THLD"></a>[FW_LAUN_AC_THLD](../advanced_config/parameter_reference.md#FW_LAUN_AC_THLD) | Acceleration threshold (acceleration in body-forward direction must be above this value) |
| <a id="FW_LAUN_AC_T"></a>[FW_LAUN_AC_T](../advanced_config/parameter_reference.md#FW_LAUN_AC_T) | Trigger time (acceleration must be above threshold for this amount of seconds) |
| <a id="FW_LAUN_MOT_DEL"></a>[FW_LAUN_MOT_DEL](../advanced_config/parameter_reference.md#FW_LAUN_MOT_DEL) | Delay from launch detection to motor spin up |
| <a id="FW_LAUN_CS_LK_DY"></a>[FW_LAUN_CS_LK_DY](../advanced_config/parameter_reference.md#FW_LAUN_CS_LK_DY) | Delay from launch detection to unlocking the control surfaces |
| <a id="CA_CS_LAUN_LK"></a>[CA_CS_LAUN_LK](../advanced_config/parameter_reference.md#CA_CS_LAUN_LK) | Bitmask to select which control surfaces are to be locked during launch |
## Runway Takeoff {#runway_launch}
+8 -8
View File
@@ -13,14 +13,14 @@ The mission is typically created and uploaded with a Ground Control Station (GCS
The following commands can be used in missions at time of writing (PX4 v1.16):
| QGC mission item | 통신 | 설명 |
| ------------------------------------- | ----------------------------------------------------------------- | ----------------------------------------------------------------- |
| Mission start | [MAV\_CMD\_MISSION\_START][MAV_CMD_MISSION_START] | Starts the mission. |
| Waypoint | [MAV\_CMD\_NAV\_WAYPOINT][MAV_CMD_NAV_WAYPOINT] | Navigate to waypoint. |
| Return to launch | [MAV\_CMD\_NAV\_RETURN\_TO\_LAUNCH][MAV_CMD_NAV_RETURN_TO_LAUNCH] | Return to the launch location. |
| Change speed | [MAV\_CMD\_DO\_CHANGE\_SPEED][MAV_CMD_DO_CHANGE_SPEED] | Change the speed setpoint |
| Set launch location | [MAV\_CMD\_DO\_SET\_HOME][MAV_CMD_DO_SET_HOME] | Changes launch location to specified coordinates. |
| Jump to item (all) | [MAV\_CMD\_DO\_JUMP][MAV_CMD_DO_JUMP] (and other jump commands) | Jump to specified mission item. |
| QGC mission item | 통신 | 설명 |
| ------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------------------------------------- |
| Mission start | [MAV_CMD_MISSION_START](MAV_CMD_MISSION_START) | Starts the mission. |
| Waypoint | [MAV_CMD_NAV_WAYPOINT](MAV_CMD_NAV_WAYPOINT) | Navigate to waypoint. |
| Return to launch | [MAV\_CMD\_NAV\_RETURN\_TO\_LAUNCH][MAV_CMD_NAV_RETURN_TO_LAUNCH] | Return to the launch location. |
| Change speed | [MAV\_CMD\_DO\_CHANGE\_SPEED][MAV_CMD_DO_CHANGE_SPEED] | Change the speed setpoint |
| Set launch location | [MAV_CMD_DO_SET_HOME](MAV_CMD_DO_SET_HOME) | Changes launch location to specified coordinates. |
| Jump to item (all) | [MAV\_CMD\_DO\_JUMP][MAV_CMD_DO_JUMP] (and other jump commands) | Jump to specified mission item. |
[MAV_CMD_MISSION_START]: https://mavlink.io/en/messages/common.html#MAV_CMD_MISSION_START
[MAV_CMD_NAV_WAYPOINT]: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_WAYPOINT
+6 -59
View File
@@ -33,67 +33,14 @@ the [Airframe Reference](../airframes/airframe_reference.md#vectored-6-dof-uuv):
- **MAIN7:** motor 7 CCW, stern starboard vertical, propeller CW
- **MAIN8:** motor 8 CCW, stern port vertical, propeller CCW
## Basic Control Axes
For underwater vehicles, motion is defined in terms of body axes:
- **Surge:** forward/back motion - translation along the body X axis.
- **Sway:** left/right motion - translation along the body Y axis.
- **Heave:** up/down motion - translation along the body Z axis.
- **Yaw:** rotation about the (vertical) body Z axis.
### Stick Mapping (Mode 2)
The mapping below illustrates the default joystick behavior:
- **Pitch stick (forward/back):** surge
- **Roll stick (left/right):** sway
- **Throttle stick (up/down):** heave
- **Yaw stick (left/right):** yaw
![RC Basic Commands](../../assets/flying/rc_mode2_mc_position_mode.png)
## Manual Modes
The following manual and assisted modes are currently supported on BlueROV2 Heavy:
| Mode | 설명 |
| ---------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| Manual | Direct manual control of thrust and yaw. |
| Stabilized | Manual control of thurst and yaw with roll/pitch stabilization. |
| Acro | Manual control of yaw-rate and direct thrust commands with roll/pitch stabilization. |
| Altitude | Manual control of x/y thrust and yaw. Control of height with PID, manually controlled by user. Keeps roll/pitch stabilized. |
| Position | Controls x, y, z and yaw with position hold when sticks are released. Keeps roll/pitch stabilized. |
## Joystick Stick Mode
BlueROV2 supports two joystick mappings for manual control, selected using the
[UUV_STICK_MODE](../advanced_config/parameter_reference.md#UUV_STICK_MODE) parameter.
By default, `UUV_STICK_MODE` is set to `0`, which enables the UUV stick mapping intended for vectored underwater vehicles.
### UUV_STICK_MODE = 0 (default)
This mode is intended for normal BlueROV2 operation.
In `Manual`, `Stabilized`, and `Acro` modes, the sticks command:
- **Pitch stick:** surge - moving stick up -> moving forward, +X translation in body frame.
- **Roll stick:** sway - moving stick right -> moving sideways right, +Y translation in body frame.
- **Throttle stick:** heave - moving stick up -> moving upwards, -Z translation in body frame (note the Z axis points Down of the vehicle in PX4).
- **Yaw stick:** yaw - moving stick right -> yawing to the right, +Z rotation in body frame.
In this mode, roll and pitch are kept level rather than commanded directly.
### UUV_STICK_MODE = 1
This mode enables the legacy multicopter-style stick mapping for `Manual`, `Stabilized`, and `Acro` modes:
- **Throttle stick:** surge - moving stick up -> moving forward, +X translation in body frame.
- **Roll stick:** roll - moving stick right -> rolling to the right side, +X rotation in body frame.
- **Pitch stick:** pitch - moving stick up -> pitching down, -X translation in body frame (note signs are switched to follow PX4 standard).
- **Yaw stick:** yaw - moving stick right -> yawing to the right, +Z rotation in body frame.
This mode is mainly provided for compatibility with older setups and user preference.
| Mode | 설명 |
| -------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- |
| Manual | Direct manual control of yaw and thrust. |
| Acro | Manual control of yaw/thrust, but keeps roll/pitch zero |
| Altitude | Manual control of x/y thrust and yaw. Control of height with PID, manually controlled by user. Keeps roll/pitch zero |
| Position | Controls x/y/z and yaw. Manually controlled by user. Keeps roll/pitch zero |
## 기체 설정
+3 -3
View File
@@ -6,15 +6,15 @@
Support for UUVs is [experimental](../airframes/index.md#experimental-vehicles).
Maintainer volunteers, [contribution](../contribute/index.md) of new features, new frame configurations, or other improvements would all be very welcome!
At time of writing manual and assisted manual modes are available for supported UUV frames, as well as ROS in offboard mode.
At time of writing it has only been tested using ROS in offboard mode.
The following features have not been implemented:
- Autonomous mission-style underwater workflows are still limited compared to aerial vehicles.
- 임무, 뎁스 홀드, 안정화 수동 제어 등과 같은 모드
- BlueRobotics gripper support.
:::
PX4 has basic support for UUVs. For BlueROV2 Heavy, PX4 currently supports Manual, Stabilized, Acro, Altitude and Position modes.
<a href="https://youtu.be/1sUaURmlmT8">유투브</a>
## Supported Frames
+46 -47
View File
@@ -14,52 +14,51 @@ PX4가 지원하는 VTOL 유형, 조립, 구성 및 비행 방법에 대하여
## VTOL 유형
PX4 supports the three most important/main VTOL types: [Standard VTOL](standardvtol.md), [Tiltrotor](tiltrotor.md), and [Tailsitter](tailsitter.md).
PX4는 세 가지 중요한 VTOL 유형을 지원합니다.
:::: tabs
:::tab 표준 VTOL
멀티콥터와 전진 비행을 위한 별도의 로터 및 비행 제어 장치.
이륙하고 로 착합니다.
![Vertical Technologies: Deltaquad](../../assets/airframes/vtol/vertical_technologies_deltaquad/hero_small.png)
- 별도의 호버링 및 전진 비행 추진 시스템으로 인한 중량 증가
- 전용 호버링 및 포워드 플라이트 액츄에이터로 제어가 가장 용이
- 호버링 가능
- Fuel engines can be used for forward flight propulsion
:::
:::tab 테일시터
Rotors permanently in fixed-wing position.
이륙하고 꼬리로 착륙합니다. 전체 차량이 앞으로 기울어져 전진 비행으로 전환합니다.
![wingtraone](../../assets/airframes/vtol/wingtraone/hero.jpg)
- 간단하고 견고함.
- 최소한의 액추에이터 세트
- 바람이 불면 제어하기 어려울 수 있음
- 동일한 액츄에이터가 사용되므로 호버링과 전진 비행의 효율성간의 균형
:::
:::tab 틸트로터
로터는 멀티콥터에서 전진 비행 방향으로 전환하기 위하여 90도 회전합니다.
이륙하고 배로 착지합니다.
![Eflight Confvergence](../../assets/airframes/vtol/eflite_convergence_pixfalcon/hero.jpg)
- 모터 틸트용 추가 액추에이터
- 기계적으로 복잡한 틸팅 메커니즘
- 더 많은 제어 권한으로 테일시터보다 호버링이 용이합니다.
:::
::::
<div class="grid_wrapper three_column">
<div class="grid_item">
<div class="grid_item_heading"><a href="tailsitter.html" title="Tailsitter"><big>Tailsitter</big></a></div>
<div class="grid_text">
Rotors permanently in fixed-wing position.
이륙하고 꼬리로 착륙합니다. 전체 차량이 앞으로 기울어져 전진 비행으로 전환합니다.
<img src="../../assets/airframes/vtol/wingtraone/hero.jpg" title="wingtraone" />
<ul>
<li>간단하고 견고함.</li>
<li>최소한의 액추에이터 세트</li>
<li>바람이 불면 제어하기 어려울 수 있음</li>
<li>동일한 액츄에이터가 사용되므로 호버링과 전진 비행의 효율성간의 균형</li>
</ul>
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><a href="tiltrotor.html" title="Tiltrotor"><big>Tiltrotor</big></a></div>
로터는 멀티콥터에서 전진 비행 방향으로 전환하기 위하여 90도 회전합니다.
이륙하고 로 착합니다.
<div class="grid_text">
<img src="../../assets/airframes/vtol/eflite_convergence_pixfalcon/hero.jpg" title="Eflight Confvergence" />
<ul>
<li>모터 틸트용 추가 액추에이터</li>
<li>기계적으로 복잡한 틸팅 메커니즘</li>
<li>더 많은 제어 권한으로 테일시터보다 호버링이 용이합니다.</li>
</ul>
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><a href="standardvtol.html" title="Standard VTOL"><big>Standard VTOL</big></a></div>
<div class="grid_text">
멀티콥터 전진 비행을 위한 별도의 로터 및 비행 제어 장치. 이륙하고 배로 착지합니다.
<img src="../../assets/airframes/vtol/vertical_technologies_deltaquad/hero_small.png" title="Vertical Technologies: Deltaquad" />
<ul>
<li>별도의 호버링 및 전진 비행 추진 시스템으로 인한 중량 증가</li>
<li>전용 호버링 및 포워드 플라이트 액츄에이터로 제어가 가장 용이 </li>
<li>호버링 가능</li>
<li>전진 비행 추진을 위한 연료 엔진 사용 가능</li>
</ul>
</div>
</div>
</div>
일반적으로, 기계적 복잡성이 증가함에 따라 기체의 비행이 용이할 수 있지만, 비용과 중량이가 증가합니다.
각 유형에는 장단점이 있으며, 이를 기반으로 성공적인 상업적인 벤처 회사들이 있습니다.
@@ -127,7 +126,7 @@ VTOL Control & Airspeed Fault Detection (PX4 Developer Summit 2019)
<!-- 20190704 -->
### Tailsitter {#tailsitter_video}
### 테일시터
[UAV Works VALAQ Patrol Tailsitter](https://www.valaqpatrol.com/valaq_patrol_technical_data/)
@@ -137,7 +136,7 @@ VTOL Control & Airspeed Fault Detection (PX4 Developer Summit 2019)
<lite-youtube videoid="acG0aTuf3f8" title="PX4 VTOL - Call for Testpilots"/>
### Tiltrotor {#tiltrotor_video}
### 틸트로터
[Convergence Tiltrotor](../frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md)
+32 -33
View File
@@ -89,36 +89,35 @@ This section contains videos that are specific to Tailsitter VTOL (videos that a
## ### Duo
:::: tabs
:::tab WingtraOne
[WingtraOne](https://wingtra.com/mapping-drone-fast-accurate-surveying/)
![Wingtra: WingtraOne VTOL Duo Tailsitter](../../assets/airframes/vtol/wingtraone/hero.jpg)
:::
:::tab Skypull
[Skypull](https://www.skypull.technology/)
![Skypull SP-1 VTOL QuadTailsitter](../../assets/airframes/vtol/skypull/skypull_sp1.jpg)
:::
:::tab TBS Caipiroshka
[TBS Caipiroshka](../frames_vtol/vtol_tailsitter_caipiroshka_pixracer.md)
![TBS Caipiroshka](../../assets/airframes/vtol/caipiroshka/caipiroshka.jpg)
:::
:::tab Woshark
[Woshark](http://uav-cas.ac.cn/WOSHARK/)
![Woshark](../../assets/airframes/vtol/xdwgood_ax1800/hero.jpg)
:::
:::tab VALAQ Patrol Tailsitter
[UAV Works VALAQ Patrol Tailsitter](https://www.valaqpatrol.com/valaq_patrol_technical_data/)
!["UAV Works VALAQ Patrol Tailsitte](../../assets/airframes/vtol/uav_works_valaq_patrol/hero.jpg)
:::
::::
<div class="grid_wrapper three_column">
<div class="grid_item">
<div class="grid_item_heading"><big><a href="https://wingtra.com/mapping-drone-fast-accurate-surveying/">WingtraOne</a></big></div>
<div class="grid_text">
<img src="../../assets/airframes/vtol/wingtraone/hero.jpg" title="Wingtra: WingtraOne VTOL Duo Tailsitter" alt="wingtraone" />
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><big><a href="https://www.skypull.technology/">Skypull</a></big></div>
<div class="grid_text">
<img title="Skypull SP-1 VTOL QuadTailsitter" src="../../assets/airframes/vtol/skypull/skypull_sp1.jpg" />
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><big><a href="../frames_vtol/vtol_tailsitter_caipiroshka_pixracer.html">TBS Caipiroshka</a></big></div>
<div class="grid_text">
<img title="TBS Caipiroshka" src="../../assets/airframes/vtol/caipiroshka/caipiroshka.jpg" />
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><big><a href="http://uav-cas.ac.cn/WOSHARK/">Woshark</a></big></div>
<div class="grid_text">
<img title="Woshark" src="../../assets/airframes/vtol/xdwgood_ax1800/hero.jpg" />
</div>
</div>
<div class="grid_item">
<div class="grid_item_heading"><big><a href="https://www.valaqpatrol.com/valaq_patrol_technical_data/">UAV Works VALAQ Patrol Tailsitter</a></big></div>
<div class="grid_text">
<img title="UAV Works VALAQ Patrol Tailsitter" src="../../assets/airframes/vtol/uav_works_valaq_patrol/hero.jpg" />
</div>
</div>
</div>
+188 -189
View File
@@ -96,206 +96,205 @@ They are not build into the module, and hence are neither published or subscribe
:::details
See messages
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [Rpm](../msg_docs/Rpm.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [LedControl](../msg_docs/LedControl.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [NeuralControl](../msg_docs/NeuralControl.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [DeviceInformation](../msg_docs/DeviceInformation.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [Mission](../msg_docs/Mission.md)
- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [InputRc](../msg_docs/InputRc.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
- [HomePositionV0](../msg_docs/HomePositionV0.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [EventV0](../msg_docs/EventV0.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [Vtx](../msg_docs/Vtx.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [Gripper](../msg_docs/Gripper.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [BatteryInfo](../msg_docs/BatteryInfo.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [Ping](../msg_docs/Ping.md)
- [GainCompression](../msg_docs/GainCompression.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [VehicleStatusV2](../msg_docs/VehicleStatusV2.md)
- [RaptorInput](../msg_docs/RaptorInput.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [Event](../msg_docs/Event.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [RaptorStatus](../msg_docs/RaptorStatus.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [SensorTemp](../msg_docs/SensorTemp.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [EscEepromRead](../msg_docs/EscEepromRead.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [GainCompression](../msg_docs/GainCompression.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [Vtx](../msg_docs/Vtx.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [EscEepromRead](../msg_docs/EscEepromRead.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [RaptorStatus](../msg_docs/RaptorStatus.md)
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [HomePositionV0](../msg_docs/HomePositionV0.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
- [InputRc](../msg_docs/InputRc.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [RaptorInput](../msg_docs/RaptorInput.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [Gripper](../msg_docs/Gripper.md)
- [EscReport](../msg_docs/EscReport.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [BatteryInfo](../msg_docs/BatteryInfo.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [LedControl](../msg_docs/LedControl.md)
- [Event](../msg_docs/Event.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [Rpm](../msg_docs/Rpm.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [EscEepromWrite](../msg_docs/EscEepromWrite.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [EscReport](../msg_docs/EscReport.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [EventV0](../msg_docs/EventV0.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [EscEepromWrite](../msg_docs/EscEepromWrite.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [Mission](../msg_docs/Mission.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [DeviceInformation](../msg_docs/DeviceInformation.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
- [NeuralControl](../msg_docs/NeuralControl.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [Ping](../msg_docs/Ping.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
:::
+9 -9
View File
@@ -8,14 +8,14 @@ pageClass: is-wide-page
## Fields
| 명칭 | 형식 | Unit [Frame] | Range/Enum | 설명 |
| --------------------------------------------------------------- | -------- | ---------------------------------------------------------------- | ---------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| timestamp | `uint64` | | | time since system start (microseconds) |
| safe_points_id | `uint32` | | | unique ID of active set of safe_point_items |
| is_evaluation_pending | `bool` | | | flag if the RTL point needs reevaluation (e.g. new safe points available, but need loading). |
| has_vtol_approach | `bool` | | | flag if approaches are defined for current RTL_TYPE parameter setting |
| rtl_type | `uint8` | | | Type of RTL chosen |
| safe_point_index | `uint8` | | | index of the chosen safe point, UINT8_MAX if no rally point was chosen |
| 명칭 | 형식 | Unit [Frame] | Range/Enum | 설명 |
| --------------------------------------------------------------- | -------- | ---------------------------------------------------------------- | ---------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| timestamp | `uint64` | | | time since system start (microseconds) |
| safe_points_id | `uint32` | | | unique ID of active set of safe_point_items |
| is_evaluation_pending | `bool` | | | flag if the RTL point needs reevaluation (e.g. new safe points available, but need loading). |
| has_vtol_approach | `bool` | | | flag if approaches are defined for current RTL_TYPE parameter setting |
| rtl_type | `uint8` | | | Type of RTL chosen |
| safe_point_index | `uint8` | | | index of the chosen safe point, if in RTL_STATUS_TYPE_DIRECT_SAFE_POINT mode |
## Constants
@@ -43,7 +43,7 @@ bool is_evaluation_pending # flag if the RTL point needs reevaluation (e.
bool has_vtol_approach # flag if approaches are defined for current RTL_TYPE parameter setting
uint8 rtl_type # Type of RTL chosen
uint8 safe_point_index # index of the chosen safe point, UINT8_MAX if no rally point was chosen
uint8 safe_point_index # index of the chosen safe point, if in RTL_STATUS_TYPE_DIRECT_SAFE_POINT mode
uint8 RTL_STATUS_TYPE_NONE=0 # pending if evaluation can't pe performed currently e.g. when it is still loading the safe points
uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # chosen to directly go to a safe point or home position
+79 -57
View File
@@ -25,6 +25,7 @@ Encodes the system state of the vehicle published by commander.
| nav_state_display | `uint8` | | | User-visible nav state sent via MAVLink (executor state if active, otherwise nav_state) |
| valid_nav_states_mask | `uint32` | | | Bitmask for all valid nav_state values |
| can_set_nav_states_mask | `uint32` | | | Bitmask for all modes that a user can select |
| failure_detector_status | `uint16` | | | |
| hil_state | `uint8` | | | |
| vehicle_type | `uint8` | | | |
| failsafe | `bool` | | | true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...) |
@@ -55,62 +56,71 @@ Encodes the system state of the vehicle published by commander.
## Constants
| 명칭 | 형식 | Value | 설명 |
| --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------- | ----- | ----------------------------------------------------- |
| <a id="#MESSAGE_VERSION"></a> MESSAGE_VERSION | `uint32` | 3 | |
| <a id="#ARMING_STATE_DISARMED"></a> ARMING_STATE_DISARMED | `uint8` | 1 | |
| <a id="#ARMING_STATE_ARMED"></a> ARMING_STATE_ARMED | `uint8` | 2 | |
| <a id="#ARM_DISARM_REASON_STICK_GESTURE"></a> ARM_DISARM_REASON_STICK_GESTURE | `uint8` | 1 | |
| <a id="#ARM_DISARM_REASON_RC_SWITCH"></a> ARM_DISARM_REASON_RC_SWITCH | `uint8` | 2 | |
| <a id="#ARM_DISARM_REASON_COMMAND_INTERNAL"></a> ARM_DISARM_REASON_COMMAND_INTERNAL | `uint8` | 3 | |
| <a id="#ARM_DISARM_REASON_COMMAND_EXTERNAL"></a> ARM_DISARM_REASON_COMMAND_EXTERNAL | `uint8` | 4 | |
| <a id="#ARM_DISARM_REASON_MISSION_START"></a> ARM_DISARM_REASON_MISSION_START | `uint8` | 5 | |
| <a id="#ARM_DISARM_REASON_LANDING"></a> ARM_DISARM_REASON_LANDING | `uint8` | 6 | |
| <a id="#ARM_DISARM_REASON_PREFLIGHT_INACTION"></a> ARM_DISARM_REASON_PREFLIGHT_INACTION | `uint8` | 7 | |
| <a id="#ARM_DISARM_REASON_KILL_SWITCH"></a> ARM_DISARM_REASON_KILL_SWITCH | `uint8` | 8 | |
| <a id="#ARM_DISARM_REASON_RC_BUTTON"></a> ARM_DISARM_REASON_RC_BUTTON | `uint8` | 13 | |
| <a id="#ARM_DISARM_REASON_FAILSAFE"></a> ARM_DISARM_REASON_FAILSAFE | `uint8` | 14 | |
| <a id="#NAVIGATION_STATE_MANUAL"></a> NAVIGATION_STATE_MANUAL | `uint8` | 0 | Manual mode |
| <a id="#NAVIGATION_STATE_ALTCTL"></a> NAVIGATION_STATE_ALTCTL | `uint8` | 1 | Altitude control mode |
| <a id="#NAVIGATION_STATE_POSCTL"></a> NAVIGATION_STATE_POSCTL | `uint8` | 2 | Position control mode |
| <a id="#NAVIGATION_STATE_AUTO_MISSION"></a> NAVIGATION_STATE_AUTO_MISSION | `uint8` | 3 | Auto mission mode |
| <a id="#NAVIGATION_STATE_AUTO_LOITER"></a> NAVIGATION_STATE_AUTO_LOITER | `uint8` | 4 | Auto loiter mode |
| <a id="#NAVIGATION_STATE_AUTO_RTL"></a> NAVIGATION_STATE_AUTO_RTL | `uint8` | 5 | Auto return to launch mode |
| <a id="#NAVIGATION_STATE_POSITION_SLOW"></a> NAVIGATION_STATE_POSITION_SLOW | `uint8` | 6 | |
| <a id="#NAVIGATION_STATE_FREE5"></a> NAVIGATION_STATE_FREE5 | `uint8` | 7 | |
| <a id="#NAVIGATION_STATE_ALTITUDE_CRUISE"></a> NAVIGATION_STATE_ALTITUDE_CRUISE | `uint8` | 8 | Altitude with Cruise mode |
| <a id="#NAVIGATION_STATE_FREE3"></a> NAVIGATION_STATE_FREE3 | `uint8` | 9 | |
| <a id="#NAVIGATION_STATE_ACRO"></a> NAVIGATION_STATE_ACRO | `uint8` | 10 | Acro mode |
| <a id="#NAVIGATION_STATE_FREE2"></a> NAVIGATION_STATE_FREE2 | `uint8` | 11 | |
| <a id="#NAVIGATION_STATE_DESCEND"></a> NAVIGATION_STATE_DESCEND | `uint8` | 12 | Descend mode (no position control) |
| <a id="#NAVIGATION_STATE_TERMINATION"></a> NAVIGATION_STATE_TERMINATION | `uint8` | 13 | Termination mode |
| <a id="#NAVIGATION_STATE_OFFBOARD"></a> NAVIGATION_STATE_OFFBOARD | `uint8` | 14 | |
| <a id="#NAVIGATION_STATE_STAB"></a> NAVIGATION_STATE_STAB | `uint8` | 15 | Stabilized mode |
| <a id="#NAVIGATION_STATE_FREE1"></a> NAVIGATION_STATE_FREE1 | `uint8` | 16 | |
| <a id="#NAVIGATION_STATE_AUTO_TAKEOFF"></a> NAVIGATION_STATE_AUTO_TAKEOFF | `uint8` | 17 | Takeoff |
| <a id="#NAVIGATION_STATE_AUTO_LAND"></a> NAVIGATION_STATE_AUTO_LAND | `uint8` | 18 | Land |
| <a id="#NAVIGATION_STATE_AUTO_FOLLOW_TARGET"></a> NAVIGATION_STATE_AUTO_FOLLOW_TARGET | `uint8` | 19 | Auto Follow |
| <a id="#NAVIGATION_STATE_AUTO_PRECLAND"></a> NAVIGATION_STATE_AUTO_PRECLAND | `uint8` | 20 | Precision land with landing target |
| <a id="#NAVIGATION_STATE_ORBIT"></a> NAVIGATION_STATE_ORBIT | `uint8` | 21 | Orbit in a circle |
| <a id="#NAVIGATION_STATE_AUTO_VTOL_TAKEOFF"></a> NAVIGATION_STATE_AUTO_VTOL_TAKEOFF | `uint8` | 22 | Takeoff, transition, establish loiter |
| <a id="#NAVIGATION_STATE_EXTERNAL1"></a> NAVIGATION_STATE_EXTERNAL1 | `uint8` | 23 | |
| <a id="#NAVIGATION_STATE_EXTERNAL2"></a> NAVIGATION_STATE_EXTERNAL2 | `uint8` | 24 | |
| <a id="#NAVIGATION_STATE_EXTERNAL3"></a> NAVIGATION_STATE_EXTERNAL3 | `uint8` | 25 | |
| <a id="#NAVIGATION_STATE_EXTERNAL4"></a> NAVIGATION_STATE_EXTERNAL4 | `uint8` | 26 | |
| <a id="#NAVIGATION_STATE_EXTERNAL5"></a> NAVIGATION_STATE_EXTERNAL5 | `uint8` | 27 | |
| <a id="#NAVIGATION_STATE_EXTERNAL6"></a> NAVIGATION_STATE_EXTERNAL6 | `uint8` | 28 | |
| <a id="#NAVIGATION_STATE_EXTERNAL7"></a> NAVIGATION_STATE_EXTERNAL7 | `uint8` | 29 | |
| <a id="#NAVIGATION_STATE_EXTERNAL8"></a> NAVIGATION_STATE_EXTERNAL8 | `uint8` | 30 | |
| <a id="#NAVIGATION_STATE_MAX"></a> NAVIGATION_STATE_MAX | `uint8` | 31 | |
| <a id="#HIL_STATE_OFF"></a> HIL_STATE_OFF | `uint8` | 0 | |
| <a id="#HIL_STATE_ON"></a> HIL_STATE_ON | `uint8` | 1 | |
| <a id="#VEHICLE_TYPE_UNSPECIFIED"></a> VEHICLE_TYPE_UNSPECIFIED | `uint8` | 0 | |
| <a id="#VEHICLE_TYPE_ROTARY_WING"></a> VEHICLE_TYPE_ROTARY_WING | `uint8` | 1 | |
| <a id="#VEHICLE_TYPE_FIXED_WING"></a> VEHICLE_TYPE_FIXED_WING | `uint8` | 2 | |
| <a id="#VEHICLE_TYPE_ROVER"></a> VEHICLE_TYPE_ROVER | `uint8` | 3 | |
| <a id="#FAILSAFE_DEFER_STATE_DISABLED"></a> FAILSAFE_DEFER_STATE_DISABLED | `uint8` | 0 | |
| <a id="#FAILSAFE_DEFER_STATE_ENABLED"></a> FAILSAFE_DEFER_STATE_ENABLED | `uint8` | 1 | |
| <a id="#FAILSAFE_DEFER_STATE_WOULD_FAILSAFE"></a> FAILSAFE_DEFER_STATE_WOULD_FAILSAFE | `uint8` | 2 | Failsafes deferred, but would trigger a failsafe |
| 명칭 | 형식 | Value | 설명 |
| --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------- | ----- | ----------------------------------------------------------------------------- |
| <a id="#MESSAGE_VERSION"></a> MESSAGE_VERSION | `uint32` | 2 | |
| <a id="#ARMING_STATE_DISARMED"></a> ARMING_STATE_DISARMED | `uint8` | 1 | |
| <a id="#ARMING_STATE_ARMED"></a> ARMING_STATE_ARMED | `uint8` | 2 | |
| <a id="#ARM_DISARM_REASON_STICK_GESTURE"></a> ARM_DISARM_REASON_STICK_GESTURE | `uint8` | 1 | |
| <a id="#ARM_DISARM_REASON_RC_SWITCH"></a> ARM_DISARM_REASON_RC_SWITCH | `uint8` | 2 | |
| <a id="#ARM_DISARM_REASON_COMMAND_INTERNAL"></a> ARM_DISARM_REASON_COMMAND_INTERNAL | `uint8` | 3 | |
| <a id="#ARM_DISARM_REASON_COMMAND_EXTERNAL"></a> ARM_DISARM_REASON_COMMAND_EXTERNAL | `uint8` | 4 | |
| <a id="#ARM_DISARM_REASON_MISSION_START"></a> ARM_DISARM_REASON_MISSION_START | `uint8` | 5 | |
| <a id="#ARM_DISARM_REASON_LANDING"></a> ARM_DISARM_REASON_LANDING | `uint8` | 6 | |
| <a id="#ARM_DISARM_REASON_PREFLIGHT_INACTION"></a> ARM_DISARM_REASON_PREFLIGHT_INACTION | `uint8` | 7 | |
| <a id="#ARM_DISARM_REASON_KILL_SWITCH"></a> ARM_DISARM_REASON_KILL_SWITCH | `uint8` | 8 | |
| <a id="#ARM_DISARM_REASON_RC_BUTTON"></a> ARM_DISARM_REASON_RC_BUTTON | `uint8` | 13 | |
| <a id="#ARM_DISARM_REASON_FAILSAFE"></a> ARM_DISARM_REASON_FAILSAFE | `uint8` | 14 | |
| <a id="#NAVIGATION_STATE_MANUAL"></a> NAVIGATION_STATE_MANUAL | `uint8` | 0 | Manual mode |
| <a id="#NAVIGATION_STATE_ALTCTL"></a> NAVIGATION_STATE_ALTCTL | `uint8` | 1 | Altitude control mode |
| <a id="#NAVIGATION_STATE_POSCTL"></a> NAVIGATION_STATE_POSCTL | `uint8` | 2 | Position control mode |
| <a id="#NAVIGATION_STATE_AUTO_MISSION"></a> NAVIGATION_STATE_AUTO_MISSION | `uint8` | 3 | Auto mission mode |
| <a id="#NAVIGATION_STATE_AUTO_LOITER"></a> NAVIGATION_STATE_AUTO_LOITER | `uint8` | 4 | Auto loiter mode |
| <a id="#NAVIGATION_STATE_AUTO_RTL"></a> NAVIGATION_STATE_AUTO_RTL | `uint8` | 5 | Auto return to launch mode |
| <a id="#NAVIGATION_STATE_POSITION_SLOW"></a> NAVIGATION_STATE_POSITION_SLOW | `uint8` | 6 | |
| <a id="#NAVIGATION_STATE_FREE5"></a> NAVIGATION_STATE_FREE5 | `uint8` | 7 | |
| <a id="#NAVIGATION_STATE_ALTITUDE_CRUISE"></a> NAVIGATION_STATE_ALTITUDE_CRUISE | `uint8` | 8 | Altitude with Cruise mode |
| <a id="#NAVIGATION_STATE_FREE3"></a> NAVIGATION_STATE_FREE3 | `uint8` | 9 | |
| <a id="#NAVIGATION_STATE_ACRO"></a> NAVIGATION_STATE_ACRO | `uint8` | 10 | Acro mode |
| <a id="#NAVIGATION_STATE_FREE2"></a> NAVIGATION_STATE_FREE2 | `uint8` | 11 | |
| <a id="#NAVIGATION_STATE_DESCEND"></a> NAVIGATION_STATE_DESCEND | `uint8` | 12 | Descend mode (no position control) |
| <a id="#NAVIGATION_STATE_TERMINATION"></a> NAVIGATION_STATE_TERMINATION | `uint8` | 13 | Termination mode |
| <a id="#NAVIGATION_STATE_OFFBOARD"></a> NAVIGATION_STATE_OFFBOARD | `uint8` | 14 | |
| <a id="#NAVIGATION_STATE_STAB"></a> NAVIGATION_STATE_STAB | `uint8` | 15 | Stabilized mode |
| <a id="#NAVIGATION_STATE_FREE1"></a> NAVIGATION_STATE_FREE1 | `uint8` | 16 | |
| <a id="#NAVIGATION_STATE_AUTO_TAKEOFF"></a> NAVIGATION_STATE_AUTO_TAKEOFF | `uint8` | 17 | Takeoff |
| <a id="#NAVIGATION_STATE_AUTO_LAND"></a> NAVIGATION_STATE_AUTO_LAND | `uint8` | 18 | Land |
| <a id="#NAVIGATION_STATE_AUTO_FOLLOW_TARGET"></a> NAVIGATION_STATE_AUTO_FOLLOW_TARGET | `uint8` | 19 | Auto Follow |
| <a id="#NAVIGATION_STATE_AUTO_PRECLAND"></a> NAVIGATION_STATE_AUTO_PRECLAND | `uint8` | 20 | Precision land with landing target |
| <a id="#NAVIGATION_STATE_ORBIT"></a> NAVIGATION_STATE_ORBIT | `uint8` | 21 | Orbit in a circle |
| <a id="#NAVIGATION_STATE_AUTO_VTOL_TAKEOFF"></a> NAVIGATION_STATE_AUTO_VTOL_TAKEOFF | `uint8` | 22 | Takeoff, transition, establish loiter |
| <a id="#NAVIGATION_STATE_EXTERNAL1"></a> NAVIGATION_STATE_EXTERNAL1 | `uint8` | 23 | |
| <a id="#NAVIGATION_STATE_EXTERNAL2"></a> NAVIGATION_STATE_EXTERNAL2 | `uint8` | 24 | |
| <a id="#NAVIGATION_STATE_EXTERNAL3"></a> NAVIGATION_STATE_EXTERNAL3 | `uint8` | 25 | |
| <a id="#NAVIGATION_STATE_EXTERNAL4"></a> NAVIGATION_STATE_EXTERNAL4 | `uint8` | 26 | |
| <a id="#NAVIGATION_STATE_EXTERNAL5"></a> NAVIGATION_STATE_EXTERNAL5 | `uint8` | 27 | |
| <a id="#NAVIGATION_STATE_EXTERNAL6"></a> NAVIGATION_STATE_EXTERNAL6 | `uint8` | 28 | |
| <a id="#NAVIGATION_STATE_EXTERNAL7"></a> NAVIGATION_STATE_EXTERNAL7 | `uint8` | 29 | |
| <a id="#NAVIGATION_STATE_EXTERNAL8"></a> NAVIGATION_STATE_EXTERNAL8 | `uint8` | 30 | |
| <a id="#NAVIGATION_STATE_MAX"></a> NAVIGATION_STATE_MAX | `uint8` | 31 | |
| <a id="#FAILURE_NONE"></a> FAILURE_NONE | `uint16` | 0 | |
| <a id="#FAILURE_ROLL"></a> FAILURE_ROLL | `uint16` | 1 | (1 << 0) |
| <a id="#FAILURE_PITCH"></a> FAILURE_PITCH | `uint16` | 2 | (1 << 1) |
| <a id="#FAILURE_ALT"></a> FAILURE_ALT | `uint16` | 4 | (1 << 2) |
| <a id="#FAILURE_EXT"></a> FAILURE_EXT | `uint16` | 8 | (1 << 3) |
| <a id="#FAILURE_ARM_ESC"></a> FAILURE_ARM_ESC | `uint16` | 16 | (1 << 4) |
| <a id="#FAILURE_BATTERY"></a> FAILURE_BATTERY | `uint16` | 32 | (1 << 5) |
| <a id="#FAILURE_IMBALANCED_PROP"></a> FAILURE_IMBALANCED_PROP | `uint16` | 64 | (1 << 6) |
| <a id="#FAILURE_MOTOR"></a> FAILURE_MOTOR | `uint16` | 128 | (1 << 7) |
| <a id="#HIL_STATE_OFF"></a> HIL_STATE_OFF | `uint8` | 0 | |
| <a id="#HIL_STATE_ON"></a> HIL_STATE_ON | `uint8` | 1 | |
| <a id="#VEHICLE_TYPE_UNSPECIFIED"></a> VEHICLE_TYPE_UNSPECIFIED | `uint8` | 0 | |
| <a id="#VEHICLE_TYPE_ROTARY_WING"></a> VEHICLE_TYPE_ROTARY_WING | `uint8` | 1 | |
| <a id="#VEHICLE_TYPE_FIXED_WING"></a> VEHICLE_TYPE_FIXED_WING | `uint8` | 2 | |
| <a id="#VEHICLE_TYPE_ROVER"></a> VEHICLE_TYPE_ROVER | `uint8` | 3 | |
| <a id="#FAILSAFE_DEFER_STATE_DISABLED"></a> FAILSAFE_DEFER_STATE_DISABLED | `uint8` | 0 | |
| <a id="#FAILSAFE_DEFER_STATE_ENABLED"></a> FAILSAFE_DEFER_STATE_ENABLED | `uint8` | 1 | |
| <a id="#FAILSAFE_DEFER_STATE_WOULD_FAILSAFE"></a> FAILSAFE_DEFER_STATE_WOULD_FAILSAFE | `uint8` | 2 | Failsafes deferred, but would trigger a failsafe |
## Source Message
@@ -122,7 +132,7 @@ Click here to see original file
```c
# Encodes the system state of the vehicle published by commander
uint32 MESSAGE_VERSION = 3
uint32 MESSAGE_VERSION = 2
uint64 timestamp # time since system start (microseconds)
@@ -190,6 +200,18 @@ uint8 nav_state_display # User-visible nav state sent vi
uint32 valid_nav_states_mask # Bitmask for all valid nav_state values
uint32 can_set_nav_states_mask # Bitmask for all modes that a user can select
# Bitmask of detected failures
uint16 failure_detector_status
uint16 FAILURE_NONE = 0
uint16 FAILURE_ROLL = 1 # (1 << 0)
uint16 FAILURE_PITCH = 2 # (1 << 1)
uint16 FAILURE_ALT = 4 # (1 << 2)
uint16 FAILURE_EXT = 8 # (1 << 3)
uint16 FAILURE_ARM_ESC = 16 # (1 << 4)
uint16 FAILURE_BATTERY = 32 # (1 << 5)
uint16 FAILURE_IMBALANCED_PROP = 64 # (1 << 6)
uint16 FAILURE_MOTOR = 128 # (1 << 7)
uint8 hil_state
uint8 HIL_STATE_OFF = 0
uint8 HIL_STATE_ON = 1
-270
View File
@@ -1,270 +0,0 @@
---
pageClass: is-wide-page
---
# VehicleStatusV2 (UORB message)
Encodes the system state of the vehicle published by commander.
**TOPICS:** vehicle_status_v2
## Fields
| 명칭 | 형식 | Unit [Frame] | Range/Enum | 설명 |
| ---------------------------------------------------------------------------------------------------------------- | -------- | ---------------------------------------------------------------- | ---------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| timestamp | `uint64` | | | time since system start (microseconds) |
| armed_time | `uint64` | | | Arming timestamp (microseconds) |
| takeoff_time | `uint64` | | | Takeoff timestamp (microseconds) |
| arming_state | `uint8` | | | |
| latest_arming_reason | `uint8` | | | |
| latest_disarming_reason | `uint8` | | | |
| nav_state_timestamp | `uint64` | | | time when current nav_state activated |
| nav_state_user_intention | `uint8` | | | Mode that the user selected (might be different from nav_state in a failsafe situation) |
| nav_state | `uint8` | | | Currently active mode |
| executor_in_charge | `uint8` | | | Current mode executor in charge (0=Autopilot) |
| nav_state_display | `uint8` | | | User-visible nav state sent via MAVLink (executor state if active, otherwise nav_state) |
| valid_nav_states_mask | `uint32` | | | Bitmask for all valid nav_state values |
| can_set_nav_states_mask | `uint32` | | | Bitmask for all modes that a user can select |
| failure_detector_status | `uint16` | | | |
| hil_state | `uint8` | | | |
| vehicle_type | `uint8` | | | |
| failsafe | `bool` | | | true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...) |
| failsafe_and_user_took_over | `bool` | | | true if system is in failsafe state but the user took over control |
| failsafe_defer_state | `uint8` | | | one of FAILSAFE_DEFER_STATE_\* |
| gcs_connection_lost | `bool` | | | datalink to GCS lost |
| gcs_connection_lost_counter | `uint8` | | | counts unique GCS connection lost events |
| high_latency_data_link_lost | `bool` | | | Set to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost |
| is_vtol | `bool` | | | True if the system is VTOL capable |
| is_vtol_tailsitter | `bool` | | | True if the system performs a 90° pitch down rotation during transition from MC to FW |
| in_transition_mode | `bool` | | | True if VTOL is doing a transition |
| in_transition_to_fw | `bool` | | | True if VTOL is doing a transition from MC to FW |
| system_type | `uint8` | | | system type, contains mavlink MAV_TYPE |
| system_id | `uint8` | | | system id, contains MAVLink's system ID field |
| component_id | `uint8` | | | subsystem / component id, contains MAVLink's component ID field |
| safety_button_available | `bool` | | | Set to true if a safety button is connected |
| safety_off | `bool` | | | Set to true if safety is off |
| power_input_valid | `bool` | | | set if input power is valid |
| usb_connected | `bool` | | | set to true (never cleared) once telemetry received from usb link |
| open_drone_id_system_present | `bool` | | | |
| open_drone_id_system_healthy | `bool` | | | |
| parachute_system_present | `bool` | | | |
| parachute_system_healthy | `bool` | | | |
| traffic_avoidance_system_present | `bool` | | | |
| rc_calibration_in_progress | `bool` | | | |
| calibration_enabled | `bool` | | | |
| pre_flight_checks_pass | `bool` | | | true if all checks necessary to arm pass |
## Constants
| 명칭 | 형식 | Value | 설명 |
| --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------- | ----- | ----------------------------------------------------------------------------- |
| <a id="#MESSAGE_VERSION"></a> MESSAGE_VERSION | `uint32` | 2 | |
| <a id="#ARMING_STATE_DISARMED"></a> ARMING_STATE_DISARMED | `uint8` | 1 | |
| <a id="#ARMING_STATE_ARMED"></a> ARMING_STATE_ARMED | `uint8` | 2 | |
| <a id="#ARM_DISARM_REASON_STICK_GESTURE"></a> ARM_DISARM_REASON_STICK_GESTURE | `uint8` | 1 | |
| <a id="#ARM_DISARM_REASON_RC_SWITCH"></a> ARM_DISARM_REASON_RC_SWITCH | `uint8` | 2 | |
| <a id="#ARM_DISARM_REASON_COMMAND_INTERNAL"></a> ARM_DISARM_REASON_COMMAND_INTERNAL | `uint8` | 3 | |
| <a id="#ARM_DISARM_REASON_COMMAND_EXTERNAL"></a> ARM_DISARM_REASON_COMMAND_EXTERNAL | `uint8` | 4 | |
| <a id="#ARM_DISARM_REASON_MISSION_START"></a> ARM_DISARM_REASON_MISSION_START | `uint8` | 5 | |
| <a id="#ARM_DISARM_REASON_LANDING"></a> ARM_DISARM_REASON_LANDING | `uint8` | 6 | |
| <a id="#ARM_DISARM_REASON_PREFLIGHT_INACTION"></a> ARM_DISARM_REASON_PREFLIGHT_INACTION | `uint8` | 7 | |
| <a id="#ARM_DISARM_REASON_KILL_SWITCH"></a> ARM_DISARM_REASON_KILL_SWITCH | `uint8` | 8 | |
| <a id="#ARM_DISARM_REASON_RC_BUTTON"></a> ARM_DISARM_REASON_RC_BUTTON | `uint8` | 13 | |
| <a id="#ARM_DISARM_REASON_FAILSAFE"></a> ARM_DISARM_REASON_FAILSAFE | `uint8` | 14 | |
| <a id="#NAVIGATION_STATE_MANUAL"></a> NAVIGATION_STATE_MANUAL | `uint8` | 0 | Manual mode |
| <a id="#NAVIGATION_STATE_ALTCTL"></a> NAVIGATION_STATE_ALTCTL | `uint8` | 1 | Altitude control mode |
| <a id="#NAVIGATION_STATE_POSCTL"></a> NAVIGATION_STATE_POSCTL | `uint8` | 2 | Position control mode |
| <a id="#NAVIGATION_STATE_AUTO_MISSION"></a> NAVIGATION_STATE_AUTO_MISSION | `uint8` | 3 | Auto mission mode |
| <a id="#NAVIGATION_STATE_AUTO_LOITER"></a> NAVIGATION_STATE_AUTO_LOITER | `uint8` | 4 | Auto loiter mode |
| <a id="#NAVIGATION_STATE_AUTO_RTL"></a> NAVIGATION_STATE_AUTO_RTL | `uint8` | 5 | Auto return to launch mode |
| <a id="#NAVIGATION_STATE_POSITION_SLOW"></a> NAVIGATION_STATE_POSITION_SLOW | `uint8` | 6 | |
| <a id="#NAVIGATION_STATE_FREE5"></a> NAVIGATION_STATE_FREE5 | `uint8` | 7 | |
| <a id="#NAVIGATION_STATE_ALTITUDE_CRUISE"></a> NAVIGATION_STATE_ALTITUDE_CRUISE | `uint8` | 8 | Altitude with Cruise mode |
| <a id="#NAVIGATION_STATE_FREE3"></a> NAVIGATION_STATE_FREE3 | `uint8` | 9 | |
| <a id="#NAVIGATION_STATE_ACRO"></a> NAVIGATION_STATE_ACRO | `uint8` | 10 | Acro mode |
| <a id="#NAVIGATION_STATE_FREE2"></a> NAVIGATION_STATE_FREE2 | `uint8` | 11 | |
| <a id="#NAVIGATION_STATE_DESCEND"></a> NAVIGATION_STATE_DESCEND | `uint8` | 12 | Descend mode (no position control) |
| <a id="#NAVIGATION_STATE_TERMINATION"></a> NAVIGATION_STATE_TERMINATION | `uint8` | 13 | Termination mode |
| <a id="#NAVIGATION_STATE_OFFBOARD"></a> NAVIGATION_STATE_OFFBOARD | `uint8` | 14 | |
| <a id="#NAVIGATION_STATE_STAB"></a> NAVIGATION_STATE_STAB | `uint8` | 15 | Stabilized mode |
| <a id="#NAVIGATION_STATE_FREE1"></a> NAVIGATION_STATE_FREE1 | `uint8` | 16 | |
| <a id="#NAVIGATION_STATE_AUTO_TAKEOFF"></a> NAVIGATION_STATE_AUTO_TAKEOFF | `uint8` | 17 | Takeoff |
| <a id="#NAVIGATION_STATE_AUTO_LAND"></a> NAVIGATION_STATE_AUTO_LAND | `uint8` | 18 | Land |
| <a id="#NAVIGATION_STATE_AUTO_FOLLOW_TARGET"></a> NAVIGATION_STATE_AUTO_FOLLOW_TARGET | `uint8` | 19 | Auto Follow |
| <a id="#NAVIGATION_STATE_AUTO_PRECLAND"></a> NAVIGATION_STATE_AUTO_PRECLAND | `uint8` | 20 | Precision land with landing target |
| <a id="#NAVIGATION_STATE_ORBIT"></a> NAVIGATION_STATE_ORBIT | `uint8` | 21 | Orbit in a circle |
| <a id="#NAVIGATION_STATE_AUTO_VTOL_TAKEOFF"></a> NAVIGATION_STATE_AUTO_VTOL_TAKEOFF | `uint8` | 22 | Takeoff, transition, establish loiter |
| <a id="#NAVIGATION_STATE_EXTERNAL1"></a> NAVIGATION_STATE_EXTERNAL1 | `uint8` | 23 | |
| <a id="#NAVIGATION_STATE_EXTERNAL2"></a> NAVIGATION_STATE_EXTERNAL2 | `uint8` | 24 | |
| <a id="#NAVIGATION_STATE_EXTERNAL3"></a> NAVIGATION_STATE_EXTERNAL3 | `uint8` | 25 | |
| <a id="#NAVIGATION_STATE_EXTERNAL4"></a> NAVIGATION_STATE_EXTERNAL4 | `uint8` | 26 | |
| <a id="#NAVIGATION_STATE_EXTERNAL5"></a> NAVIGATION_STATE_EXTERNAL5 | `uint8` | 27 | |
| <a id="#NAVIGATION_STATE_EXTERNAL6"></a> NAVIGATION_STATE_EXTERNAL6 | `uint8` | 28 | |
| <a id="#NAVIGATION_STATE_EXTERNAL7"></a> NAVIGATION_STATE_EXTERNAL7 | `uint8` | 29 | |
| <a id="#NAVIGATION_STATE_EXTERNAL8"></a> NAVIGATION_STATE_EXTERNAL8 | `uint8` | 30 | |
| <a id="#NAVIGATION_STATE_MAX"></a> NAVIGATION_STATE_MAX | `uint8` | 31 | |
| <a id="#FAILURE_NONE"></a> FAILURE_NONE | `uint16` | 0 | |
| <a id="#FAILURE_ROLL"></a> FAILURE_ROLL | `uint16` | 1 | (1 << 0) |
| <a id="#FAILURE_PITCH"></a> FAILURE_PITCH | `uint16` | 2 | (1 << 1) |
| <a id="#FAILURE_ALT"></a> FAILURE_ALT | `uint16` | 4 | (1 << 2) |
| <a id="#FAILURE_EXT"></a> FAILURE_EXT | `uint16` | 8 | (1 << 3) |
| <a id="#FAILURE_ARM_ESC"></a> FAILURE_ARM_ESC | `uint16` | 16 | (1 << 4) |
| <a id="#FAILURE_BATTERY"></a> FAILURE_BATTERY | `uint16` | 32 | (1 << 5) |
| <a id="#FAILURE_IMBALANCED_PROP"></a> FAILURE_IMBALANCED_PROP | `uint16` | 64 | (1 << 6) |
| <a id="#FAILURE_MOTOR"></a> FAILURE_MOTOR | `uint16` | 128 | (1 << 7) |
| <a id="#HIL_STATE_OFF"></a> HIL_STATE_OFF | `uint8` | 0 | |
| <a id="#HIL_STATE_ON"></a> HIL_STATE_ON | `uint8` | 1 | |
| <a id="#VEHICLE_TYPE_UNSPECIFIED"></a> VEHICLE_TYPE_UNSPECIFIED | `uint8` | 0 | |
| <a id="#VEHICLE_TYPE_ROTARY_WING"></a> VEHICLE_TYPE_ROTARY_WING | `uint8` | 1 | |
| <a id="#VEHICLE_TYPE_FIXED_WING"></a> VEHICLE_TYPE_FIXED_WING | `uint8` | 2 | |
| <a id="#VEHICLE_TYPE_ROVER"></a> VEHICLE_TYPE_ROVER | `uint8` | 3 | |
| <a id="#FAILSAFE_DEFER_STATE_DISABLED"></a> FAILSAFE_DEFER_STATE_DISABLED | `uint8` | 0 | |
| <a id="#FAILSAFE_DEFER_STATE_ENABLED"></a> FAILSAFE_DEFER_STATE_ENABLED | `uint8` | 1 | |
| <a id="#FAILSAFE_DEFER_STATE_WOULD_FAILSAFE"></a> FAILSAFE_DEFER_STATE_WOULD_FAILSAFE | `uint8` | 2 | Failsafes deferred, but would trigger a failsafe |
## Source Message
[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleStatusV2.msg)
:::details
Click here to see original file
```c
# Encodes the system state of the vehicle published by commander
uint32 MESSAGE_VERSION = 2
uint64 timestamp # time since system start (microseconds)
uint64 armed_time # Arming timestamp (microseconds)
uint64 takeoff_time # Takeoff timestamp (microseconds)
uint8 arming_state
uint8 ARMING_STATE_DISARMED = 1
uint8 ARMING_STATE_ARMED = 2
uint8 latest_arming_reason
uint8 latest_disarming_reason
uint8 ARM_DISARM_REASON_STICK_GESTURE = 1
uint8 ARM_DISARM_REASON_RC_SWITCH = 2
uint8 ARM_DISARM_REASON_COMMAND_INTERNAL = 3
uint8 ARM_DISARM_REASON_COMMAND_EXTERNAL = 4
uint8 ARM_DISARM_REASON_MISSION_START = 5
uint8 ARM_DISARM_REASON_LANDING = 6
uint8 ARM_DISARM_REASON_PREFLIGHT_INACTION = 7
uint8 ARM_DISARM_REASON_KILL_SWITCH = 8
uint8 ARM_DISARM_REASON_RC_BUTTON = 13
uint8 ARM_DISARM_REASON_FAILSAFE = 14
uint64 nav_state_timestamp # time when current nav_state activated
uint8 nav_state_user_intention # Mode that the user selected (might be different from nav_state in a failsafe situation)
uint8 nav_state # Currently active mode
uint8 NAVIGATION_STATE_MANUAL = 0 # Manual mode
uint8 NAVIGATION_STATE_ALTCTL = 1 # Altitude control mode
uint8 NAVIGATION_STATE_POSCTL = 2 # Position control mode
uint8 NAVIGATION_STATE_AUTO_MISSION = 3 # Auto mission mode
uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode
uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode
uint8 NAVIGATION_STATE_POSITION_SLOW = 6
uint8 NAVIGATION_STATE_FREE5 = 7
uint8 NAVIGATION_STATE_ALTITUDE_CRUISE = 8 # Altitude with Cruise mode
uint8 NAVIGATION_STATE_FREE3 = 9
uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode
uint8 NAVIGATION_STATE_FREE2 = 11
uint8 NAVIGATION_STATE_DESCEND = 12 # Descend mode (no position control)
uint8 NAVIGATION_STATE_TERMINATION = 13 # Termination mode
uint8 NAVIGATION_STATE_OFFBOARD = 14
uint8 NAVIGATION_STATE_STAB = 15 # Stabilized mode
uint8 NAVIGATION_STATE_FREE1 = 16
uint8 NAVIGATION_STATE_AUTO_TAKEOFF = 17 # Takeoff
uint8 NAVIGATION_STATE_AUTO_LAND = 18 # Land
uint8 NAVIGATION_STATE_AUTO_FOLLOW_TARGET = 19 # Auto Follow
uint8 NAVIGATION_STATE_AUTO_PRECLAND = 20 # Precision land with landing target
uint8 NAVIGATION_STATE_ORBIT = 21 # Orbit in a circle
uint8 NAVIGATION_STATE_AUTO_VTOL_TAKEOFF = 22 # Takeoff, transition, establish loiter
uint8 NAVIGATION_STATE_EXTERNAL1 = 23
uint8 NAVIGATION_STATE_EXTERNAL2 = 24
uint8 NAVIGATION_STATE_EXTERNAL3 = 25
uint8 NAVIGATION_STATE_EXTERNAL4 = 26
uint8 NAVIGATION_STATE_EXTERNAL5 = 27
uint8 NAVIGATION_STATE_EXTERNAL6 = 28
uint8 NAVIGATION_STATE_EXTERNAL7 = 29
uint8 NAVIGATION_STATE_EXTERNAL8 = 30
uint8 NAVIGATION_STATE_MAX = 31
uint8 executor_in_charge # Current mode executor in charge (0=Autopilot)
uint8 nav_state_display # User-visible nav state sent via MAVLink (executor state if active, otherwise nav_state)
uint32 valid_nav_states_mask # Bitmask for all valid nav_state values
uint32 can_set_nav_states_mask # Bitmask for all modes that a user can select
# Bitmask of detected failures
uint16 failure_detector_status
uint16 FAILURE_NONE = 0
uint16 FAILURE_ROLL = 1 # (1 << 0)
uint16 FAILURE_PITCH = 2 # (1 << 1)
uint16 FAILURE_ALT = 4 # (1 << 2)
uint16 FAILURE_EXT = 8 # (1 << 3)
uint16 FAILURE_ARM_ESC = 16 # (1 << 4)
uint16 FAILURE_BATTERY = 32 # (1 << 5)
uint16 FAILURE_IMBALANCED_PROP = 64 # (1 << 6)
uint16 FAILURE_MOTOR = 128 # (1 << 7)
uint8 hil_state
uint8 HIL_STATE_OFF = 0
uint8 HIL_STATE_ON = 1
# Current vehicle locomotion method. A vehicle can have different methods (e.g. VTOL transitions from RW to FW method)
uint8 vehicle_type
uint8 VEHICLE_TYPE_UNSPECIFIED = 0
uint8 VEHICLE_TYPE_ROTARY_WING = 1
uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3
uint8 FAILSAFE_DEFER_STATE_DISABLED = 0
uint8 FAILSAFE_DEFER_STATE_ENABLED = 1
uint8 FAILSAFE_DEFER_STATE_WOULD_FAILSAFE = 2 # Failsafes deferred, but would trigger a failsafe
bool failsafe # true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...)
bool failsafe_and_user_took_over # true if system is in failsafe state but the user took over control
uint8 failsafe_defer_state # one of FAILSAFE_DEFER_STATE_*
# Link loss
bool gcs_connection_lost # datalink to GCS lost
uint8 gcs_connection_lost_counter # counts unique GCS connection lost events
bool high_latency_data_link_lost # Set to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost
# VTOL flags
bool is_vtol # True if the system is VTOL capable
bool is_vtol_tailsitter # True if the system performs a 90° pitch down rotation during transition from MC to FW
bool in_transition_mode # True if VTOL is doing a transition
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
# MAVLink identification
uint8 system_type # system type, contains mavlink MAV_TYPE
uint8 system_id # system id, contains MAVLink's system ID field
uint8 component_id # subsystem / component id, contains MAVLink's component ID field
bool safety_button_available # Set to true if a safety button is connected
bool safety_off # Set to true if safety is off
bool power_input_valid # set if input power is valid
bool usb_connected # set to true (never cleared) once telemetry received from usb link
bool open_drone_id_system_present
bool open_drone_id_system_healthy
bool parachute_system_present
bool parachute_system_healthy
bool traffic_avoidance_system_present
bool rc_calibration_in_progress
bool calibration_enabled
bool pre_flight_checks_pass # true if all checks necessary to arm pass
```
:::
-1
View File
@@ -275,4 +275,3 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
- [VehicleLocalPositionV0](VehicleLocalPositionV0.md) — Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
- [VehicleStatusV0](VehicleStatusV0.md) — Encodes the system state of the vehicle published by commander.
- [VehicleStatusV1](VehicleStatusV1.md) — Encodes the system state of the vehicle published by commander.
- [VehicleStatusV2](VehicleStatusV2.md) — Encodes the system state of the vehicle published by commander.
+1 -1
View File
@@ -13,7 +13,7 @@ DShot is an alternative ESC protocol that has several advantages over [PWM](../p
## Supported ESC
[ESCs & Motors > Supported ESCs](../peripherals/esc_motors.md#supported-esc) has a list of supported ESC (check "Protocols" column for DShot ESC).
[ESCs & Motors > Supported ESCs](../peripherals/esc_motors#supported-esc) has a list of supported ESC (check "Protocols" column for DShot ESC).
## Wiring/Connections {#wiring}
+27 -93
View File
@@ -22,31 +22,37 @@ jMAVSim can also be used for HITL Simulation ([as shown here](../simulation/hitl
## 설치
jMAVSim requires JDK 17 or later.
On Ubuntu and Windows, the [standard development environment setup](../dev_setup/dev_env.md) scripts install all required dependencies including Java.
On macOS, you need to install Java manually as shown below.
jMAVSim setup is included in our [standard build instructions](../dev_setup/dev_env.md) for Ubuntu Linux and Windows.
Follow the instructions below to install jMAVSim on macOS.
### macOS
jMAVSim requires OpenJDK 17 or later.
Install it via Homebrew:
To setup the environment for [jMAVSim](../sim_jmavsim/index.md) simulation:
```sh
brew install openjdk@17
```
1. Install a recent version of Java (e.g. Java 15).
You can download [Java 15 (or later) from Oracle](https://www.oracle.com/java/technologies/downloads/?er=221886) or use [Eclipse Temurin](https://adoptium.net):
Homebrew installs OpenJDK but does not link it into your `PATH`, so you need to set `JAVA_HOME` for jMAVSim to find it.
Add this to your shell profile (e.g. `~/.zshrc`):
```sh
brew install --cask temurin
```
```sh
export JAVA_HOME=$(/usr/libexec/java_home -v 17)
```
2. Install jMAVSim:
```sh
brew install px4-sim-jmavsim
```
:::warning
PX4 v1.11 and beyond require at least JDK 15 for jMAVSim simulation.
For earlier versions, macOS users might see the error `Exception in thread "main" java.lang.UnsupportedClassVersionError:`.
You can find the fix in the [jMAVSim with SITL > Troubleshooting](../sim_jmavsim/index.md#troubleshooting)).
:::
## Simulation Environment
Software in the Loop Simulation runs the complete system on the host machine and simulates the autopilot.
It connects via local network to the simulator.
The setup looks like this:
Software in the Loop Simulation runs the complete system on the host machine and simulates the autopilot. It connects via local network to the simulator. The setup looks like this:
[![Mermaid graph: SITL Simulator](https://mermaid.ink/img/eyJjb2RlIjoiZ3JhcGggTFI7XG4gIFNpbXVsYXRvci0tPk1BVkxpbms7XG4gIE1BVkxpbmstLT5TSVRMOyIsIm1lcm1haWQiOnsidGhlbWUiOiJkZWZhdWx0In0sInVwZGF0ZUVkaXRvciI6ZmFsc2V9)](https://mermaid-js.github.io/mermaid-live-editor/#/edit/eyJjb2RlIjoiZ3JhcGggTFI7XG4gIFNpbXVsYXRvci0tPk1BVkxpbms7XG4gIE1BVkxpbmstLT5TSVRMOyIsIm1lcm1haWQiOnsidGhlbWUiOiJkZWZhdWx0In0sInVwZGF0ZUVkaXRvciI6ZmFsc2V9)
@@ -89,8 +95,7 @@ It will also bring up a window showing a 3D view of the [jMAVSim](https://github
## Taking it to the Sky
The system will start printing status information.
You will be able to start flying once you have a position lock (shortly after the console displays the message: _EKF commencing GPS fusion_).
The system will start printing status information. You will be able to start flying once you have a position lock (shortly after the console displays the message: _EKF commencing GPS fusion_).
To takeoff enter the following into the console:
@@ -215,13 +220,11 @@ To disable lockstep in:
## Extending and Customizing
To extend or customize the simulation interface, edit the files in the **Tools/jMAVSim** folder.
The code can be accessed through the[jMAVSim repository](https://github.com/px4/jMAVSim) on Github.
To extend or customize the simulation interface, edit the files in the **Tools/jMAVSim** folder. The code can be accessed through the[jMAVSim repository](https://github.com/px4/jMAVSim) on Github.
:::info
The build system enforces the correct submodule to be checked out for all dependencies, including the simulator.
It will not overwrite changes in files in the directory, however, when these changes are committed the submodule needs to be registered in the Firmware repo with the new commit hash.
To do so, `git add Tools/jMAVSim` and commit the change.
It will not overwrite changes in files in the directory, however, when these changes are committed the submodule needs to be registered in the Firmware repo with the new commit hash. To do so, `git add Tools/jMAVSim` and commit the change.
This will update the GIT hash of the simulator.
:::
@@ -234,75 +237,6 @@ The simulation can be [interfaced to ROS](../simulation/ros_interface.md) the sa
- The startup scripts are discussed in [System Startup](../concept/system_startup.md).
- The simulated root file system ("`/`" directory) is created inside the build directory here: `build/px4_sitl_default/rootfs`.
## Display-Only Mode
jMAVSim can run as a display-only renderer for other simulators (like [SIH](../sim_sih/index.md)), with its internal physics disabled.
In this mode, jMAVSim receives vehicle position via MAVLink and only renders the 3D view.
To use jMAVSim as a display for SIH running in SITL:
```sh
# Start SIH first
make px4_sitl_sih sihsim_quadx
# In another terminal, start jMAVSim in display-only mode
./Tools/simulation/jmavsim/jmavsim_run.sh -p 19410 -u -q -o # 19410 is the default SIH display port
```
For SIH running on flight controller hardware:
```sh
./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -o
```
Use `-a` for airplane display or `-t` for tailsitter display.
## Command-Line Reference
The `jmavsim_run.sh` launch script accepts the following flags:
| Flag | 설명 |
| ------------- | -------------------------------------------------------------------------------------------- |
| `-b <rate>` | Serial baud rate (default: 921600) |
| `-d <device>` | Serial device path (e.g., `/dev/ttyACM0`) |
| `-u` | Use UDP connection instead of serial |
| `-i <id>` | Simulated MAVLink system ID |
| `-p <port>` | UDP port (default: 14560) |
| `-q` | No interactive console |
| `-s <port>` | TCP serial port |
| `-r <rate>` | Render rate in Hz |
| `-l` | Enable lockstep |
| `-o` | Display-only mode (disable physics, render only) |
| `-a` | Use airplane model |
| `-t` | Use tailsitter model |
| `HEADLESS=1` | Environment variable: run without GUI window |
## How jMAVSim Works
jMAVSim is a Java-based lightweight simulator that communicates with PX4 via MAVLink HIL (Hardware-In-the-Loop) messages.
In normal mode:
1. PX4 sends actuator commands via [HIL_ACTUATOR_CONTROLS](https://mavlink.io/en/messages/common.html#HIL_ACTUATOR_CONTROLS).
2. jMAVSim runs its physics engine to compute the vehicle state.
3. jMAVSim sends sensor data back via [HIL_SENSOR](https://mavlink.io/en/messages/common.html#HIL_SENSOR) and [HIL_GPS](https://mavlink.io/en/messages/common.html#HIL_GPS).
In **display-only mode** (`-o` flag), jMAVSim disables its physics engine and only reads [HIL_STATE_QUATERNION](https://mavlink.io/en/messages/common.html#HIL_STATE_QUATERNION) messages to render the vehicle position.
This allows it to visualize vehicles from other simulators like SIH.
jMAVSim supports [lockstep synchronization](#lockstep) with PX4 (enabled with `-l` flag), ensuring deterministic simulation results.
## Keyboard Shortcuts
Camera modes in the jMAVSim 3D view:
| Key | Camera Mode |
| -------------------------------- | ------------------------------------------------------- |
| **F** | First person (attached to vehicle) |
| **S** | Stationary (fixed position) |
| **G** | Gimbal (follows vehicle orientation) |
| **(default)** | Third person follow |
## 문제 해결
### java.long.NoClassDefFoundError
@@ -393,8 +327,8 @@ Exception in thread "main" java.lang.UnsupportedClassVersionError: me/drton/jmav
This error is telling you, you need a more recent version of Java in your environment.
Class file version 58 corresponds to jdk14, version 59 to jdk15, version 60 to jdk 16 etc.
To fix it under macOS, install a newer OpenJDK via Homebrew:
To fix it under macOS, we recommend installing OpenJDK through homebrew
```sh
brew install openjdk@17
brew install --cask adoptopenjdk16
```

Some files were not shown because too many files have changed in this diff Show More