Compare commits

..

1 Commits

Author SHA1 Message Date
Niklas Hauser c7aae96cd2 [WIP] Run the ROMFS through a CPP with the boardconfig 2026-01-22 15:38:49 +01:00
240 changed files with 3246 additions and 12477 deletions
@@ -90,9 +90,6 @@ jobs:
mkdir -p /opt/px4_ws/src
cd /opt/px4_ws/src
git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib.git
# Ignore python packages due to compilation issue (can be enabled when updating ROS)
touch px4-ros2-interface-lib/px4_ros2_py/COLCON_IGNORE || true
touch px4-ros2-interface-lib/examples/python/COLCON_IGNORE || true
cd ..
# Copy messages to ROS workspace
"${PX4_DIR}/Tools/copy_to_ros_ws.sh" "$(pwd)"
+15
View File
@@ -0,0 +1,15 @@
## This file should be placed in the root directory of your project.
## Then modify the CMakeLists.txt file in the root directory of your
## project to incorporate the testing dashboard.
##
## # The following are required to submit to the CDash dashboard:
## ENABLE_TESTING()
## INCLUDE(CTest)
set(CTEST_PROJECT_NAME "PX4 Firmware")
set(CTEST_NIGHTLY_START_TIME "00:00:00 EST")
set(CTEST_DROP_METHOD "http")
set(CTEST_DROP_SITE "my.cdash.org")
set(CTEST_DROP_LOCATION "/submit.php?project=PX4+Firmware")
set(CTEST_DROP_SITE_CDASH TRUE)
Vendored
-1
View File
@@ -101,7 +101,6 @@ pipeline {
echo $0;
git clone https://github.com/emscripten-core/emsdk.git _emscripten_sdk;
cd _emscripten_sdk;
git checkout 4.0.15;
./emsdk install latest;
./emsdk activate latest;
cd ..;
+9 -2
View File
@@ -146,6 +146,11 @@ add_custom_command(
${romfs_copy_stamp}
COMMAND ${CMAKE_COMMAND} -E remove_directory ${romfs_gen_root_dir}/*
COMMAND ${CMAKE_COMMAND} -E tar xf ${romfs_tar_file}
# Preprocess ROMFS files with KConfig definitions
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_romfs_preprocess.py
--romfs-dir ${romfs_gen_root_dir}
--kconfig-header ${PX4_BINARY_DIR}/px4_boardconfig.h
--cpp ${CMAKE_C_COMPILER}
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_process_airframes.py
--airframes-path ${romfs_gen_root_dir}/init.d
--start-script ${romfs_gen_root_dir}/init.d/rc.autostart
@@ -159,8 +164,10 @@ add_custom_command(
--params-file ${CONFIG_BOARD_PARAM_FILE}
COMMAND ${CMAKE_COMMAND} -E touch ${romfs_copy_stamp}
WORKING_DIRECTORY ${romfs_gen_root_dir}
DEPENDS ${romfs_tar_file}
COMMENT "ROMFS: copying, generating airframes"
DEPENDS
${romfs_tar_file}
${PX4_BINARY_DIR}/px4_boardconfig.h
COMMENT "ROMFS: copying, preprocessing, generating airframes"
)
# copy extras into ROMFS
@@ -101,6 +101,6 @@ param set-default NAV_ACC_RAD 5
param set-default NAV_DLL_ACT 2
param set-default VT_FWD_THRUST_EN 4
param set-default VT_F_TRANS_THR 1
param set-default VT_F_TRANS_THR 0.3
param set-default VT_TYPE 2
param set-default FD_ESCS_EN 0
@@ -123,9 +123,3 @@ if(CONFIG_MODULES_TEMPERATURE_COMPENSATION)
rc.thermal_cal
)
endif()
if(CONFIG_DRIVERS_VTXTABLE)
px4_add_romfs_files(
rc.vtxtable
)
endif()
+100 -1
View File
@@ -8,17 +8,24 @@
# Begin Optional drivers #
###############################################################################
%ifdef CONFIG_DRIVERS_BATT_SMBUS
if param compare -s SENS_EN_BATT 1
then
batt_smbus start -X
fi
%endif
%ifdef CONFIG_DRIVERS_SMART_BATTERY_BATMON
# Start batmon driver if enabled using BATMON_DRIVER_EN
if param compare -s BATMON_DRIVER_EN 1
then
batmon start -X #start on external bus
fi
%endif
%ifdef CONFIG_DRIVERS_PWM_INPUT
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_LL40LS
# Sensors on the PWM interface bank
if param compare -s SENS_EN_LL40LS 1
then
@@ -27,92 +34,121 @@ then
ll40ls_pwm start
fi
fi
%endif
# External automatic trigger system
if param compare FD_EXT_ATS_EN 1
then
pwm_input start
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_LL40LS
# Lidar-Lite on I2C
if param compare -s SENS_EN_LL40LS 2
then
ll40ls start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_MAPPYDOT
# mappydot lidar sensor
if param compare -s SENS_EN_MPDT 1
then
mappydot start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_MB12XX
# mb12xx sonar sensor
if param greater -s SENS_EN_MB12XX 0
then
mb12xx start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_PGA460
# pga460 sonar sensor
if param greater -s SENS_EN_PGA460 0
then
pga460 start
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C
# Lightware i2c lidar sensor
if param greater -s SENS_EN_SF1XX 0
then
lightware_laser_i2c start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_SRF05
# Sensor HY-SRF05 or HC-SR05 ultrasonic sensor
if param compare -s SENS_EN_SR05 1
then
srf05 start
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_TERARANGER
# Teraranger one tof sensor
if param greater -s SENS_EN_TRANGER 0
then
teraranger start -X
fi
%endif
%ifdef CONFIG_DRIVERS_OPTICAL_FLOW_PAA3905
# paa3905 optical flow sensor (external SPI)
if param greater -s SENS_EN_PAA3905 0
then
paa3905 -S start
fi
%endif
%ifdef CONFIG_DRIVERS_OPTICAL_FLOW_PAW3902
# paw3902 optical flow sensor (external SPI)
if param greater -s SENS_EN_PAW3902 0
then
paw3902 -S start
fi
%endif
%ifdef CONFIG_DRIVERS_OPTICAL_FLOW_PMW3901
# pmw3901 optical flow sensor (external SPI)
if param greater -s SENS_EN_PMW3901 0
then
pmw3901 -S start
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X
# vl53l0x i2c distance sensor
if param compare -s SENS_EN_VL53L0X 1
then
vl53l0x start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X
# vl53l1x i2c distance sensor
if param compare -s SENS_EN_VL53L1X 1
then
vl53l1x start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_TF02PRO
# tf02 pro i2c distance sensor
if param compare -s SENS_EN_TF02PRO 1
then
tf02pro start -X
fi
%endif
%ifdef CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448
# ADIS16448 spi external IMU
if param compare -s SENS_EN_ADIS164X 1
then
@@ -125,25 +161,33 @@ then
adis16448 -S start -R 4
fi
fi
%endif
%ifdef CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507
# ADIS16507 spi external IMU
if param greater -s SENS_EN_ADIS165X 0
then
adis16507 -S start
fi
%endif
%ifdef CONFIG_DRIVERS_IMU_MURATA_SCH16T
# SCH16T spi external IMU
if param compare -s SENS_EN_SCH16T 1
then
sch16t -S start
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ETS
# Eagle Tree airspeed sensor external I2C
if param compare -s SENS_EN_ETSASPD 1
then
ets_airspeed start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_SDP3X
# Sensirion SDP3X differential pressure sensor external I2C
if param compare -s SENS_EN_SDP3X 1
then
@@ -153,116 +197,171 @@ then
sdp3x start -X -a 0x22
fi
fi
%endif
%ifdef CONFIG_DRIVERS_TEMPERATURE_SENSOR_MCP9808
# Microchip MCP9808 temperature sensor external I2C
if param compare -s SENS_EN_MCP9808 1
then
mcp9808 start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4515
# TE MS4515 differential pressure sensor external I2C
if param compare -s SENS_EN_MS4515 1
then
ms4515 start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4525DO
# TE MS4525DO differential pressure sensor external I2C
if param compare -s SENS_EN_MS4525DO 1
then
ms4525do start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS5525DSO
# TE MS5525DSO differential pressure sensor external I2C
if param compare -s SENS_EN_MS5525DS 1
then
ms5525dso start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033
# TE ASP5033 differential pressure sensor external I2C
if param compare -s SENS_EN_ASP5033 1
then
asp5033 start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV
# AUAV absolute/differential pressure sensor external I2C
if param greater -s SENS_EN_AUAVX 0
then
auav start -D -X
auav start -A -X
fi
%endif
%ifdef CONFIG_DRIVERS_HYGROMETER_SHT3X
# SHT3x temperature and hygrometer sensor, external I2C
if param compare -s SENS_EN_SHT3X 1
then
sht3x start -X
sht3x start -X -a 0x45
fi
%endif
%ifdef CONFIG_DRIVERS_IRLOCK
# IR-LOCK sensor external I2C
if param compare -s SENS_EN_IRLOCK 1
then
irlock start -X
fi
%endif
%ifdef CONFIG_DRIVERS_BAROMETER_GOERTEK_SPL06
# SPL06 sensor external I2C
if param compare -s SENS_EN_SPL06 1
then
spl06 -X start
spl06 -X -a 0x77 start
fi
%endif
%ifdef CONFIG_DRIVERS_BAROMETER_GOERTEK_SPA06
# SPA06 sensor external I2C
if param compare -s SENS_EN_SPA06 1
then
spa06 -X start
spa06 -X -a 0x77 start
fi
%endif
%ifdef CONFIG_DRIVERS_RPM_PCF8583
# PCF8583 counter (RPM sensor)
if param compare -s SENS_EN_PCF8583 1
then
pcf8583 start -X
pcf8583 start -X -a 0x51
fi
%endif
%ifdef CONFIG_DRIVERS_ADC_ADS7953
# ADC sensor ADS7953 external SPI
if param compare -s ADC_ADS7953_EN 1
then
ads7953 start -S
fi
%endif
%ifdef CONFIG_DRIVERS_ADC_TLA2528
# ADC sensor tla2528 external I2C
if param compare -s ADC_TLA2528_EN 1
then
tla2528 start -X
fi
%endif
%ifdef CONFIG_DRIVERS_TEMPERATURE_SENSOR_TMP102
# Start TMP102 temperature sensor
if param compare SENS_EN_TMP102 1
if param compare -s SENS_EN_TMP102 1
then
tmp102 start -X
fi
%endif
%ifdef COMMON_MAGNETOMETER
# probe for optional external I2C devices
if param compare SENS_EXT_I2C_PRB 1
then
%ifdef CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948
icm20948_i2c_passthrough -X -q start
%endif
# compasses
%ifdef CONFIG_DRIVERS_MAGNETOMETER_HMC5883
hmc5883 -T -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC
iis2mdc -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308
ist8308 -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310
ist8310 -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL
if ! lis3mdl -X -q start
then
lis3mdl -X -q -a 0x1c start
fi
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_QMC5883L
qmc5883l -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_QMC5883P
qmc5883p -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_RM3100
rm3100 -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM350
bmm350 -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC
iis2mdc -X -q start
%endif
# start last (wait for possible icm20948 passthrough mode)
%ifdef CONFIG_DRIVERS_MAGNETOMETER_AKM_AK09916
ak09916 -X -q start
%endif
fi
%endif
-8
View File
@@ -1,8 +0,0 @@
#!/bin/sh
#
# VTX table loading script.
#
# NOTE: Script variables are declared/initialized/unset in the rcS script.
#
vtxtable load
+125 -41
View File
@@ -265,12 +265,15 @@ else
# Start the tone_alarm driver.
# Needs to be started after the parameters are loaded (for CBRK_BUZZER).
#
%ifdef CONFIG_DRIVERS_TONE_ALARM
tone_alarm start
%endif
#
# Waypoint storage.
# REBOOTWORK this needs to start in parallel.
#
%ifdef CONFIG_MODULES_DATAMAN
if param compare -s SYS_DM_BACKEND 1
then
dataman start -r
@@ -281,11 +284,14 @@ else
dataman start
fi
fi
%endif
#
# Start the socket communication send_event handler.
#
%ifdef CONFIG_MODULES_SEND_EVENT
send_event start
%endif
#
# Start the hardfault streamer.
@@ -298,15 +304,25 @@ else
#
# Start the resource load monitor.
#
%ifdef CONFIG_MODULES_LOAD_MON
load_mon start
%endif
#
# Start system state indicator.
#
%ifdef CONFIG_DRIVERS_LIGHTS_RGBLED
rgbled start -X -q
%endif
%ifdef CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C
rgbled_ncp5623c start -X -q
%endif
%ifdef CONFIG_DRIVERS_LIGHTS_RGBLED_LP5562
rgbled_lp5562 start -X -q
%endif
%ifdef CONFIG_DRIVERS_LIGHTS_RGBLED_IS31FL3195
rgbled_is31fl3195 start -X -q
%endif
#
# Override parameters from user configuration file.
@@ -331,11 +347,21 @@ else
# start the simulator in hardware if needed
if param compare SYS_HITL 2
then
%ifdef CONFIG_MODULES_SIMULATION_SIMULATOR_SIH
simulator_sih start
%endif
%ifdef CONFIG_MODULES_SIMULATION_SENSOR_BARO_SIM
sensor_baro_sim start
%endif
%ifdef CONFIG_MODULES_SIMULATION_SENSOR_MAG_SIM
sensor_mag_sim start
%endif
%ifdef CONFIG_MODULES_SIMULATION_SENSOR_GPS_SIM
sensor_gps_sim start
%endif
%ifdef CONFIG_MODULES_SIMULATION_SENSOR_AGP_SIM
sensor_agp_sim start
%endif
fi
else
@@ -352,43 +378,58 @@ else
. ${R}etc/init.d/rc.sensors
%ifdef CONFIG_MODULES_SENSORS
%ifdef CONFIG_MODULES_ESC_BATTERY
if param compare -s BAT1_SOURCE 2
then
esc_battery start
fi
%endif
%ifdef CONFIG_MODULES_BATTERY_STATUS
if ! param compare BAT1_SOURCE 1
then
battery_status start
fi
%endif
%endif
%ifdef CONFIG_MODULES_SENSORS
sensors start
%endif
fi
#
# state estimator selection
#
%ifdef CONFIG_MODULES_EKF2
if param compare -s EKF2_EN 1
then
ekf2 start &
fi
%endif
%ifdef CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR
if param compare -s LPE_EN 1
then
local_position_estimator start
fi
%endif
%ifdef CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q
if param compare -s ATT_EN 1
then
attitude_estimator_q start
fi
%endif
%ifdef CONFIG_DRIVERS_PX4IO
#
# px4io
#
if px4io supported
then
# Check if PX4IO present and update firmware if needed.
# Check if PX4IO present and update firmware if needed.
if [ -f $IOFW ]
then
if ! px4io checkcrc ${IOFW}
@@ -418,40 +459,56 @@ else
fi
fi
fi
%endif
# Heater driver for temperature regulated IMUs.
# The heater needs to start after px4io.
%ifdef CONFIG_DRIVERS_HEATER
if param compare -s SENS_EN_THERMAL 1
then
heater start
fi
%endif
#
# RC update (map raw RC input to calibrate manual control)
# start before commander
#
%ifdef CONFIG_MODULES_RC_UPDATE
rc_update start
%endif
%ifdef CONFIG_MODULES_MANUAL_CONTROL
manual_control start
%endif
# Start camera trigger, capture and PPS before pwm_out as they might access
# pwm pins
%ifdef CONFIG_DRIVERS_CAMERA_TRIGGER
if param greater -s TRIG_MODE 0
then
camera_trigger start
%ifdef CONFIG_MODULES_CAMERA_FEEDBACK
camera_feedback start
%endif
fi
%endif
# PPS capture driver
%ifdef CONFIG_DRIVERS_PPS_CAPTURE
if param greater -s PPS_CAP_ENABLE 0
then
pps_capture start
fi
%endif
# RPM capture driver
%ifdef CONFIG_DRIVERS_RPM_CAPTURE
if param greater -s RPM_CAP_ENABLE 0
then
rpm_capture start
fi
%endif
# Camera capture driver
%ifdef CONFIG_DRIVERS_CAMERA_CAPTURE
if param greater -s CAM_CAP_FBACK 0
then
if camera_capture start
@@ -459,38 +516,34 @@ else
camera_capture on
fi
fi
%endif
#
# Commander
#
%ifdef CONFIG_MODULES_COMMANDER
if param greater SYS_HITL 0
then
commander start -h
%ifdef CONFIG_MODULES_SIMULATION_PWM_OUT_SIM
if ! pwm_out_sim start -m hil
then
tune_control play error
fi
%endif
else
commander start
%ifdef CONFIG_DRIVERS_DSHOT
dshot start
%endif
%ifdef CONFIG_DRIVERS_PWM_OUT
pwm_out start
%endif
fi
#
# Optional UAVCAN/DroneCAN or Cyphal
#
if param greater -s UAVCAN_ENABLE 0
then
uavcan start
else
if param greater -s CYPHAL_ENABLE 0
then
cyphal start
fi
fi
%endif
#
# Configure vehicle type specific parameters.
@@ -498,10 +551,12 @@ else
. ${R}etc/init.d/rc.vehicle_setup
# Pre-takeoff continuous magnetometer calibration
%ifdef CONFIG_MODULES_MAG_BIAS_ESTIMATOR
if param compare -s MBE_ENABLE 1
then
mag_bias_estimator start
fi
%endif
#
# Optional board mavlink streams: rc.board_mavlink
@@ -520,11 +575,6 @@ else
#
. ${R}etc/init.d/rc.serial
if param greater -s ZENOH_ENABLE 0
then
zenoh start
fi
# Must be started after the serial config is read
rc_input start $RC_INPUT_ARGS
@@ -551,54 +601,67 @@ else
#
# Start the navigator.
#
%ifdef CONFIG_MODULES_NAVIGATOR
navigator start
%endif
%ifdef CONFIG_MODULES_TEMPERATURE_COMPENSATION
#
# Start a thermal calibration if required.
#
set RC_THERMAL_CAL ${R}etc/init.d/rc.thermal_cal
if [ -f ${RC_THERMAL_CAL} ]
then
. ${RC_THERMAL_CAL}
fi
unset RC_THERMAL_CAL
. ${R}etc/init.d/rc.thermal_cal
%endif
#
# Start gimbal to control mounts such as gimbals, disabled by default.
#
%ifdef CONFIG_MODULES_GIMBAL
if param greater -s MNT_MODE_IN -1
then
gimbal start
fi
%endif
# Blacksheep telemetry
%ifdef CONFIG_DRIVERS_TELEMETRY_BST
if param compare -s TEL_BST_EN 1
then
bst start -X
fi
%endif
%ifdef CONFIG_MODULES_GYRO_FFT
if param compare -s IMU_GYRO_FFT_EN 1
then
gyro_fft start
fi
%endif
%ifdef CONFIG_MODULES_GYRO_CALIBRATION
if param compare -s IMU_GYRO_CAL_EN 1
then
gyro_calibration start
fi
%endif
# Check for px4flow sensor
%ifdef CONFIG_DRIVERS_OPTICAL_FLOW_PX4FLOW
if param compare -s SENS_EN_PX4FLOW 1
then
px4flow start -X &
fi
%endif
%ifdef CONFIG_MODULES_PAYLOAD_DELIVERER
payload_deliverer start
%endif
%ifdef CONFIG_MODULES_INTERNAL_COMBUSTION_ENGINE_CONTROL
if param compare -s ICE_EN 1
then
internal_combustion_engine_control start
fi
%endif
#
# Optional board supplied extras: rc.board_extras
@@ -620,25 +683,12 @@ else
. $FEXTRAS
fi
%ifdef CONFIG_MODULES_LOGGER
#
# Start the logger.
#
set RC_LOGGING ${R}etc/init.d/rc.logging
if [ -f ${RC_LOGGING} ]
then
. ${RC_LOGGING}
fi
unset RC_LOGGING
#
# Start the VTX services.
#
set RC_VTXTABLE ${R}etc/init.d/rc.vtxtable
if [ -f ${RC_VTXTABLE} ]
then
. ${RC_VTXTABLE}
fi
unset RC_VTXTABLE
. ${R}etc/init.d/rc.logging
%endif
#
# Set additional parameters and env variables for selected AUTOSTART.
@@ -656,6 +706,40 @@ else
fi
unset BOARD_BOOTLOADER_UPGRADE
#
# Check if UAVCAN is enabled, default to it for ESCs.
#
%ifdef CONFIG_DRIVERS_UAVCAN
if param greater -s UAVCAN_ENABLE 0
then
# Start core UAVCAN module.
if ! uavcan start
then
tune_control play error
fi
else
%ifdef CONFIG_DRIVERS_CYPHAL
if param greater -s CYPHAL_ENABLE 0
then
cyphal start
fi
%endif
fi
%else
%ifdef CONFIG_DRIVERS_CYPHAL
if param greater -s CYPHAL_ENABLE 0
then
cyphal start
fi
%endif
%endif
%ifdef CONFIG_MODULES_ZENOH
if param greater -s ZENOH_ENABLE 0
then
zenoh start
fi
%endif
#
# End of autostart.
#
+58 -822
View File
@@ -8,803 +8,6 @@ Also generates docs/en/middleware/dds_topics.md from dds_topics.yaml
import os
import argparse
import sys
import re
VALID_FIELDS = { #Note, also have to add the message types as those can be fields
'uint64',
'uint16',
'uint8',
'uint32'
}
ALLOWED_UNITS = set(["m", "m/s", "m/s^2", "(m/s)^2", "deg", "deg/s", "rad", "rad/s", "rad^2", "rpm" ,"V", "A", "mA", "mAh", "W", "dBm", "h", "s", "ms", "us", "Ohm", "MB", "Kb/s", "degC","Pa","%","-"])
invalid_units = set()
ALLOWED_FRAMES = set(["NED","Body"])
ALLOWED_INVALID_VALUES = set(["NaN", "0"])
ALLOWED_CONSTANTS_NOT_IN_ENUM = set(["ORB_QUEUE_LENGTH","MESSAGE_VERSION"])
class Error:
def __init__(self, type, message, linenumber=None, issueString = None, field = None):
self.type = type
self.message = message
self.linenumber = linenumber
self.issueString = issueString
self.field = field
def display_error(self):
#print(f"Debug: Error: display_error")
if 'trailing_whitespace' == self.type:
if self.issueString.strip():
print(f"NOTE: Line has trailing whitespace ({self.message}: {self.linenumber}): {self.issueString}")
else:
print(f"NOTE: Line has trailing whitespace ({self.message}: {self.linenumber})")
elif 'leading_whitespace_field_or_constant' == self.type:
print(f"NOTE: Whitespace before field or constant ({self.message}: {self.linenumber}): {self.issueString}")
elif 'field_or_constant_has_multiple_whitepsace' == self.type:
print(f"NOTE: Field/constant has more than one sequential whitespace character ({self.message}: {self.linenumber}): {self.issueString}")
elif 'empty_start_line' == self.type:
print(f"NOTE: Empty line at start of file ({self.message}: {self.linenumber})")
elif 'internal_comment' == self.type:
print(f"NOTE: Internal Comment ({self.message}: {self.linenumber})\n {self.issueString}")
elif 'internal_comment_empty' == self.type:
print(f"NOTE: Empty Internal Comment ({self.message}: {self.linenumber})")
elif 'summary_missing' == self.type:
print(f"WARNING: No message description ({self.message})")
elif 'topic_error' == self.type:
print(f"NOTE: TOPIC ISSUE: {self.issueString}")
elif 'unknown_unit' == self.type:
print(f"WARNING: Unknown Unit: [{self.issueString}] on `{self.field}` ({self.message}: {self.linenumber})")
elif 'constant_not_in_assigned_enum' == self.type:
print(f"WARNING: `{self.issueString}` constant: Prefix not in `@enum` field metadata ({self.message}: {self.linenumber})")
elif 'unknown_invalid_value' == self.type:
print(f"WARNING: Unknown @invalid value: [{self.issueString}] on `{self.field}` ({self.message}: {self.linenumber})")
elif 'unknown_frame' == self.type:
print(f"WARNING: Unknown @frame: [{self.issueString}] on `{self.field}` ({self.message}: {self.linenumber})")
elif 'command_no_params_pipes' == self.type:
print(f"WARNING: `{self.field}` command has no parameters (pipes): [{self.issueString}] ({self.message}: {self.linenumber})")
elif 'command_missing_params' == self.type:
print(f"WARNING: `{self.field}` command missing params - should be 7 params surrounded by 8 pipes: [{self.issueString}] ({self.message}: {self.linenumber})")
elif 'command_too_many_params' == self.type:
print(f"WARNING: `{self.field}` command too many params (should be 7). Extras: [{self.issueString}] ({self.message}: {self.linenumber})")
else:
self.display_info()
def display_info(self):
"""
Display info about an error.
Used as a fallback if error does not have specific printout in display_error()
"""
#print(f"Debug: Error: display_info")
print(f" type: {self.type}, message: {self.message}, linenumber: {self.linenumber}, issueString: {self.issueString}, field: {self.field}")
class Enum:
def __init__(self, name, parentMessage):
self.name = name
self.parent = parentMessage
self.enumValues = dict()
def display_info(self):
"""
Display info about an enum
"""
print(f"Debug: Enum: display_info")
print(f" name: {self.name}")
for key, value in self.enumValues.items():
value.display_info()
class ConstantValue:
def __init__(self, name, type, value, comment, line_number):
self.name = name.strip()
self.type = type.strip()
self.value = value.strip()
self.comment = comment
self.line_number = line_number
if not self.value:
print(f"Debug WARNING: NO VALUE in ConstantValue: {self.name}") ## TODO make into ERROR
exit()
# TODO if value or name are empty, error
def display_info(self):
print(f"Debug: ConstantValue: display_info")
print(f" name: {self.name}, type: {self.type}, value: {self.value}, comment: {self.comment}, line: {self.line_number}")
class CommandParam:
"""
Represents an individual param in a command constant
Encapsulates parsing of the param to extract units etc.
"""
def __init__(self, num, paramText, line_number, parentCommand):
self.paramNum = num
self.paramText = paramText.strip()
self.enum = None
self.range = None
#self.type = type
self.units = []
self.enums = []
self.minValue = None
self.maxValue = None
self.invalidValue = None
self.frameValue = None
self.lineNumber = line_number
self.parent = parentCommand
self.parentMessage = self.parent.parent
match = None
if self.paramText:
match = re.match(r'^((?:\[[^\]]*\]\s*)+)(.*)$', paramText)
self.description = paramText
bracketed_part = None
if match:
bracketed_part = match.group(1).strip() # .strip() removes trailing whitespace from the bracketed part
self.description = match.group(2).strip()
if bracketed_part:
# get units
bracket_content_matches = re.findall(r'\[(.*?)\]', bracketed_part)
#print(f"DEBUG: bracket_content_matches: {bracket_content_matches}")
for item in bracket_content_matches:
item = item.strip()
if item.startswith('@'): # Not a unit:
if item.startswith('@enum'):
item = item.split(" ")
enum = item[1].strip()
if enum and enum not in self.enums:
self.enums.append(enum)
# Create parent enum objects for any enums created in this step
for enumName in self.enums:
if not enumName in self.parentMessage.enums:
self.parentMessage.enums[enumName]=Enum(enumName,self.parentMessage)
elif item.startswith('@range'):
item = item[6:].strip().split(",")
self.range = item
self.minValue = item[0].strip()
self.maxValue = item[1].strip()
elif item.startswith('@invalid'):
self.invalidValue = item[8:].strip()
#TODO: Do we require a description? (not currently)
if self.invalidValue.split(" ")[0] not in ALLOWED_INVALID_VALUES:
print(f"TODO: Command param do not support @invalid: {self.invalidValue}")
"""
error = Error("unknown_invalid_value", self.parent.filename, self.lineNumber, self.invalidValue, self.name)
#error.display_error()
if not "unknown_invalid_value" in self.parent.errors:
self.parent.errors["unknown_invalid_value"] = []
self.parent.errors["unknown_invalid_value"].append(error)
"""
elif item.startswith('@frame'):
self.frameValue = item[6:].strip()
print(f"TODO: Command param do not support @frame: {self.frameValue}")
"""
if self.frameValue not in ALLOWED_FRAMES:
error = Error("unknown_frame", self.parent.filename, self.lineNumber, self.frameValue, self.name)
#error.display_error()
if not "unknown_frame" in self.parent.errors:
self.parent.errors["unknown_frame"] = []
self.parent.errors["unknown_frame"].append(error)
"""
else:
print(f"WARNING: Unhandled metadata in message comment: {item}")
# TODO - report errors for different kinds of metadata
exit()
else: # bracket is a unit
unit = item.strip()
if item == "-":
unit = ""
if unit and unit not in self.units:
self.units.append(unit)
if unit not in ALLOWED_UNITS:
invalid_units.add(unit)
error = Error("unknown_unit", self.parentMessage.filename, self.lineNumber, unit, self.parent.name)
#error.display_error()
if not "unknown_unit" in self.parentMessage.errors:
self.parentMessage.errors["unknown_unit"] = []
self.parentMessage.errors["unknown_unit"].append(error)
def display_info(self):
print(f"Debug: CommandParam: display_info")
print(f" id: {self.paramNum}")
print(f" paramText: {self.paramText}\n unit: {self.units}\n enums: {self.enums}\n lineNumber: {self.lineNumber}\n range: {self.range}\n minValue: {self.minValue}\n maxValue: {self.maxValue}\n invalidValue: {self.invalidValue}\n frameValue: {self.frameValue}\n parent: {self.parent}\n ")
class CommandConstant:
"""
Represents a constant that is a command definition.
Encapsulates parsing of the command format.
The individual params are further parsed in CommandParam
"""
def __init__(self, name, type, value, comment, line_number, parentMessage):
self.name = name.strip()
self.type = type.strip()
self.value = value.strip()
self.comment = comment
self.line_number = line_number
self.parent = parentMessage
self.description = self.comment
self.param1 = None
self.param2 = None
self.param3 = None
self.param4 = None
self.param5 = None
self.param6 = None
self.param7 = None
if not self.value:
print(f"Debug WARNING: NO VALUE in CommandConstant: {self.name}") ## TODO make into ERROR
exit()
if not self.comment: # This is an bug for a command
#print(f"Debug WARNING: NO COMMENT in CommandConstant: {self.name}") ## TODO make into ERROR
return
# Parse command comment to get the description and parameters.
# print(f"Debug CommandConstant: {self.comment}")
if not "|" in self.comment:
# This is an error for a command constant
error = Error("command_no_params_pipes", self.parent.filename, self.line_number, self.comment, self.name)
#error.display_error()
if not "command_no_params_pipes" in self.parent.errors:
self.parent.errors["command_no_params_pipes"] = []
self.parent.errors["command_no_params_pipes"].append(error)
return
# Split on pipes
commandSplit = self.comment.split("|")
if len(commandSplit) < 9:
# Should 7 pipes, so each command is fully surrounded
error = Error("command_missing_params", self.parent.filename, self.line_number, self.comment, self.name)
#error.display_error()
if not "command_missing_params" in self.parent.errors:
self.parent.errors["command_missing_params"] = []
self.parent.errors["command_missing_params"].append(error)
self.description = commandSplit[0].strip()
self.description = self.description if self.description else None
params_to_update = commandSplit[1:8]
for i, value in enumerate(params_to_update, start=1):
if value.strip():
# parse the param
param = CommandParam(i, value, self.line_number, self)
#param.display_info() # DEBUG CODE XXX
setattr(self, f"param{i}", param)
# parse the param
if len(commandSplit) > 8:
extras = commandSplit[8:]
error = Error("command_too_many_params", self.parent.filename, self.line_number, extras, self.name)
if not "command_too_many_params" in self.parent.errors:
self.parent.errors["command_too_many_params"] = []
self.parent.errors["command_too_many_params"].append(error)
# TODO if value or name are empty, error
def markdown_out(self):
#print("DEBUG: CommandConstant.markdown_out")
output = f"""### {self.name} ({self.value})
{self.description}
Param | Units | Range/Enum | Description
--- | --- | --- | ---
"""
for i in range(1, 8):
attr_name = f"param{i}"
# getattr returns None if the attribute doesn't exist
val = getattr(self, attr_name, None)
if val is not None:
rangeVal = ""
if val.minValue or val.maxValue:
rangeVal = f"[{val.minValue if val.minValue else '-'} : {val.maxValue if val.maxValue else '-' }]"
output+=f"{i} | {", ".join(val.units)}|{', '.join(f"[{e}](#{e})" for e in val.enums)}{rangeVal} | {val.description}\n"
else:
output+=f"{i} | | | ?\n"
output+=f"\n"
return output
def display_info(self):
print(f"Debug: CommandConstant: display_info")
print(f" name: {self.name}, type: {self.type}, value: {self.value}, comment: {self.comment}, line: {self.line_number}")
print(f" description: {self.description}\n param1: {self.param1}\n param2: {self.param2}\n param3: {self.param3}\n param4: {self.param4}\n param5: {self.param5}\n param6: {self.param6}\n param7: {self.param7}")
class MessageField:
"""
Represents a field.
Encapsulates parsing of the field information.
"""
def __init__(self, name, type, comment, line_number, parentMessage):
self.name = name
self.type = type
self.comment = comment
self.unit = None
self.enums = None
self.minValue = None
self.maxValue = None
self.invalidValue = None
self.frameValue = None
self.lineNumber = line_number
self.parent = parentMessage
#print(f"MessageComment: {comment}")
match = None
if self.comment:
match = re.match(r'^((?:\[[^\]]*\]\s*)+)(.*)$', comment)
self.description = comment
bracketed_part = None
if match:
bracketed_part = match.group(1).strip() # .strip() removes trailing whitespace from the bracketed part
self.description = match.group(2).strip()
if bracketed_part:
# get units
bracket_content_matches = re.findall(r'\[(.*?)\]', bracketed_part)
#print(f"bracket_content_matches: {bracket_content_matches}")
for item in bracket_content_matches:
item = item.strip()
if item.startswith('@'): # Not a unit:
if item.startswith('@enum'):
item = item.split(" ")
self.enums = item[1:]
# Create parent enum objects
for enumName in self.enums:
if not enumName in parentMessage.enums:
parentMessage.enums[enumName]=Enum(enumName,parentMessage)
elif item.startswith('@range'):
item = item[6:].strip().split(",")
self.minValue = item[0].strip()
self.maxValue = item[1].strip()
elif item.startswith('@invalid'):
self.invalidValue = item[8:].strip()
#TODO: Do we require a description? (not currently)
if self.invalidValue.split(" ")[0] not in ALLOWED_INVALID_VALUES:
error = Error("unknown_invalid_value", self.parent.filename, self.lineNumber, self.invalidValue, self.name)
#error.display_error()
if not "unknown_invalid_value" in self.parent.errors:
self.parent.errors["unknown_invalid_value"] = []
self.parent.errors["unknown_invalid_value"].append(error)
elif item.startswith('@frame'):
self.frameValue = item[6:].strip()
if self.frameValue not in ALLOWED_FRAMES:
error = Error("unknown_frame", self.parent.filename, self.lineNumber, self.frameValue, self.name)
#error.display_error()
if not "unknown_frame" in self.parent.errors:
self.parent.errors["unknown_frame"] = []
self.parent.errors["unknown_frame"].append(error)
else:
print(f"WARNING: Unhandled metadata in message comment: {item}")
# TODO - report errors for different kinds of metadata
exit()
else: # bracket is a unit
self.unit = item
if self.unit not in ALLOWED_UNITS:
invalid_units.add(self.unit)
error = Error("unknown_unit", self.parent.filename, self.lineNumber, self.unit, self.name)
#error.display_error()
if not "unknown_unit" in self.parent.errors:
self.parent.errors["unknown_unit"] = []
self.parent.errors["unknown_unit"].append(error)
if item == "-":
self.unit = ""
def display_info(self):
print(f"Debug: MessageField: display_info")
print(f" name: {self.name}, type: {self.type}, description: {self.description}, enums: {self.enums}, minValue: {self.minValue}, maxValue: {self.maxValue}, invalidValue: {self.invalidValue}, frameValue: {self.frameValue}")
class UORBMessage:
"""
Represents a whole message, including fields, enums, commands, constants.
The parser function delegates the parsing of each part of the message to
more appropriate classes, once the specific type of line has been identified.
"""
def __init__(self, filename):
self.filename = filename
msg_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),"../../msg")
self.msg_filename = os.path.join(msg_path, self.filename)
self.name = os.path.splitext(os.path.basename(msg_file))[0]
self.shortDescription = ""
self.longDescription = ""
self.fields = []
self.constantFields = dict()
self.commandConstants = dict()
self.enums = dict()
self.output_file = os.path.join(output_dir, f"{self.name}.md")
self.topics = []
self.errors = dict()
self.parseFile()
if args.errors:
#print(f"DEBUG: args.errors: {args.errors}")
if args.error_messages:
messages = args.error_messages.split(" ")
#print(f"DEBUG: args.errors: {messages},self.name: {self.name}")
if self.name in messages:
self.reportErrors()
#print(f"Debug: {self.name} in {messages}")
else:
self.reportErrors()
def reportErrors(self):
#print(f"Debug: UORBMessage: reportErrors()")
for errorType, errors in self.errors.items():
for error in errors:
error.display_error()
def markdown_out(self):
#print(f"Debug: UORBMessage: markdown_out()")
# Add page header (forces wide pages)
markdown = f"""---
pageClass: is-wide-page
---
# {self.name} (UORB message)
"""
## Append description info if present
markdown += f"{self.shortDescription}\n\n" if self.shortDescription else ""
markdown += f"{self.longDescription}\n\n" if self.longDescription else ""
topicList = " ".join(self.topics)
markdown += f"**TOPICS:** {topicList}\n\n"
# Generate field docs
markdown += f"## Fields\n\n"
markdown += "Name | Type | Unit [Frame] | Range/Enum | Description\n"
markdown += "--- | --- | --- | --- | ---\n"
for field in self.fields:
unit = f"{field.unit}" if field.unit else ""
frame = f"[{field.frameValue}]" if field.frameValue else ""
unit = f"{unit} {frame}"
unit.strip()
unit = f" {unit}"
value = " "
if field.enums:
value = ""
for enum in field.enums:
value += f"[{enum}](#{enum})"
value = value.strip()
value = f"{value}"
elif field.minValue or field.maxValue:
value = f"[{field.minValue if field.minValue else '-'} : {field.maxValue if field.maxValue else '-' }]"
description = f" {field.description}" if field.description else ""
invalid = f" (Invalid: {field.invalidValue}) " if field.invalidValue else ""
markdown += f"{field.name} | `{field.type}` |{unit}|{value}|{description}{invalid}\n"
# Generate table for command docs
if len(self.commandConstants) > 0:
#print("DEBUGCOMMAND")
markdown += f"\n## Commands\n\n"
"""
markdown += "Name | Type | Value | Description\n"
markdown += "--- | --- | --- |---\n"
for name, command in self.commandConstants.items():
description = f" {command.comment} " if enum.comment else " "
markdown += f'<a href="#{name}"></a> {name} | `{command.type}` | {command.value} |{description}\n'
"""
for commandConstant in self.commandConstants.values():
#print(commandConstant)
markdown += commandConstant.markdown_out()
# Generate enum docs
if len(self.enums) > 0:
markdown += f"\n## Enums\n"
for name, enum in self.enums.items():
markdown += f"\n### {name} {{#{name}}}\n\n"
markdown += "Name | Type | Value | Description\n"
markdown += "--- | --- | --- | ---\n"
for enumValueName, enumValue in enum.enumValues.items():
description = f" {enumValue.comment} " if enumValue.comment else " "
markdown += f'<a href="#{enumValueName}"></a> {enumValueName} | `{enumValue.type}` | {enumValue.value} |{description}\n'
# Generate table for constants docs
if len(self.constantFields) > 0:
markdown += f"\n## Constants\n\n"
markdown += "Name | Type | Value | Description\n"
markdown += "--- | --- | --- |---\n"
for name, enum in self.constantFields.items():
description = f" {enum.comment} " if enum.comment else " "
markdown += f'<a href="#{name}"></a> {name} | `{enum.type}` | {enum.value} |{description}\n'
# Append msg contents to the end
with open(self.msg_filename, 'r') as source_file:
msg_contents = source_file.read()
msg_contents = msg_contents.strip()
#Format markdown using msg name, comment, url, contents.
markdown += f"""
## Source Message
[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/{self.filename})
::: details Click here to see original file
```c
{msg_contents}
```
:::
"""
with open(self.output_file, 'w') as content_file:
content_file.write(markdown)
#exit()
def display_info(self):
print(f"UORBMessage: display_info")
print(f" name: {self.name}")
print(f" filename: {self.filename}, ")
print(f" msg_filename: {self.msg_filename}, ")
print(f"self.shortDescription: {self.shortDescription}")
print(f"self.longDescription: {self.longDescription}")
print(f"self.enums: {self.enums}")
for enum, enumObject in self.enums.items():
enumObject.display_info()
# Output our data so far
for field in self.fields:
field.display_info()
for enumvalue in self.constantFields:
print(enumvalue)
self.constantFields[enumvalue].display_info()
def handleField(self, line, line_number, parentMessage):
#print(f"debug: handleField: (line): \n {line}")
# Note, here we know we don't have a comment or a topic.
# We expect it to be a field.
# Check field doesn't have leading whitespace (trailing spaces already checked)
if line[:1].isspace(): # Returns True for ' ', '\t', '\n', '\r', etc.
#print("First character is whitespace")
error = Error("leading_whitespace_field_or_constant", self.filename, line_number, line)
if not "leading_whitespace_field_or_constant" in self.errors:
self.errors["leading_whitespace_field_or_constant"] = []
self.errors["leading_whitespace_field_or_constant"].append(error)
# Now we can parse the stripped line
fieldOrConstant = line.strip()
# Check that the field or constant has only single whitespace separators
stripped_fieldOrConstant = re.sub(r'\s+', ' ', fieldOrConstant) # Collapse all spaces to a single space (LHS already stripped).
if stripped_fieldOrConstant != fieldOrConstant:
#print("Field/Constant has multiple whitespace characters") # Since the collapsed version shows them.
error = Error("field_or_constant_has_multiple_whitepsace", self.filename, line_number, line)
if not "field_or_constant_has_multiple_whitepsace" in self.errors:
self.errors["field_or_constant_has_multiple_whitepsace"] = []
self.errors["field_or_constant_has_multiple_whitepsace"].append(error)
fieldOrConstant = stripped_fieldOrConstant
comment = None
if "#" in line:
commentExtract = line.split("#", 1) # Split once on left-most '#'
fieldOrConstant = commentExtract[0].strip()
comment = commentExtract[-1].strip()
if "=" not in fieldOrConstant:
# Is a field:
field = fieldOrConstant.split(" ")
type = field[0].strip()
name = field[1].strip()
field = MessageField(name, type, comment, line_number, parentMessage)
self.fields.append(field)
else:
temp = fieldOrConstant.split("=")
value = temp[-1]
typeAndName = temp[0].split(" ")
type = typeAndName[0]
name = typeAndName[1]
if name.startswith("VEHICLE_CMD_") and parentMessage.name == 'VehicleCommand': #it's a command.
#print(f"DEBUG: startswith VEHICLE_CMD_ {name}")
commandConstant = CommandConstant(name, type, value, comment, line_number, parentMessage)
#commandConstant.display_info()
self.commandConstants[name]=commandConstant
else: #it's a constant (or part of an enum)
constantField = ConstantValue(name, type, value, comment, line_number)
self.constantFields[name]=constantField
def parseFile(self):
initial_block_lines = []
#stopping_token = None
found_first_relevant_content = False
gettingInitialComments = False
gettingFields = False
with open(self.msg_filename, 'r', encoding='utf-8') as uorbfile:
lines = uorbfile.read().splitlines()
for line_number, line in enumerate(lines, 1):
if line != line.rstrip():
#print(f"[{self.filename}] Trailing whitespace on line {line_number}: XX{line}YY")
error = Error("trailing_whitespace", self.filename, line_number, line)
if not "trailing_whitespace" in self.errors:
self.errors["trailing_whitespace"] = []
self.errors["trailing_whitespace"].append(error)
#print(f"line: {line}")
stripped_line = re.sub(r'\s+', ' ', line).strip() # Collapse all spaces to a single space and strip stuff off end.
#print(f"stripped_line: {stripped_line}")
# TODO? Perhaps report whitespace if the size of those two is different and it is empty
# Or perhaps we just fix it on request
isEmptyLine = False if line.strip() else True
if not found_first_relevant_content and isEmptyLine: #Empty line
#print(f"{self.filename}: Empty line at start of file: [{line_number}]\n {line}")
error = Error("empty_start_line", self.filename, line_number, line)
if not "empty_start_line" in self.errors:
self.errors["empty_start_line"] = []
self.errors["empty_start_line"].append(error)
#error.display_error()
continue
if not found_first_relevant_content and not isEmptyLine:
found_first_relevant_content = True
if stripped_line.startswith("#"):
gettingInitialComments = True
else:
gettingInitialComments = False
gettingFields = True
if gettingInitialComments and stripped_line.startswith("#"):
stripped_line=stripped_line[1:].strip()
#print(f"DEBUG: gettingInitialComments: comment line: {stripped_line}")
initial_block_lines.append(stripped_line)
else:
gettingInitialComments = False
gettingFields = True #Getting fields and constants
if gettingFields:
if isEmptyLine:
continue # empty line
if stripped_line.startswith("# TOPICS "):
stripped_line = stripped_line[9:]
stripped_line = stripped_line.split(" ")
self.topics+= stripped_line
# Note, default topic and topic errors handled after all lines parsed
continue
if stripped_line.startswith("#"):
# Its an internal comment
stripped_line=stripped_line[1:].strip()
if stripped_line:
#print(f"{self.filename}: Internal comment: [{line_number}]\n {line}")
error = Error("internal_comment", self.filename, line_number, line)
if not "internal_comment" in self.errors:
self.errors["internal_comment"] = []
self.errors["internal_comment"].append(error)
else:
#print(f"{self.filename}: Empty internal comment: [{line_number}]\n {line}")
error = Error("internal_comment_empty", self.filename, line_number, line)
if not "internal_comment_empty" in self.errors:
self.errors["internal_comment_empty"] = []
self.errors["internal_comment_empty"].append(error)
#pass # Empty comment
continue
# Must be a field or a comment.
self.handleField(line, line_number, parentMessage=self)
# Fix up topics if the topic is empty
def camel_to_snake(name):
# Match upper case not at start of string
s1 = re.sub('(.)([A-Z][a-z]+)', r'\1_\2', name)
# Handle cases with multiple capital first letter
return re.sub('([A-Z]+)([A-Z][a-z]*)', r'\1_\2', s1).lower()
defaultTopic = camel_to_snake(self.name)
if len(self.topics) == 0:
# We have no topic declared, so set the default topic
self.topics.append(defaultTopic)
elif len(self.topics) == 1:
# We have 1 topic declared - either it is default or there is some issue.
if defaultTopic in self.topics:
# Declared topic is default topic
error = Error("topic_error", self.filename, "", f"WARNING: TOPIC {defaultTopic} unnecessarily declared for {self.name}")
else:
# Declared topic is not default topic
error = Error("topic_error", self.filename, "", f"NOTE: TOPIC {self.topics[1]}: Only Declared topic is not default topic {defaultTopic} for {self.name}")
if not "topic_error" in self.errors:
self.errors["topic_error"] = []
self.errors["topic_error"].append(error)
elif len(self.topics) > 1:
if defaultTopic not in self.topics:
error = Error("topic_error", self.filename, "", f"NOTE: TOPIC - Default topic {defaultTopic} for {self.name} not in {self.topics}")
# Parse our short and long description
#print(f"DEBUG: initial_block_lines: {initial_block_lines}")
doingLongDescription = False
for summaryline in initial_block_lines:
if not self.shortDescription and summaryline.strip() == '':
continue
if not doingLongDescription and not summaryline.strip() == '':
self.shortDescription += f" {summaryline}"
self.shortDescription = self.shortDescription.strip()
if not self.shortDescription[-1:] == ".": # Add terminating fullstop if not present.
self.shortDescription += "."
if not doingLongDescription and summaryline.strip() == '':
doingLongDescription = True
continue
if doingLongDescription:
self.longDescription += f"{summaryline}\n"
if self.longDescription:
self.longDescription.strip()
if not self.shortDescription:
# Summary has not been defined
error = Error("summary_missing", self.filename)
if not "summary_missing" in self.errors:
self.errors["summary_missing"] = []
self.errors["summary_missing"].append(error)
# TODO Parse our constantValues into enums, leaving only constants
constantValuesToRemove = []
#print(f"DEBUG: Self.enums: {self.enums}")
for enumName, enumObject in self.enums.items():
for enumValueName, enumValueObject in self.constantFields.items():
if enumValueName.startswith(enumName):
# Copy this value into the object (cant be duplicate because parent is dict)
enumObject.enumValues[enumValueName]=enumValueObject
constantValuesToRemove.append(enumValueName)
# Now delete the original enumvalues
for enumValName in constantValuesToRemove:
del self.constantFields[enumValName]
constantsNotAssignedToEnums = len(self.constantFields)
if constantsNotAssignedToEnums > 0:
#print(f"Debug: WARNING constantsNotAssignedToEnums: {constantsNotAssignedToEnums}")
for enumValueName, enumValue in self.constantFields.items():
if enumValueName in ALLOWED_CONSTANTS_NOT_IN_ENUM: # Ignore constants
pass
else:
error = Error("constant_not_in_assigned_enum", self.filename, enumValue.line_number, enumValueName)
if not "constant_not_in_assigned_enum" in self.errors:
self.errors["constant_not_in_assigned_enum"] = []
self.errors["constant_not_in_assigned_enum"].append(error)
# TODO Maybe present as list of possible enums.
import yaml
@@ -924,50 +127,83 @@ if __name__ == "__main__":
parser = argparse.ArgumentParser(description='Generate docs from .msg files')
parser.add_argument('-d', dest='dir', help='output directory', required=True)
parser.add_argument('-e', dest='errors', action='store_true', help='Report errors')
parser.add_argument('-m', dest='error_messages', help='Message to report errors against (by default all)')
args = parser.parse_args()
output_dir = args.dir
if not os.path.isdir(output_dir):
print(f"making output_dir {output_dir}")
os.mkdir(output_dir)
msg_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),"../../msg")
msg_files = get_msgs_list(msg_path)
msg_files.sort()
versioned_msgs_list = ''
unversioned_msgs_list = ''
msgTypes = set()
for msg_file in msg_files:
# Add messages to set of allowed types (compound types)
#msg_type = msg_file.rsplit('/')[-1]
#msg_type = msg_type.rsplit('\\')[-1]
#msg_type = msg_type.rsplit('.')[0]
msg_name = os.path.splitext(os.path.basename(msg_file))[0]
msgTypes.add(msg_name)
output_file = os.path.join(output_dir, msg_name+'.md')
msg_filename = os.path.join(msg_path, msg_file)
print("{:} -> {:}".format(msg_filename, output_file))
for msg_file in msg_files:
message = UORBMessage(msg_file)
# Any additional tests that can't be in UORBMessage parser go here.
message.markdown_out()
#Format msg url
msg_url="[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/%s)" % msg_file
msg_description = ""
summary_description = ""
#Get msg description (first non-empty comment line from top of msg)
with open(msg_filename, 'r') as lineparser:
line = lineparser.readline()
while line.startswith('#') or (line.strip() == ''):
print('DEBUG: line: %s' % line)
line=line[1:].strip()+'\n'
stripped_line=line.strip()
if msg_description and not summary_description and stripped_line=='':
summary_description = msg_description.strip()
msg_description+=line
line = lineparser.readline()
msg_description=msg_description.strip()
if not summary_description and msg_description:
summary_description = msg_description
print('msg_description: Z%sZ' % msg_description)
print('summary_description: Z%sZ' % summary_description)
summary_description
msg_contents = ""
#Get msg contents (read the file)
with open(msg_filename, 'r') as source_file:
msg_contents = source_file.read()
#Format markdown using msg name, comment, url, contents.
markdown_output="""# %s (UORB message)
%s
%s
```c
%s
```
""" % (msg_name, msg_description, msg_url, msg_contents)
with open(output_file, 'w') as content_file:
content_file.write(markdown_output)
# Categorize as versioned or unversioned
if "versioned" in msg_file:
versioned_msgs_list += f"- [{message.name}]({message.name}.md)"
if message.shortDescription:
versioned_msgs_list += f"{message.shortDescription}"
versioned_msgs_list += '- [%s](%s.md)' % (msg_name, msg_name)
if summary_description:
versioned_msgs_list += "%s" % summary_description
versioned_msgs_list += "\n"
else:
unversioned_msgs_list += f"- [{message.name}]({message.name}.md)"
if message.shortDescription:
unversioned_msgs_list += f"{message.shortDescription}"
unversioned_msgs_list += '- [%s](%s.md)' % (msg_name, msg_name)
if summary_description:
unversioned_msgs_list += "%s" % summary_description
unversioned_msgs_list += "\n"
# Write out the index.md file
index_text=f"""# uORB Message Reference
index_text="""# uORB Message Reference
::: info
This list is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
@@ -982,14 +218,14 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
## Versioned Messages
{versioned_msgs_list}
%s
## Unversioned Messages
{unversioned_msgs_list}
"""
%s
""" % (versioned_msgs_list, unversioned_msgs_list)
index_file = os.path.join(output_dir, 'index.md')
with open(index_file, 'w', encoding='utf-8') as content_file:
with open(index_file, 'w') as content_file:
content_file.write(index_text)
generate_dds_yaml_doc(msg_files)
-2
View File
@@ -1138,8 +1138,6 @@ if num_mags >= 1:
if not math.isnan(sensor_mag_0['temperature'][0]):
mag_0_params['TC_M0_ID'] = int(np.median(sensor_mag_0['device_id']))
# find the min, max and reference temperature
mag_0_params['TC_M0_TMIN'] = np.amin(sensor_mag_0['temperature'])
mag_0_params['TC_M0_TMAX'] = np.amax(sensor_mag_0['temperature'])
File diff suppressed because it is too large Load Diff
+188
View File
@@ -0,0 +1,188 @@
#!/usr/bin/env python3
"""
Preprocesses ROMFS files with C preprocessor to enable KConfig support.
This script processes all rc* files in the ROMFS directory through the C preprocessor,
allowing use of #ifdef, #ifndef, #if, #else, #endif directives with KConfig definitions.
"""
import argparse
import os
import subprocess
import sys
import tempfile
from pathlib import Path
def preprocess_file(file_path, kconfig_header, cpp_command):
"""
Preprocess a single file through the C preprocessor.
Uses % as the preprocessor directive symbol (instead of #) to avoid conflicts
with shell comments. Converts %ifdef, %ifndef, %if, %else, %endif to
#ifdef, #ifndef, #if, #else, #endif before preprocessing.
Args:
file_path: Path to the file to preprocess
kconfig_header: Path to the px4_boardconfig.h header
cpp_command: C preprocessor command (usually the C compiler)
"""
# Read original file
with open(file_path, 'r') as f:
original_content = f.read()
# Process the file line by line:
# 1. Remove shell comment lines (to avoid conflicts with CPP)
# 2. Convert % preprocessor directives to # directives
lines = original_content.split('\n')
converted_lines = []
for line in lines:
stripped = line.lstrip()
# Check if line starts with % followed by a preprocessor keyword
if stripped.startswith('%ifdef ') or stripped.startswith('%ifdef\t'):
# Preserve leading whitespace, convert %ifdef to #ifdef
converted_lines.append(line.replace('%ifdef', '#ifdef', 1))
elif stripped.startswith('%ifndef ') or stripped.startswith('%ifndef\t'):
converted_lines.append(line.replace('%ifndef', '#ifndef', 1))
elif stripped.startswith('%if '):
converted_lines.append(line.replace('%if', '#if', 1))
elif stripped.startswith('%elif '):
converted_lines.append(line.replace('%elif', '#elif', 1))
elif stripped.startswith('%else'):
converted_lines.append(line.replace('%else', '#else', 1))
elif stripped.startswith('%endif'):
converted_lines.append(line.replace('%endif', '#endif', 1))
elif stripped.startswith('#') and not stripped.startswith('#!'):
# Remove shell comment lines (but keep shebang)
# This prevents "# if ..." comments from being interpreted as "#if" by CPP
continue
else:
converted_lines.append(line)
converted_content = '\n'.join(converted_lines)
# Create temporary file with include directive and converted content
with tempfile.NamedTemporaryFile(mode='w', suffix='.in', delete=False) as tmp:
tmp.write(f'#include "{kconfig_header}"\n')
tmp.write(converted_content)
tmp_path = tmp.name
try:
# Run C preprocessor
# -P: don't generate #line directives
# -E: preprocess only
# -undef: don't predefine any non-standard macros
# -nostdinc: don't search standard include directories
# -x assembler-with-cpp: treat input as assembly (allows # comments to pass through)
result = subprocess.run(
[cpp_command, '-P', '-E', '-undef', '-nostdinc', '-x', 'assembler-with-cpp', tmp_path],
capture_output=True,
text=True,
check=True
)
preprocessed = result.stdout
# Clean up the output:
# 1. Remove empty lines at the beginning
# 2. Remove lines that are just whitespace
lines = preprocessed.split('\n')
cleaned_lines = []
started = False
for line in lines:
# Skip empty lines at the beginning
if not started and not line.strip():
continue
started = True
cleaned_lines.append(line)
# Remove trailing empty lines
while cleaned_lines and not cleaned_lines[-1].strip():
cleaned_lines.pop()
# Write preprocessed content back
with open(file_path, 'w') as f:
f.write('\n'.join(cleaned_lines))
if cleaned_lines: # Add final newline if file is not empty
f.write('\n')
return True
except subprocess.CalledProcessError as e:
print(f"Error preprocessing {file_path}: {e}")
print(f"stderr: {e.stderr}")
return False
finally:
# Clean up temporary file
try:
os.unlink(tmp_path)
except:
pass
def main():
parser = argparse.ArgumentParser(description='Preprocess ROMFS files with KConfig definitions')
parser.add_argument('--romfs-dir', required=True, help='ROMFS root directory')
parser.add_argument('--kconfig-header', required=True, help='Path to px4_boardconfig.h')
parser.add_argument('--cpp', required=True, help='C preprocessor command')
parser.add_argument('--pattern', default='rc*', help='File pattern to preprocess (default: rc*)')
args = parser.parse_args()
# Verify inputs
romfs_dir = Path(args.romfs_dir)
kconfig_header = Path(args.kconfig_header)
if not romfs_dir.exists():
print(f"Error: ROMFS directory not found: {romfs_dir}")
return 1
if not kconfig_header.exists():
print(f"Error: KConfig header not found: {kconfig_header}")
return 1
# Find all files to preprocess in init.d directory
init_d_dir = romfs_dir / 'init.d'
if not init_d_dir.exists():
print(f"Warning: init.d directory not found in {romfs_dir}")
return 0
# Find all rc* files (shell scripts)
files_to_process = []
for pattern in ['rc*', 'rcS']:
files_to_process.extend(init_d_dir.glob(pattern))
# Also check subdirectories like airframes
for subdir in init_d_dir.iterdir():
if subdir.is_dir():
for pattern in ['rc*']:
files_to_process.extend(subdir.glob(pattern))
# Remove duplicates and filter only files
files_to_process = list(set([f for f in files_to_process if f.is_file()]))
if not files_to_process:
print(f"Warning: No files matching pattern '{args.pattern}' found in {init_d_dir}")
return 0
print(f"Preprocessing {len(files_to_process)} ROMFS files with KConfig definitions...")
# Process each file
success_count = 0
for file_path in sorted(files_to_process):
rel_path = file_path.relative_to(romfs_dir)
print(f" Processing: {rel_path}")
if preprocess_file(file_path, kconfig_header.absolute(), args.cpp):
success_count += 1
else:
print(f" Warning: Failed to preprocess {rel_path}")
print(f"Successfully preprocessed {success_count}/{len(files_to_process)} files")
return 0 if success_count == len(files_to_process) else 1
if __name__ == '__main__':
sys.exit(main())
+947
View File
@@ -0,0 +1,947 @@
#!/usr/bin/env python3
############################################################################
#
# Copyright (c) 2012-2024 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Serial firmware uploader for the PX4FMU bootloader
#
# The PX4 firmware file is a JSON-encoded Python object, containing
# metadata fields and a zlib-compressed base64-encoded firmware image.
#
# The uploader uses the following fields from the firmware file:
#
# image
# The firmware that will be uploaded.
# image_size
# The size of the firmware in bytes.
# board_id
# The board for which the firmware is intended.
# board_revision
# Currently only used for informational purposes.
#
import sys
import argparse
import binascii
import socket
import struct
import json
import zlib
import base64
import time
import array
import os
from sys import platform as _platform
try:
import serial
except ImportError as e:
print(f"Failed to import serial: {e}")
print("")
print("You may need to install it using:")
print(" python -m pip install pyserial")
print("")
sys.exit(1)
# Detect python version
if sys.version_info[0] < 3:
raise RuntimeError("Python 2 is not supported. Please try again using Python 3.")
sys.exit(1)
# Use monotonic time where available
def _time():
try:
return time.monotonic()
except Exception:
return time.time()
class FirmwareNotSuitableException(Exception):
def __init__(self, message):
super(FirmwareNotSuitableException, self).__init__(message)
class firmware(object):
'''Loads a firmware file'''
desc = {}
image = bytes()
def __init__(self, path):
# read the file
f = open(path, "r")
self.desc = json.load(f)
f.close()
self.image = bytearray(zlib.decompress(base64.b64decode(self.desc['image'])))
# pad image to 4-byte length
while ((len(self.image) % 4) != 0):
self.image.extend(b'\xff')
def property(self, propname):
return self.desc[propname]
def crc(self, padlen):
state = 0xFFFFFFFF
state = zlib.crc32(self.image, state)
padding_length = padlen - len(self.image)
if padding_length > 0:
padding = b'\xff' * padding_length
state = zlib.crc32(padding, state)
return (state ^ 0xFFFFFFFF) & 0xFFFFFFFF
class uploader:
'''Uploads a firmware file to the PX4 bootloader'''
# protocol bytes
INSYNC = b'\x12'
EOC = b'\x20'
# reply bytes
OK = b'\x10'
FAILED = b'\x11'
INVALID = b'\x13' # rev3+
BAD_SILICON_REV = b'\x14' # rev5+
# command bytes
NOP = b'\x00' # guaranteed to be discarded by the bootloader
GET_SYNC = b'\x21'
GET_DEVICE = b'\x22'
CHIP_ERASE = b'\x23'
CHIP_VERIFY = b'\x24' # rev2 only
PROG_MULTI = b'\x27'
READ_MULTI = b'\x28' # rev2 only
GET_CRC = b'\x29' # rev3+
GET_OTP = b'\x2a' # rev4+ , get a word from OTP area
GET_SN = b'\x2b' # rev4+ , get a word from SN area
GET_CHIP = b'\x2c' # rev5+ , get chip version
SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay
GET_CHIP_DES = b'\x2e' # rev5+ , get chip description in ASCII
GET_VERSION = b'\x2f' # rev5+ , get bootloader version in ASCII
CHIP_FULL_ERASE = b'\x40' # full erase of flash, rev6+
MAX_DES_LENGTH = 20
REBOOT = b'\x30'
INFO_BL_REV = b'\x01' # bootloader protocol revision
BL_REV_MIN = 2 # minimum supported bootloader protocol
BL_REV_MAX = 5 # maximum supported bootloader protocol
INFO_BOARD_ID = b'\x02' # board type
INFO_BOARD_REV = b'\x03' # board revision
INFO_FLASH_SIZE = b'\x04' # max firmware size in bytes
PROG_MULTI_MAX = 252 # protocol max is 255, must be multiple of 4
READ_MULTI_MAX = 252 # protocol max is 255
NSH_INIT = bytearray(b'\x0d\x0d\x0d')
NSH_REBOOT_BL = b"reboot -b\n"
NSH_REBOOT = b"reboot\n"
MAVLINK_REBOOT_ID1 = bytearray(b'\xfe\x21\x72\xff\x00\x4c\x00\x00\x40\x40\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf6\x00\x01\x00\x00\x53\x6b')
MAVLINK_REBOOT_ID0 = bytearray(b'\xfe\x21\x45\xff\x00\x4c\x00\x00\x40\x40\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf6\x00\x00\x00\x00\xcc\x37')
MAX_FLASH_PRGRAM_TIME = 0.001 # Time on an F7 to send SYNC, RESULT from last data in multi RXed
def __init__(self, portname, baudrate_bootloader, baudrate_flightstack):
# Open the port, keep the default timeout short so we can poll quickly.
# On some systems writes can suddenly get stuck without having a
# write_timeout > 0 set.
# chartime 8n1 * bit rate is us
self.chartime = 10 * (1.0 / baudrate_bootloader)
# we use a window approche to SYNC,<result> gathring
self.window = 0
self.window_max = 256
self.window_per = 2 # Sync,<result>
self.ackWindowedMode = False # Assume Non Widowed mode for all USB CDC
self.port = serial.Serial(portname, baudrate_bootloader, timeout=0.5, write_timeout=0)
self.otp = b''
self.sn = b''
self.baudrate_bootloader = baudrate_bootloader
self.baudrate_flightstack = baudrate_flightstack
self.baudrate_flightstack_idx = -1
self.force_erase = False
def close(self):
if self.port is not None:
self.port.close()
def open(self):
# upload timeout
timeout = _time() + 0.2
# attempt to open the port while it exists and until timeout occurs
while self.port is not None:
portopen = True
try:
portopen = self.port.is_open
except AttributeError:
portopen = self.port.isOpen()
if not portopen and _time() < timeout:
try:
self.port.open()
except OSError:
# wait for the port to be ready
time.sleep(0.04)
except serial.SerialException:
# if open fails, try again later
time.sleep(0.04)
else:
break
# debugging code
def __probe(self, state):
# self.port.setRTS(state)
return
def __send(self, c):
# print("send " + binascii.hexlify(c))
self.port.write(c)
def __recv(self, count=1):
c = self.port.read(count)
if len(c) < 1:
raise RuntimeError("timeout waiting for data (%u bytes)" % count)
# print("recv " + binascii.hexlify(c))
return c
def __recv_int(self):
raw = self.__recv(4)
val = struct.unpack("<I", raw)
return val[0]
def __getSync(self, doFlush=True):
if (doFlush):
self.port.flush()
c = bytes(self.__recv())
if c != self.INSYNC:
raise RuntimeError("unexpected %s instead of INSYNC" % c)
c = self.__recv()
if c == self.INVALID:
raise RuntimeError("bootloader reports INVALID OPERATION")
if c == self.FAILED:
raise RuntimeError("bootloader reports OPERATION FAILED")
if c != self.OK:
raise RuntimeError("unexpected response 0x%x instead of OK" % ord(c))
# The control flow for receiving Sync is on the order of 16 Ms per Sync
# This will validate all the SYNC,<results> for a window of programing
# in about 13.81 Ms for 256 blocks written
def __ackSyncWindow(self, count):
if (count > 0):
data = bytearray(bytes(self.__recv(count)))
if (len(data) != count):
raise RuntimeError("Ack Window %i not %i " % (len(data), count))
for i in range(0, len(data), 2):
if bytes([data[i]]) != self.INSYNC:
raise RuntimeError("unexpected %s instead of INSYNC" % data[i])
if bytes([data[i+1]]) == self.INVALID:
raise RuntimeError("bootloader reports INVALID OPERATION")
if bytes([data[i+1]]) == self.FAILED:
raise RuntimeError("bootloader reports OPERATION FAILED")
if bytes([data[i+1]]) != self.OK:
raise RuntimeError("unexpected response 0x%x instead of OK" % ord(data[i+1]))
# attempt to get back into sync with the bootloader
def __sync(self):
# send a stream of ignored bytes longer than the longest possible conversation
# that we might still have in progress
# self.__send(uploader.NOP * (uploader.PROG_MULTI_MAX + 2))
self.port.flushInput()
self.__send(uploader.GET_SYNC +
uploader.EOC)
self.__getSync()
def __trySync(self):
try:
self.port.flush()
if (self.__recv() != self.INSYNC):
# print("unexpected 0x%x instead of INSYNC" % ord(c))
return False
c = self.__recv()
if (c == self.BAD_SILICON_REV):
raise NotImplementedError()
if (c != self.OK):
# print("unexpected 0x%x instead of OK" % ord(c))
return False
return True
except NotImplementedError:
raise RuntimeError("Programing not supported for this version of silicon!\n"
"See https://docs.px4.io/main/en/flight_controller/silicon_errata.html")
except RuntimeError:
# timeout, no response yet
return False
# attempt to determins if the device is CDCACM or A FTDI
def __determineInterface(self):
self.port.flushInput()
# Set a baudrate that can not work on a real serial port
# in that it is 233% off.
try:
self.port.baudrate = self.baudrate_bootloader * 2.33
except NotImplementedError as e:
# This error can occur because pySerial on Windows does not support odd baudrates
print(f"{e} -> could not check for FTDI device, assuming USB connection")
return
self.__send(uploader.GET_SYNC +
uploader.EOC)
try:
self.__getSync(False)
except RuntimeError:
# if it fails we are on a real serial port - only leave this enabled on Windows
if sys.platform.startswith('win'):
self.ackWindowedMode = True
finally:
try:
self.port.baudrate = self.baudrate_bootloader
except Exception:
pass
# send the GET_DEVICE command and wait for an info parameter
def __getInfo(self, param):
self.__send(uploader.GET_DEVICE + param + uploader.EOC)
value = self.__recv_int()
self.__getSync()
return value
# send the GET_OTP command and wait for an info parameter
def __getOTP(self, param):
t = struct.pack("I", param) # int param as 32bit ( 4 byte ) char array.
self.__send(uploader.GET_OTP + t + uploader.EOC)
value = self.__recv(4)
self.__getSync()
return value
# send the GET_SN command and wait for an info parameter
def __getSN(self, param):
t = struct.pack("I", param) # int param as 32bit ( 4 byte ) char array.
self.__send(uploader.GET_SN + t + uploader.EOC)
value = self.__recv(4)
self.__getSync()
return value
# send the GET_CHIP command
def __getCHIP(self):
self.__send(uploader.GET_CHIP + uploader.EOC)
value = self.__recv_int()
self.__getSync()
return value
# send the GET_CHIP command
def __getCHIPDes(self):
self.__send(uploader.GET_CHIP_DES + uploader.EOC)
length = self.__recv_int()
value = self.__recv(length)
self.__getSync()
pieces = value.split(b",")
return pieces
def __getVersion(self):
self.__send(uploader.GET_VERSION + uploader.EOC)
try:
length = self.__recv_int()
value = self.__recv(length)
self.__getSync()
except RuntimeError:
# Bootloader doesn't support version call
return "unknown"
return value.decode()
def __drawProgressBar(self, label, progress, maxVal):
if maxVal < progress:
progress = maxVal
percent = (float(progress) / float(maxVal)) * 100.0
redraw = "\r" if sys.stdout.isatty() else "\n"
sys.stdout.write("%s%s: [%-20s] %.1f%%" % (redraw, label, '='*int(percent/5.0), percent))
sys.stdout.flush()
# send the CHIP_ERASE command and wait for the bootloader to become ready
def __erase(self, label):
print(f"Windowed mode: {self.ackWindowedMode}")
print("\n", end='')
if self.force_erase:
print("Trying force erase of full chip...\n")
self.__send(uploader.CHIP_FULL_ERASE +
uploader.EOC)
else:
self.__send(uploader.CHIP_ERASE +
uploader.EOC)
# erase is very slow, give it 30s
deadline = _time() + 30.0
while _time() < deadline:
usualEraseDuration = 15.0
estimatedTimeRemaining = deadline-_time()
if estimatedTimeRemaining >= usualEraseDuration:
self.__drawProgressBar(label, 30.0-estimatedTimeRemaining, usualEraseDuration)
else:
self.__drawProgressBar(label, 10.0, 10.0)
sys.stdout.write(" (timeout: %d seconds) " % int(deadline-_time()))
sys.stdout.flush()
if self.__trySync():
self.__drawProgressBar(label, 10.0, 10.0)
if self.force_erase:
print("\nForce erase done.\n")
return
if self.force_erase:
raise RuntimeError("timed out waiting for erase, force erase is likely not supported by bootloader!")
else:
raise RuntimeError("timed out waiting for erase")
# send a PROG_MULTI command to write a collection of bytes
def __program_multi(self, data, windowMode):
length = len(data).to_bytes(1, byteorder='big')
self.__send(uploader.PROG_MULTI)
self.__send(length)
self.__send(data)
self.__send(uploader.EOC)
if (not windowMode):
self.__getSync(False)
else:
# The following is done to have minimum delay on the transmission
# of the ne fw. The per block cost of __getSync was about 16 mS per.
# Passively wait on Sync and Result using board rates and
# N.B. attempts to activly wait on InWating still carried 8 mS of overhead
self.__probe(False)
self.__probe(True)
time.sleep((ord(length) * self.chartime) + uploader.MAX_FLASH_PRGRAM_TIME)
self.__probe(False)
# verify multiple bytes in flash
def __verify_multi(self, data):
length = len(data).to_bytes(1, byteorder='big')
self.__send(uploader.READ_MULTI)
self.__send(length)
self.__send(uploader.EOC)
self.port.flush()
programmed = self.__recv(len(data))
if programmed != data:
print("got " + binascii.hexlify(programmed))
print("expect " + binascii.hexlify(data))
return False
self.__getSync()
return True
# send the reboot command
def __reboot(self):
self.__send(uploader.REBOOT +
uploader.EOC)
self.port.flush()
# v3+ can report failure if the first word flash fails
if self.bl_rev >= 3:
self.__getSync()
# split a sequence into a list of size-constrained pieces
def __split_len(self, seq, length):
return [seq[i:i+length] for i in range(0, len(seq), length)]
# upload code
def __program(self, label, fw):
self.__probe(False)
print("\n", end='')
code = fw.image
groups = self.__split_len(code, uploader.PROG_MULTI_MAX)
# Give imedate feedback
self.__drawProgressBar(label, 0, len(groups))
uploadProgress = 0
for bytes in groups:
self.__program_multi(bytes, self.ackWindowedMode)
# If in Window mode, extend the window size for the __ackSyncWindow
if self.ackWindowedMode:
self.window += self.window_per
# Print upload progress (throttled, so it does not delay upload progress)
uploadProgress += 1
if uploadProgress % 256 == 0:
self.__probe(True)
self.__probe(False)
self.__probe(True)
self.__ackSyncWindow(self.window)
self.__probe(False)
self.window = 0
self.__drawProgressBar(label, uploadProgress, len(groups))
# Do any remaining fragment
self.__ackSyncWindow(self.window)
self.window = 0
self.__drawProgressBar(label, 100, 100)
# verify code
def __verify_v2(self, label, fw):
print("\n", end='')
self.__send(uploader.CHIP_VERIFY +
uploader.EOC)
self.__getSync()
code = fw.image
groups = self.__split_len(code, uploader.READ_MULTI_MAX)
verifyProgress = 0
for bytes in groups:
verifyProgress += 1
if verifyProgress % 256 == 0:
self.__drawProgressBar(label, verifyProgress, len(groups))
if (not self.__verify_multi(bytes)):
raise RuntimeError("Verification failed")
self.__drawProgressBar(label, 100, 100)
def __verify_v3(self, label, fw):
print("\n", end='')
self.__drawProgressBar(label, 1, 100)
expect_crc = fw.crc(self.fw_maxsize)
self.__send(uploader.GET_CRC + uploader.EOC)
time.sleep(0.5)
report_crc = self.__recv_int()
self.__getSync()
if report_crc != expect_crc:
print("Expected 0x%x" % expect_crc)
print("Got 0x%x" % report_crc)
raise RuntimeError("Program CRC failed")
self.__drawProgressBar(label, 100, 100)
def __set_boot_delay(self, boot_delay):
self.__send(uploader.SET_BOOT_DELAY +
struct.pack("b", boot_delay) +
uploader.EOC)
self.__getSync()
# get basic data about the board
def identify(self):
self.__determineInterface()
# make sure we are in sync before starting
self.__sync()
# get the bootloader protocol ID first
self.bl_rev = self.__getInfo(uploader.INFO_BL_REV)
if (self.bl_rev < uploader.BL_REV_MIN) or (self.bl_rev > uploader.BL_REV_MAX):
print("Unsupported bootloader protocol %d" % uploader.INFO_BL_REV)
raise RuntimeError("Bootloader protocol mismatch")
self.board_type = self.__getInfo(uploader.INFO_BOARD_ID)
self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV)
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
self.version = self.__getVersion()
# upload the firmware
def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_erase=False):
self.force_erase = force_erase
# select correct binary
found_suitable_firmware = False
for file in fw_list:
fw = firmware(file)
if self.board_type == fw.property('board_id'):
if len(fw_list) > 1: print("using firmware binary {}".format(file))
found_suitable_firmware = True
break
if not found_suitable_firmware:
msg = "Firmware not suitable for this board (Firmware board_type=%u board_id=%u)" % (
self.board_type, fw.property('board_id'))
print("WARNING: %s" % msg)
if force:
if len(fw_list) > 1:
raise FirmwareNotSuitableException("force flashing failed, more than one file provided, none suitable")
print("FORCED WRITE, FLASHING ANYWAY!")
else:
raise FirmwareNotSuitableException(msg)
percent = fw.property('image_size') / fw.property('image_maxsize')
binary_size = float(fw.property('image_size'))
binary_max_size = float(fw.property('image_maxsize'))
percent = (binary_size / binary_max_size) * 100
print("Loaded firmware for board id: %s,%s size: %d bytes (%.2f%%) " % (fw.property('board_id'), fw.property('board_revision'), fw.property('image_size'), percent))
print()
print(f"Bootloader version: {self.version}")
# Make sure we are doing the right thing
start = _time()
if self.board_type != fw.property('board_id'):
msg = "Firmware not suitable for this board (Firmware board_type=%u board_id=%u)" % (
self.board_type, fw.property('board_id'))
print("WARNING: %s" % msg)
if force:
print("FORCED WRITE, FLASHING ANYWAY!")
else:
raise FirmwareNotSuitableException(msg)
# Prevent uploads where the image would overflow the flash
if self.fw_maxsize < fw.property('image_size'):
raise RuntimeError("Firmware image is too large for this board")
# OTP added in v4:
if self.bl_rev >= 4:
for byte in range(0, 32*6, 4):
x = self.__getOTP(byte)
self.otp = self.otp + x
# print(binascii.hexlify(x).decode('Latin-1') + ' ', end='')
# see src/modules/systemlib/otp.h in px4 code:
self.otp_id = self.otp[0:4]
self.otp_idtype = self.otp[4:5]
self.otp_vid = self.otp[8:4:-1]
self.otp_pid = self.otp[12:8:-1]
self.otp_coa = self.otp[32:160]
# show user:
try:
print("Sn: ", end='')
for byte in range(0, 12, 4):
x = self.__getSN(byte)
x = x[::-1] # reverse the bytes
self.sn = self.sn + x
print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
print('')
print("Chip: %08x" % self.__getCHIP())
otp_id = self.otp_id.decode('Latin-1')
if ("PX4" in otp_id):
print("OTP id: " + otp_id)
print("OTP idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1'))
print("OTP vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1'))
print("OTP pid: " + binascii.hexlify(self.otp_pid).decode('Latin-1'))
print("OTP coa: " + binascii.b2a_base64(self.otp_coa).decode('Latin-1'))
except Exception as e:
# ignore bad character encodings
print(f"Exception ignored: {e}")
pass
# Silicon errata check was added in v5
if (self.bl_rev >= 5):
des = self.__getCHIPDes()
if (len(des) == 2):
family, revision = des
print(f"Family: {family.decode()}")
print(f"Revision: {revision.decode()}")
print(f"Flash: {self.fw_maxsize} bytes")
# Prevent uploads where the maximum image size of the board config is smaller than the flash
# of the board. This is a hint the user chose the wrong config and will lack features
# for this particular board.
# This check should also check if the revision is an unaffected revision
# and thus can support the full flash, see
# https://github.com/PX4/Firmware/blob/master/src/drivers/boards/common/stm32/board_mcu_version.c#L125-L144
if self.fw_maxsize > fw.property('image_maxsize') and not force:
print(f"WARNING: Board can accept larger flash images ({self.fw_maxsize} bytes) than board config ({fw.property('image_maxsize')} bytes)")
else:
# If we're still on bootloader v4 on a Pixhawk, we don't know if we
# have the silicon errata and therefore need to flash px4_fmu-v2
# with 1MB flash or if it supports px4_fmu-v3 with 2MB flash.
if fw.property('board_id') == 9 \
and fw.property('image_size') > 1032192 \
and not force:
raise RuntimeError("\nThe Board uses bootloader revision 4 and can therefore not determine\n"
"if flashing more than 1 MB (px4_fmu-v3_default) is safe, chances are\n"
"high that it is not safe! If unsure, use px4_fmu-v2_default.\n"
"\n"
"If you know you that the board does not have the silicon errata, use\n"
"this script with --force, or update the bootloader. If you are invoking\n"
"upload using make, you can use force-upload target to force the upload.\n")
self.__erase("Erase ")
self.__program("Program", fw)
if self.bl_rev == 2:
self.__verify_v2("Verify ", fw)
else:
self.__verify_v3("Verify ", fw)
if boot_delay is not None:
self.__set_boot_delay(boot_delay)
print("\nRebooting.", end='')
self.__reboot()
self.port.close()
print(" Elapsed Time %3.3f\n" % (_time() - start))
def __next_baud_flightstack(self):
if self.baudrate_flightstack_idx + 1 >= len(self.baudrate_flightstack):
return False
try:
self.port.baudrate = self.baudrate_flightstack[self.baudrate_flightstack_idx + 1]
self.baudrate_flightstack_idx = self.baudrate_flightstack_idx + 1
except serial.SerialException:
# Sometimes _configure_port fails
time.sleep(0.04)
return True
def send_protocol_splitter_format(self, data):
# Header Structure:
# bits: 1 2 3 4 5 6 7 8
# header[0] - | Magic | (='S')
# header[1] - |T| LenH | (T - 0: mavlink; 1: rtps)
# header[2] - | LenL |
# header[3] - | Checksum |
MAGIC = 83
len_bytes = len(data).to_bytes(2, "big")
LEN_H = len_bytes[0] & 127
LEN_L = len_bytes[1] & 255
CHECKSUM = MAGIC ^ LEN_H ^ LEN_L
header_ints = [MAGIC, LEN_H, LEN_L, CHECKSUM]
header_bytes = struct.pack("{}B".format(len(header_ints)), *header_ints)
self.__send(header_bytes)
self.__send(data)
def send_reboot(self, use_protocol_splitter_format=False):
if (not self.__next_baud_flightstack()):
return False
print("Attempting reboot on %s with baudrate=%d..." % (self.port.port, self.port.baudrate), file=sys.stderr)
if "ttyS" in self.port.port:
print("If the board does not respond, check the connection to the Flight Controller")
else:
print("If the board does not respond, unplug and re-plug the USB connector.", file=sys.stderr)
try:
send_fct = self.__send
if use_protocol_splitter_format:
send_fct = self.send_protocol_splitter_format
# try MAVLINK command first
self.port.flush()
send_fct(uploader.MAVLINK_REBOOT_ID1)
send_fct(uploader.MAVLINK_REBOOT_ID0)
# then try reboot via NSH
send_fct(uploader.NSH_INIT)
send_fct(uploader.NSH_REBOOT_BL)
send_fct(uploader.NSH_INIT)
send_fct(uploader.NSH_REBOOT)
self.port.flush()
self.port.baudrate = self.baudrate_bootloader
except Exception:
try:
self.port.flush()
self.port.baudrate = self.baudrate_bootloader
except Exception:
pass
return True
def main():
# Parse commandline arguments
parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
parser.add_argument('--port', action="store", required=True, help="Comma-separated list of serial port(s) to which the FMU may be attached")
parser.add_argument('--baud-bootloader', action="store", type=int, default=115200, help="Baud rate of the serial port (default is 115200) when communicating with bootloader, only required for true serial ports.")
parser.add_argument('--baud-flightstack', action="store", default="57600", help="Comma-separated list of baud rate of the serial port (default is 57600) when communicating with flight stack (Mavlink or NSH), only required for true serial ports.")
parser.add_argument('--force', action='store_true', default=False, help='Override board type check, or silicon errata checks and continue loading')
parser.add_argument('--force-erase', action="store_true", help="Do not perform the blank check, always erase every sector of the application space")
parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash')
parser.add_argument('--use-protocol-splitter-format', action='store_true', help='use protocol splitter format for reboot')
parser.add_argument('firmware', action="store", nargs='+', help="Firmware file(s)")
args = parser.parse_args()
if args.use_protocol_splitter_format:
print("Using protocol splitter format to reboot pixhawk!")
# warn people about ModemManager which interferes badly with Pixhawk
if os.path.exists("/usr/sbin/ModemManager"):
print("==========================================================================================================")
print("WARNING: You should uninstall ModemManager as it conflicts with any non-modem serial device (like Pixhawk)")
print("==========================================================================================================")
print("Waiting for bootloader...")
# tell any GCS that might be connected to the autopilot to give up
# control of the serial port
# send to localhost and default GCS port
ipaddr = '127.0.0.1'
portnum = 14550
# COMMAND_LONG in MAVLink 1
heartbeatpacket = bytearray.fromhex('fe097001010000000100020c5103033c8a')
commandpacket = bytearray.fromhex('fe210101014c00000000000000000000000000000000000000000000803f00000000f6000000008459')
# initialize an UDP socket
s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
# send heartbeat to initialize connection and command to free the link
s.sendto(heartbeatpacket, (ipaddr, portnum))
s.sendto(commandpacket, (ipaddr, portnum))
# close the socket
s.close()
# Spin waiting for a device to show up
try:
while True:
portlist = []
patterns = args.port.split(",")
# on unix-like platforms use glob to support wildcard ports. This allows
# the use of /dev/serial/by-id/usb-3D_Robotics on Linux, which prevents the upload from
# causing modem hangups etc
if "linux" in _platform or "darwin" in _platform or "cygwin" in _platform:
import glob
for pattern in patterns:
portlist += glob.glob(pattern)
else:
portlist = patterns
baud_flightstack = [int(x) for x in args.baud_flightstack.split(',')]
successful = False
unsuitable_board = False
for port in portlist:
# print("Trying %s" % port)
# create an uploader attached to the port
try:
if "linux" in _platform:
# Linux, don't open Mac OS and Win ports
if "COM" not in port and "tty.usb" not in port:
up = uploader(port, args.baud_bootloader, baud_flightstack)
elif "darwin" in _platform:
# OS X, don't open Windows and Linux ports
if "COM" not in port and "ACM" not in port:
up = uploader(port, args.baud_bootloader, baud_flightstack)
elif "cygwin" in _platform:
# Cygwin, don't open native Windows COM and Linux ports
if "COM" not in port and "ACM" not in port:
up = uploader(port, args.baud_bootloader, baud_flightstack)
elif "win" in _platform:
# Windows, don't open POSIX ports
if "/" not in port:
up = uploader(port, args.baud_bootloader, baud_flightstack)
except Exception as e:
# open failed, rate-limit our attempts
time.sleep(0.05)
print(f"Exception ignored: {e}")
# and loop to the next port
continue
found_bootloader = False
while True:
up.open()
# port is open, try talking to it
try:
# identify the bootloader
up.identify()
found_bootloader = True
print()
print(f"Found board id: {up.board_type},{up.board_rev} bootloader protocol revision {up.bl_rev} on {port}")
break
except (RuntimeError, serial.SerialException):
if not up.send_reboot(args.use_protocol_splitter_format):
break
# wait for the reboot, without we might run into Serial I/O Error 5
time.sleep(0.25)
# always close the port
up.close()
# wait for the close, without we might run into Serial I/O Error 6
time.sleep(0.3)
if not found_bootloader:
# Go to the next port
continue
try:
# ok, we have a bootloader, try flashing it
up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay, force_erase=args.force_erase)
# if we made this far without raising exceptions, the upload was successful
successful = True
except RuntimeError as e:
# print the error
print(f"\n\nError: {e}")
except FirmwareNotSuitableException:
unsuitable_board = True
up.close()
continue
except IOError:
up.close()
continue
finally:
# always close the port
up.close()
# we could loop here if we wanted to wait for more boards...
if successful:
sys.exit(0)
else:
sys.exit(1)
if unsuitable_board:
# If we land here, we went through all ports, did not flash any
# board and found at least one unsuitable board.
# Exit with 2, so a caller can distinguish from other errors
sys.exit(2)
# Delay retries to < 20 Hz to prevent spin-lock from hogging the CPU
time.sleep(0.05)
# CTRL+C aborts the upload/spin-lock by interrupt mechanics
except KeyboardInterrupt:
print("\n Upload aborted by user.")
sys.exit(0)
if __name__ == '__main__':
main()
# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4
+2 -4
View File
@@ -176,10 +176,8 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
echo
echo "Fetching Xtensa compilers"
XTENSA_FILE_NAME=xtensa-esp-elf-13.2.0_20240530-x86_64-linux-gnu.tar.xz
wget -q -P $DIR https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/$XTENSA_FILE_NAME
sudo tar -xf $DIR/$XTENSA_FILE_NAME -C /opt
rm $DIR/$XTENSA_FILE_NAME
wget -q -P $DIR https://github.com/espressif/crosstool-NG/releases/download/esp-13.2.0_20240530/xtensa-esp-elf-13.2.0_20240530-x86_64-linux-gnu.tar.xz
sudo tar -xf $DIR/xtensa-esp-elf-13.2.0_20240530-x86_64-linux-gnu.tar.xz -C /opt
echo 'export PATH=$PATH:/opt/xtensa-esp-elf/bin/' >> /home/$USER/.bashrc
fi
-1
View File
@@ -31,7 +31,6 @@ CONFIG_UAVCANNODE_ESC_RAW_COMMAND=y
CONFIG_UAVCANNODE_ESC_STATUS=y
CONFIG_UAVCANNODE_FLOW_MEASUREMENT=y
CONFIG_UAVCANNODE_GNSS_FIX=y
CONFIG_UAVCANNODE_HARDPOINT_COMMAND=y
CONFIG_UAVCANNODE_HYGROMETER_MEASUREMENT=y
CONFIG_UAVCANNODE_LIGHTS_COMMAND=y
CONFIG_UAVCANNODE_MAGNETIC_FIELD_STRENGTH=y
-3
View File
@@ -15,8 +15,6 @@ CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_PPS_CAPTURE=y
CONFIG_DRIVERS_VTX=y
CONFIG_VTX_CRSF_MSP_SUPPORT=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_BMI088_ACCELEROMETER_INT2=y
CONFIG_COMMON_LIGHT=y
@@ -94,4 +92,3 @@ CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_WQ_TTY_STACKSIZE=2500
@@ -160,7 +160,7 @@ CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=24
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
-2
View File
@@ -1,6 +1,4 @@
# CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE is not set
CONFIG_DRIVERS_UAVCAN=n
CONFIG_MODULES_UXRCE_DDS_CLIENT=n
CONFIG_SYSTEMCMDS_SD_BENCH=n
CONFIG_SYSTEMCMDS_I2CDETECT=n
CONFIG_MODULES_ZENOH=y
@@ -16,36 +16,36 @@
# CONFIG_NSH_DISABLE_CAT is not set
# CONFIG_NSH_DISABLE_CD is not set
# CONFIG_NSH_DISABLE_CP is not set
CONFIG_NSH_DISABLE_DATE=y
CONFIG_NSH_DISABLE_DF=y
# CONFIG_NSH_DISABLE_DATE is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_ECHO is not set
# CONFIG_NSH_DISABLE_ENV is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
CONFIG_NSH_DISABLE_EXPORT=y
CONFIG_NSH_DISABLE_FREE=y
CONFIG_NSH_DISABLE_GET=y
# CONFIG_NSH_DISABLE_EXPORT is not set
# CONFIG_NSH_DISABLE_FREE is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_HELP is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_KILL is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_LS is not set
CONFIG_NSH_DISABLE_MKDIR=y
# CONFIG_NSH_DISABLE_MKDIR is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_MOUNT is not set
# CONFIG_NSH_DISABLE_MV is not set
CONFIG_NSH_DISABLE_PRINTF=y
CONFIG_NSH_DISABLE_PS=y
CONFIG_NSH_DISABLE_PSSTACKUSAGE=y
CONFIG_NSH_DISABLE_PWD=y
# CONFIG_NSH_DISABLE_PRINTF is not set
# CONFIG_NSH_DISABLE_PS is not set
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
# CONFIG_NSH_DISABLE_PWD is not set
# CONFIG_NSH_DISABLE_RM is not set
CONFIG_NSH_DISABLE_RMDIR=y
# CONFIG_NSH_DISABLE_RMDIR is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_SET is not set
# CONFIG_NSH_DISABLE_SLEEP is not set
# CONFIG_NSH_DISABLE_SOURCE is not set
# CONFIG_NSH_DISABLE_TEST is not set
CONFIG_NSH_DISABLE_TIME=y
# CONFIG_NSH_DISABLE_TIME is not set
# CONFIG_NSH_DISABLE_UMOUNT is not set
# CONFIG_NSH_DISABLE_UNSET is not set
# CONFIG_NSH_DISABLE_USLEEP is not set
+1 -1
View File
@@ -92,7 +92,7 @@ static bool phy_get_led(int led)
{
if (g_ledmap[led] != 0) {
return !imxrt_gpio_read(g_ledmap[led]);
return imxrt_gpio_read(!g_ledmap[led]);
}
return false;
+3 -3
View File
@@ -8,12 +8,12 @@ board_adc start
# IMU
if ! icm42688p -s -b 1 -R 4 start
then
bmi270 -s -b 1 -R 2 start
bmi270 -s -b 1 -R 4 start
fi
if ! icm42688p -s -b 4 -R 4 start
then
bmi270 -s -b 4 -R 2 start
bmi270 -s -b 4 -R 4 start
fi
# baro
@@ -23,4 +23,4 @@ then
fi
# internal mag
qmc5883p -I -R 4 start
qmc5883p -I -R 2 start
-41
View File
@@ -160,44 +160,3 @@
.vp-doc img {
display: inline; /* block by default set by vitepress */
}
/**
* Custom styles for wide pages
* -------------------------------------------------------------------------- */
.is-wide-page .content-container {
max-width: 100% !important;
}
@media (min-width: 1280px) {
.is-wide-page .content {
min-width: 940px !important;
}
}
/* Make page width larger */
@media (min-width: 1440px) {
.is-wide-page .VPSidebar {
padding-left: 32px !important;
width: var(--vp-sidebar-width) !important;
}
.is-wide-page .VPContent.has-sidebar {
padding-left: var(--vp-sidebar-width) !important;
padding-right: 0 !important;
}
.is-wide-page .VPNavBar.has-sidebar .title {
padding-left: 32px !important;
}
.is-wide-page .VPNavBar.has-sidebar .content {
padding-left: var(--vp-sidebar-width) !important;
padding-right: 32px !important;
}
/* Very hacky */
.is-wide-page .VPNavBar.has-sidebar #local-search {
z-index: 10;
}
}
-2
View File
@@ -93,7 +93,6 @@
- [Back-transition Tuning](config_vtol/vtol_back_transition_tuning.md)
- [VTOL w/o Airspeed Sensor](config_vtol/vtol_without_airspeed_sensor.md)
- [VTOL Weather Vane](config_vtol/vtol_weathervane.md)
- [VTOL Ice Shedding](config_vtol/vtol_ice_shedding.md)
- [Flight Modes](flight_modes_vtol/index.md)
- [Mission Mode (VTOL)](flight_modes_vtol/mission.md)
- [Return Mode (VTOL)](flight_modes_vtol/return.md)
@@ -351,7 +350,6 @@
- [FrSky Telemetry](peripherals/frsky_telemetry.md)
- [TBS Crossfire (CRSF) Telemetry](telemetry/crsf_telemetry.md)
- [Satellite Comms (Iridium/RockBlock)](advanced_features/satcom_roadblock.md)
- [Analog Video Transmitters](vtx/index.md)
- [Power Systems](power_systems/index.md)
- [Battery Estimation Tuning](config/battery.md)
+2 -2
View File
@@ -106,7 +106,7 @@ The settings and underlying parameters are shown below.
| Setting | Parameter | Description |
| -------------------------------------------------------------------- | ------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None (default), `1`: Warning, `3`: Return mode. |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None, `1`: Warning, `3`: Return mode (default). |
| <a id="COM_FLT_TIME_MAX"></a> Maximum flight time failsafe level | [COM_FLT_TIME_MAX](../advanced_config/parameter_reference.md#COM_FLT_TIME_MAX) | Maximum allowed flight time before Return mode will be engaged, in seconds. `-1`: Disabled (default). |
## Manual Control Loss Failsafe
@@ -283,7 +283,7 @@ Acting on a detected failure during flight is deactivated by default (enable by
During **takeoff** the failure detector [attitude trigger](#attitude-trigger) invokes the [disarm action](#act_disarm) if the vehicle flips (disarm kills the motors but, unlike flight termination, will not launch a parachute or perform other failure actions).
Note that this check is _always enabled on takeoff_, irrespective of the `CBRK_FLIGHTTERM` parameter.
The failure detector is active in all vehicle types and modes, except for those where the vehicle is _expected_ to do flips (i.e. [Acro mode (MC)](../flight_modes_mc/acro.md), [Acro mode (FW)](../flight_modes_fw/acro.md), and [Manual (FW)](../flight_modes_fw/manual.md)).
The failure detector is active in all vehicle types and modes, except for those where the vehicle is _expected_ to do flips (i.e. [Acro mode (MC)](../flight_modes_mc/altitude.md), [Acro mode (FW)](../flight_modes_fw/altitude.md), and [Manual (FW)](../flight_modes_fw/manual.md)).
### Attitude Trigger
-1
View File
@@ -9,4 +9,3 @@ Then perform VTOL-specific configuration and tuning:
- [Back-transition Tuning](../config_vtol/vtol_back_transition_tuning.md)
- [VTOL w/o Airspeed Sensor](../config_vtol/vtol_without_airspeed_sensor.md)
- [VTOL Weather Vane](../config_vtol/vtol_weathervane.md)
- [Ice Shedding](../config_vtol/vtol_ice_shedding.md)
-20
View File
@@ -1,20 +0,0 @@
# VTOL Ice Shedding feature
## Overview
Ice shedding is a feature that periodically spins unused motors in fixed-wing
flight, to break off any ice that is starting to build up in the motors while it
is still feasible to do so.
It is configured by the paramter `CA_ICE_PERIOD`. When it is 0, the feature is
disabled, when it is above 0, it sets the duration of the ice shedding cycle in
seconds. In each cycle, the rotors are spun for two seconds at a motor output of
0.01.
:::warning
When enabling the feature on a new airframe, there is the risk of producing
torques that disturb the fixed-wing rate controller. To mitigate this risk:
- Set your `PWM_MIN` values correctly, so that the motor output 0.01 actually
produces 1% thrust
- Be prepared to take control and switch back to multicopter
:::
+1 -1
View File
@@ -34,7 +34,7 @@ If you update an existing file you are not required to make the whole file compl
### Line Length
- Maximum line length is 140 characters.
- Maximum line length is 120 characters.
### File Extensions
+1 -1
View File
@@ -324,7 +324,7 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi
- [UXRCE_DDS_NS_IDX](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) <Badge type="tip" text="PX4 v1.17" />: Index-based namespace definition.
Setting this parameter to any value other than `-1` creates a namespace with the prefix `uav_` and the specified value, e.g. `uav_0`, `uav_1`, etc.
See [namespace](#customizing-the-namespace) for methods to define richer or arbitrary namespaces.
- [`UXRCE_DDS_FLCTRL`](../advanced_config/parameter_reference.md#UXRCE_DDS_FLCTRL) <Badge type="tip" text="main (planned for: PX4 v1.18)" />: Serial port hardware flow control enable.
- [`UXRCE_DDS_FLCTRL`](../advanced_config/parameter_reference.md#UXRCE_DDS_FLCTRL) <Badge type="tip" text="PX4 main" />: Serial port hardware flow control enable.
To use hardware flow control, a custom MicroXRCE Agent needs to be adopted. Please refer to [this PR](https://github.com/eProsima/Micro-XRCE-DDS-Agent/pull/407) for the required changes, cherry-pick them on top of the [agent version](#build-run-within-ros-2-workspace) you need to use and then run the agent with the additional `--flow-control` option.
::: info
+1 -5
View File
@@ -88,17 +88,13 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too
```
:::tip
The main function must be named `<module_name>_main` and exported from the module as shown.
:::
:::tip
`PX4_INFO` is the equivalent of `printf` for the PX4 shell (included from **px4_platform_common/log.h**).
There are different log levels: `PX4_INFO`, `PX4_WARN`, `PX4_ERR`, `PX4_DEBUG`.
Warnings and errors are additionally added to the [ULog](../dev_log/ulog_file_format.md) and shown on [Flight Review](https://logs.px4.io/).
:::
1. Create and open a new _cmake_ definition file named **CMakeLists.txt**.
@@ -164,7 +160,7 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too
1. Create and open a new _Kconfig_ definition file named **Kconfig** and define your symbol for naming (see [Kconfig naming convention](../hardware/porting_guide_config.md#px4-kconfig-symbol-naming-convention)).
Copy in the text below:
```text
```
menuconfig EXAMPLES_PX4_SIMPLE_APP
bool "px4_simple_app"
default n
@@ -22,11 +22,7 @@ If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tu
This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works.
The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether.
::: tip
For more information, see the Masters thesis from which this module was created: [Deep Reinforcement Learning for Embedded Control Policies for Aerial Vehicles](https://nva.sikt.no/registration/019b26689144-efeebae8-84d6-4413-ad7f-9aceb4ff7374).
In addition, the (Norwegian) website [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/) has a youtube video and a workshop paper .
:::
If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/).
## Neural Network PX4 Firmware
+1 -1
View File
@@ -35,7 +35,7 @@ The method we developed for training the RAPTOR policy is called Meta-Imitation
You can torture test the RAPTOR policy in your browser at [https://raptor.rl.tools](https://raptor.rl.tools) or in the embedded app here:
<iframe src="https://raptor.rl.tools?raptor=false" width="100%" height="1000" style="border: none;"></iframe>
<iframe src="https://rl-tools.github.io/raptor.rl.tools?raptor=false" width="100%" height="1000" style="border: none;"></iframe>
For more information please refer to the paper at [https://arxiv.org/abs/2509.11481](https://arxiv.org/abs/2509.11481).
+1 -1
View File
@@ -11,7 +11,7 @@ PX4 traffic avoidance works with ADS-B or FLARM products that supply transponder
It has been tested with the following devices:
- [PingRX ADS-B Receiver](https://uavionix.com/product/pingrx-pro/) (uAvionix)
- [FLARM](https://www.flarm.com/en/drones/)
- [FLARM](https://flarm.com/products/uav/atom-uav-flarm-for-drones/) <!-- I think originally https://flarm.com/products/powerflarm/uav/ -->
## Hardware Setup
+1 -7
View File
@@ -13,7 +13,7 @@ At the time of writing, parts of the PX4 ROS 2 Control Interface are experimenta
:::
The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) is a C++ library (with Python bindings) that simplifies controlling PX4 from ROS 2.
The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) is a C++ library that simplifies controlling PX4 from ROS 2.
Developers use the library to create and dynamically register modes written using ROS 2.
These modes are dynamically registered with PX4, and appear to be part of PX4 to a ground station or other external system.
@@ -25,12 +25,6 @@ These classes abstract the internal setpoints used by PX4, and that can therefor
PX4 ROS 2 modes are easier to implement and maintain than PX4 internal modes, and provide more resources for developers in terms of processing power and pre-existing libraries.
Unless the mode is safety-critical, requires strict timing or very high update rates, or your vehicle doesn't have a companion computer, you should [consider using PX4 ROS 2 modes in preference to PX4 internal modes](../concept/flight_modes.md#internal-vs-external-modes).
::: tip
If you want to use Python, check out the [examples in the repository](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/python).
Not all classes have Python bindings yet — the [supported bindings are here](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_py/src/px4_ros2).
You are welcome to add and contribute missing classes.
:::
## Overview
This diagram provides a conceptual overview of how the control interface modes and mode executors interact with PX4.
+1 -1
View File
@@ -6,7 +6,7 @@
At the time of writing, parts of the PX4 ROS 2 Interface Library are experimental, and hence subject to change.
:::
The [PX4 ROS 2 Interface Library](https://github.com/Auterion/px4-ros2-interface-lib) is a C++ library (with Python bindings) that simplifies controlling and interacting with PX4 from ROS 2.
The [PX4 ROS 2 Interface Library](https://github.com/Auterion/px4-ros2-interface-lib) is a C++ library that simplifies controlling and interacting with PX4 from ROS 2.
The library provides three high-level interfaces for developers:
-2
View File
@@ -15,8 +15,6 @@ The following models are supported by PX4, and can be connected to either the I2
| [LW20/C](https://lightware.co.za/products/lw20-c-100-m) | 100 | I2C bus | Waterproofed (IP67) with servo for sense-and-avoid applications |
| [SF30/D](https://lightwarelidar.com/shop/sf30-d-200-m/) | 200 | I2C bus | Waterproofed (IP67) |
| [SF45/B](../sensor/sf45_rotating_lidar.md) | 50 | Serial | Rotary Lidar (Used for [Collision Prevention](../computer_vision/collision_prevention.md)) |
| [GRF250](https://lightwarelidar.com/shop/grf-250/) | 250 | I2C | Gimbal Range Finder
| [GRF500](https://lightwarelidar.com/shop/grf-500/) | 500 | I2C | Gimbal Range Finder
::: details Discontinued
-287
View File
@@ -1,287 +0,0 @@
# Analog Video Transmitters
Analog Video Transmitters (VTX) can be controlled by PX4 via a half-duplex UART connection implementing the SmartAudio v1, v2, and v2.1 and Tramp protocols.
The protocols allow writing and reading:
- device status.
- transmission frequency in MHz or via band and channel index.
- transmission power in dBm or mW.
- operation modes.
VTX settings are controlled by parameters and optionally via RC AUX channels or CRSF MSP commands.
The driver stores frequency and power tables that map band/channel indices to actual transmission values.
Configuration is device-specific and set up using the command line interface.
## Getting Started
Connect the SmartAudio or Tramp pin of the VTX to the TX pin of a free serial port on the flight controller.
Then set the following parameters:
- `VTX_SER_CFG`: Select the serial port used for VTX communication.
- `VTX_DEVICE`: Selects the VTX device (generic SmartAudio/Tramp or a specific device).
Note that since the VTX communication is half-duplex, you can, for example, use the single-pin Radio Controller port for the VTX and use a full duplex TELEM port for CRSF communication.
You should now be able to see the VTX device in the driver status:
```
nsh> vtx status
INFO [vtx] UART device: /dev/ttyS4
INFO [vtx] VTX table "UNINITIALIZED":
INFO [vtx] Power levels:
INFO [vtx] RC mapping: Disabled
INFO [vtx] Parameters:
INFO [vtx] band: 1
INFO [vtx] channel: 1
INFO [vtx] frequency: 0 MHz
INFO [vtx] power level: 1
INFO [vtx] power: 0 = 0 mW
INFO [vtx] pit mode: off
INFO [vtx] SmartAudio v2:
INFO [vtx] band: 1
INFO [vtx] channel: 1
INFO [vtx] frequency: 6110 MHz
INFO [vtx] power level: 1
INFO [vtx] power: 0 mW
INFO [vtx] pit mode: on
INFO [vtx] lock: unlocked
```
:::warning
Without a configured power table, power mappings are unknown and default to 0 mW.
Some VTX devices enter pit mode when power is set to 0, regardless of the `VTX_PIT_MODE` parameter.
:::
## VTX Table Configuration
The VTX table stores frequency and power mappings for your specific device.
The manufacturer usually provides this information in the form of a JSON file that can be translated into a [Betaflight CLI command set](https://www.betaflight.com/docs/development/VTX#vtx-table) that this driver implements for compatibility.
### Power Level Configuration
```
# Set table name ≤16 characters
vtxtable name "Peak THOR T67"
# Set the power values that are sent to the VTX for each power level index
# Note: SmartAudio v1 and v2 use index values!
vtxtable powervalues 0 1 2 3 4
# Note: SmartAudio v2.1 uses dBm values instead!
# vtxtable powervalues 14 23 27 30 35
# Note: Tramp uses mW values instead!
# vtxtable powervalues 25 200 500 1000 3000
# Set the corresponding power labels for each power level index ≤4 characters.
# These are used for status reporting.
vtxtable powerlabels 25 200 500 1W 3W
# Set number of power levels
vtxtable powerlevels 5
# Save configuration
vtxtable save
```
This will create a VTX table with 5 power levels.
```nsh> vtxtable status
INFO [vtxtable] VTX table "Peak THOR T67":
INFO [vtxtable] Power levels:
INFO [vtxtable] 1: 0 = 25
INFO [vtxtable] 2: 1 = 200
INFO [vtxtable] 3: 2 = 500
INFO [vtxtable] 4: 3 = 1W
INFO [vtxtable] 5: 4 = 3W
```
### Frequency Table Configuration
```
# Set the name of each band and the frequencies of each channel
vtxtable band 1 BAND_A A FACTORY 6110 6130 6150 6170 6190 6210 6230 6250
vtxtable band 2 BAND_B B FACTORY 6270 6290 6310 6330 6350 6370 6390 6410
vtxtable band 3 BAND_E E FACTORY 6430 6450 6470 6490 6510 6530 6550 6570
vtxtable band 4 BAND_F F FACTORY 6590 6610 6630 6650 6670 6690 6710 6730
vtxtable band 5 BAND_R R FACTORY 6750 6770 6790 6810 6830 6850 6870 6890
vtxtable band 6 BAND_P P FACTORY 6910 6930 6950 6970 6990 7010 7030 7050
vtxtable band 7 BAND_H H FACTORY 7070 7090 7110 7130 7150 7170 7190 7210
vtxtable band 8 BAND_U U FACTORY 6115 6265 6425 6585 6745 6905 7065 7185
# Set number of bands and channels
vtxtable bands 8
vtxtable channels 8
# Save configuration
vtxtable save
```
This will create a VTX table with 8 bands and 8 channels.
Note that FACTORY sends the band and channel indexes to the VTX device and they use their internal frequency mapping. In this mode the frequency is just for indication purposes.
In contrast, CUSTOM would send the actual frequency values to the VTX device, but not all devices support this mode.
Setting a frequency to zero will skip setting it.
```
nsh> vtxtable status
INFO [vtxtable] VTX table 8x8: Peak THOR T67
INFO [vtxtable] A: BAND_A = 6110 6130 6150 6170 6190 6210 6230 6250
INFO [vtxtable] B: BAND_B = 6270 6290 6310 6330 6350 6370 6390 6410
INFO [vtxtable] E: BAND_E = 6430 6450 6470 6490 6510 6530 6550 6570
INFO [vtxtable] F: BAND_F = 6590 6610 6630 6650 6670 6690 6710 6730
INFO [vtxtable] R: BAND_R = 6750 6770 6790 6810 6830 6850 6870 6890
INFO [vtxtable] P: BAND_P = 6910 6930 6950 6970 6990 7010 7030 7050
INFO [vtxtable] H: BAND_H = 7070 7090 7110 7130 7150 7170 7190 7210
INFO [vtxtable] U: BAND_U = 6115 6265 6425 6585 6745 6905 7065 7185
```
### Table Constraints
Maximum table dimensions:
- ≤24 bands each with ≤16 channels and ≤32GHz frequency values.
- ≤16 power levels.
- ≤16 characters table name.
- ≤12 characters band name and 1 character band letter.
- ≤4 characters power label length (to support "2.5W").
## AUX Channel Mapping
The AUX mapping feature allows you to control VTX settings using RC AUX channels.
Each mapping entry defines an AUX channel range that triggers a specific VTX configuration.
To enable AUX mapping, set `VTX_MAP_CONFIG` to one of the following values:
- `0`: Disabled
- `1`: Disabled (reserved for CRSF MSP integration)
- `2`: Map AUX channels to power level control only
- `3`: Map AUX channels to band and channel control only
- `4`: Map AUX channels to all settings (power, band, and channel)
### Configuring AUX Map Entries
Use the following command format to add mapping entries:
```
vtxtable <index> <aux_channel> <band> <channel> <power> <start_pwm> <end_pwm>
```
Parameters:
- `index`: Map entry index (0-159)
- `aux_channel`: AUX channel number (3-19, where AUX1=3)
- `band`: Target band (1-24, or 0 to leave unchanged)
- `channel`: Target channel (1-16, or 0 to leave unchanged)
- `power`: Power level (1-16, 0 to leave unchanged, or -1 for pit mode)
- `start_pwm`: Start of PWM range in microseconds (typically 900-2100)
- `end_pwm`: End of PWM range in microseconds (typically 900-2100)
:::info
AUX channel numbering starts from 3 (AUX1=channel 3) to account for the first four RC channels 0-3 used for flight control.
:::
Example configuration for a 6-position dial controlling band/channel on AUX4 (channel 7):
```
vtx 0 7 7 1 0 900 1025
vtx 1 7 7 2 0 1025 1100
vtx 2 7 7 4 0 1100 1175
vtx 3 7 7 6 0 1175 1225
vtx 4 7 7 8 0 1225 1300
vtx 5 7 3 8 0 1300 2100
```
Example configuration for power control on AUX3 (channel 6):
```
vtxtable 16 6 0 0 -1 900 1250
vtxtable 17 6 0 0 1 1250 1525
vtxtable 18 6 0 0 2 1525 1650
vtxtable 19 6 0 0 3 1650 1875
vtxtable 20 6 0 0 4 1875 2010
```
Save the configuration with:
```
vtxtable save
```
The map status can be verified with `vtxtable status`.
## CRSF MSP Integration
When using a CRSF receiver with MSP support, you can control VTX settings directly from your transmitter using MSP commands sent over the CRSF link.
This feature must be enabled at compile time with the `VTX_CRSF_MSP_SUPPORT` Kconfig option.
To enable CRSF MSP control, set `VTX_MAP_CONFIG` to one of:
- `1`: MSP controls both frequency (band/channel) and power
- `2`: MSP controls frequency (band/channel) only, AUX controls power
- `3`: MSP controls power only, AUX controls band/channel
When MSP integration is active, the driver responds to `MSP_SET_VTX_CONFIG` (0x59) commands.
The transmitter can send band, channel, frequency, power level, and pit mode settings via MSP, which are automatically mapped to the corresponding PX4 parameters.
:::tip
The MSP integration allows seamless VTX control from transmitters that support VTX configuration via Lua scripts or built-in VTX menus without requiring additional hardware switches.
:::
## Build Configuration
Both the VTX driver and VTX table support are configured via Kconfig options.
Key configuration options:
- `VTX_CRSF_MSP_SUPPORT`: Enables CRSF MSP command support (default: disabled)
- `VTXTABLE_CONFIG_FILE`: File path for persistent configuration (default: `/fs/microsd/vtx_config`)
- `VTXTABLE_AUX_MAP`: Enables AUX channel mapping (default: disabled)
## Parameter Reference
### VTX Settings Parameters
- `VTX_BAND` (0-23): Frequency band selection (Band 1-24 in UI)
- `VTX_CHANNEL` (0-15): Channel within band (Channel 1-16 in UI)
- `VTX_FREQUENCY` (0-32000): Direct frequency in MHz (overrides band/channel when non-zero)
- `VTX_POWER` (0-15): Power level (Level 1-16 in UI, as configured in table)
- `VTX_PIT_MODE` (boolean): Pit mode for reduced power (default: disabled)
### Configuration Parameters
- `VTX_SER_CFG`: Serial port assignment for VTX communication
- `VTX_MAP_CONFIG`: Controls how VTX settings are mapped:
- Without `VTX_CRSF_MSP_SUPPORT`:
- `0`: Disabled
- `1`: Disabled
- `2`: AUX controls power only
- `3`: AUX controls band/channel only
- `4`: AUX controls both power and band/channel
- With `VTX_CRSF_MSP_SUPPORT`:
- `0`: Disabled
- `1`: MSP controls both frequency and power
- `2`: MSP controls frequency, AUX controls power
- `3`: MSP controls power, AUX controls band/channel
- `4`: Not used with MSP support
- `VTX_DEVICE`: Device-specific configuration (see below)
## Device-Specific Configuration
The `VTX_DEVICE` parameter allows device-specific workarounds.
It encodes both the protocol type and device variant:
- Low byte (bits 0-7): Protocol selection
- `0`: SmartAudio (default)
- `1`: Tramp
- High byte (bits 8-15): Device-specific variant
- `0`: Generic device
- `20`: Peak THOR T67
- `40`: Rush Max Solo
### Known Device Workarounds
**Peak THOR T67** (`VTX_DEVICE` = 5120):
This device incorrectly reports pit mode status but otherwise functions normally.
The driver applies a workaround to override the reported status with the actual configured state.
For generic devices, use `VTX_DEVICE` = 0 (SmartAudio) or `VTX_DEVICE` = 1 (Tramp).
+3 -9
View File
@@ -128,7 +128,6 @@
- [LED 신호 정의](getting_started/led_meanings.md)
- [알람 소리 정의](getting_started/tunes.md)
- [QGroundControl Flight-Readiness Status](flying/pre_flight_checks.md)
- [Asset Tracking](debug/asset_tracking.md)
- [Hardware Selection & Setup](hardware/drone_parts.md)
- [비행 컨트롤러 (오토파일럿)](flight_controller/index.md)
@@ -274,8 +273,6 @@
- [Holybro M8N & M9N GPS](gps_compass/gps_holybro_m8n_m9n.md)
- [Sky-Drones SmartAP GPS](gps_compass/gps_smartap.md)
- [RTK GNSS](gps_compass/rtk_gps.md)
- [ARK G5 RTK GPS](dronecan/ark_g5_rtk_gps.md)
- [ARK G5 RTK HEADING GPS](dronecan/ark_g5_rtk_heading_gps.md)
- [ARK RTK GPS (CAN)](dronecan/ark_rtk_gps.md)
- [ARK RTK GPS L1 L5 (CAN)](dronecan/ark_rtk_gps_l1_l2.md)
- [ARK X20 RTK GPS (CAN)](dronecan/ark_x20_rtk_gps.md)
@@ -843,11 +840,9 @@
- [Camera Integration/Architecture](camera/camera_architecture.md)
- [컴퓨터 비전](advanced/computer_vision.md)
- [Motion Capture (VICON, Optitrack, NOKOV)](tutorials/motion-capture.md)
- [Neural Networks](neural_networks/index.md)
- [MC NN Control Module (Generic)](neural_networks/mc_neural_network_control.md)
- [Neural Network Module Utilities](neural_networks/nn_module_utilities.md)
- [TensorFlow Lite Micro (TFLM)](neural_networks/tflm.md)
- [RAPTOR Adaptive RL NN Module](neural_networks/raptor.md)
- [Neural Networks](advanced/neural_networks.md)
- [Neural Network Module Utilities](advanced/nn_module_utilities.md)
- [TensorFlow Lite Micro (TFLM)](advanced/tflm.md)
- [Intel RealSense R200용 드라이버 설치](advanced/realsense_intel_driver.md)
- [상태 추정기 전환](advanced/switching_state_estimators.md)
- [트리 외부 모듈](advanced/out_of_tree_modules.md)
@@ -930,7 +925,6 @@
- [출시](releases/index.md)
- [main (alpha)](releases/main.md)
- [1.17 (alpha)](releases/1.17.md)
- [1.16 (stable)](releases/1.16.md)
- [1.15](releases/1.15.md)
- [1.14](releases/1.14.md)
+1 -1
View File
@@ -74,7 +74,7 @@ For example, you might have the following settings to assign the gimbal roll, pi
![Gimbal Actuator config](../../assets/config/actuators/qgc_actuators_gimbal.png)
The PWM values to use for the disarmed, maximum, center and minimum values can be determined in the same way as other servo, using the [Actuator Test sliders](../config/actuators.md#actuator-testing) to confirm that each slider moves the appropriate axis, and changing the values so that the gimbal is in the appropriate position at the disarmed, low, center and high position in the slider.
The PWM values to use for the disarmed, maximum and minimum values can be determined in the same way as other servo, using the [Actuator Test sliders](../config/actuators.md#actuator-testing) to confirm that each slider moves the appropriate axis, and changing the values so that the gimbal is in the appropriate position at the disarmed, low and high position in the slider.
The values may also be provided in gimbal documentation.
## Gimbal Control in Missions
+119 -1
View File
@@ -1 +1,119 @@
<Redirect to="../neural_networks/mc_neural_network_control" />
# Neural Networks
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
:::warning
This is an experimental module.
Use at your own risk.
:::
The Multicopter Neural Network (NN) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) is an example module that allows you to experiment with using a pre-trained neural network on PX4.
It might be used, for example, to experiment with controllers for non-traditional drone morphologies, computer vision tasks, and so on.
The module integrates a pre-trained neural network based on the [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md) module.
The module is trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md) multicopter frame.
While the controller is fairly robust, and might work on other platforms, we recommend [Training your own Network](#training-your-own-network) if you use a different vehicle.
Note that after training the network you will need to update and rebuild PX4.
TLFM is a mature inference library intended for use on embedded devices.
It has support for several architectures, so there is a high likelihood that you can build it for the board you want to use.
If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview).
This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works.
The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether.
If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/).
## Neural Network PX4 Firmware
:::warning
This module requires Ubuntu 24.04 or newer (it is not supported in Ubuntu 22.04).
:::
The module has been tested on a number of configurations, which can be build locally using the commands:
```sh
make px4_sitl_neural
```
```sh
make px4_fmu-v6c_neural
```
```sh
make mro_pixracerpro_neural
```
You can add the module to other board configurations by modifying their `default.px4board file` configuration to include these lines:
```sh
CONFIG_LIB_TFLM=y
CONFIG_MODULES_MC_NN_CONTROL=y
```
:::tip
The `mc_nn_control` module takes up roughly 50KB, and many of the `default.px4board file` are already close to filling all the flash on their boards. To make room for the neural control module you can remove the include statements for other modules, such as FW, rover, VTOL and UUV.
:::
## Example Module Overview
The example module replaces the entire controller structure as well as the control allocator, as shown in the diagram below:
![neural_control](../../assets/advanced/neural_control.png)
In the [controller diagram](../flight_stack/controller_diagrams.md) you can see the [uORB message](../middleware/uorb.md) flow.
We hook into this flow by subscribing to messages at particular points, using our neural network to calculate outputs, and then publishing them into the next point in the flow.
We also need to stop the module publishing the topic to be replaced, which is covered in [Neural Network Module: System Integration](nn_module_utilities.md)
### Input
The input can be changed to whatever you want.
Set up the input you want to use during training and then provide the same input in PX4.
In the Neural Control module the input is an array of 15 numbers, and consists of these values in this order:
- [3] Local position error. (goal position - current position)
- [6] The first 2 rows of a 3 dimensional rotation matrix.
- [3] Linear velocity
- [3] Angular velocity
All the input values are collected from uORB topics and transformed into the correct representation in the `PopulateInputTensor()` function.
PX4 uses the NED frame representation, while the Aerial Gym Simulator, in which the NN was trained, uses the ENU representation.
Therefore two rotation matrices are created in the function and all the inputs are transformed from the NED representation to the ENU one.
![ENU-NED](../../assets/advanced/ENU-NED.png)
ENU and NED are just rotation representations, the translational difference is only there so both can be seen in the same figure.
### 출력
The output consists of 4 values, the motor forces, one for each motor.
These are transformed in the `RescaleActions()` function.
This is done because PX4 expects normalized motor commands while the Aerial Gym Simulator uses physical values.
So the output from the network needs to be normalized before they can be sent to the motors in PX4.
The commands are published to the [ActuatorMotors](../msg_docs/ActuatorMotors.md) topic.
The publishing is handled in `PublishOutput(float* command_actions)` function.
:::tip
If the neural control mode is too aggressive or unresponsive the [MC_NN_THRST_COEF](../advanced_config/parameter_reference.md#MC_NN_THRST_COEF) parameter can be tuned.
Decrease it for more thrust.
:::
## Training your own Network
The network is currently trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md).
But the controller is somewhat robust, so it could work directly on other platforms, but performing system identification and training a new network is recommended.
Since the Aerial Gym Simulator is open-source you can download it and train your own networks as long as you have access to an NVIDIA GPU.
If you want to train a control network optimized for your platform you can follow the instructions in the [Aerial Gym Documentation](https://ntnu-arl.github.io/aerial_gym_simulator/9_sim2real/).
You should do one system identification flight for this and get an approximate inertia matrix for your platform.
On the `sys-id` flight you need ESC telemetry, you can read more about that in [DSHOT](../peripherals/dshot.md).
Then do the following steps:
- Do a hover flight
- Read of the logs what RPM is required for the drone to hover.
- Use the weight of each motor, length of the motor arms, total weight of the platform with battery to calculate an approximate inertia matrix for the platform.
- Insert these values into the Aerial Gym configuration and train your network.
- Convert the network as explained in [TFLM](tflm.md).
-4
View File
@@ -10,10 +10,6 @@ CAN it is designed to be democratic and uses differential signaling.
For this reason it is very robust even over longer cable lengths (on large vehicles), and avoids a single point of failure.
CAN also allows status feedback from peripherals and convenient firmware upgrades over the bus.
PX4 has the ability to track and log detailed information from CAN devices, including firmware versions, hardware versions, and serial numbers.
This enables unique identification and lifecycle tracking of hardware connected to the flight controller.
See [Asset Tracking](../debug/asset_tracking.md) for more information.
PX4 supports two software protocols for communicating with CAN devices:
- [DroneCAN](../dronecan/index.md): PX4 recommends this for most common setups.
+16 -12
View File
@@ -106,7 +106,7 @@ There are several other "battery related" failsafe mechanisms that may be config
| 설정 | 매개변수 | 설명 |
| -------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None (default), `1`: Warning, `3`: Return mode. |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None, `1`: Warning, `3`: Return mode (default). |
| <a id="COM_FLT_TIME_MAX"></a> Maximum flight time failsafe level | [COM_FLT_TIME_MAX](../advanced_config/parameter_reference.md#COM_FLT_TIME_MAX) | Maximum allowed flight time before Return mode will be engaged, in seconds. `-1`: Disabled (default). |
## Manual Control Loss Failsafe
@@ -121,32 +121,36 @@ PX4 and the receiver may also need to be configured in order to _detect RC loss_
![Safety - RC Loss (QGC)](../../assets/qgc/setup/safety/safety_rc_loss.png)
The QGCroundControl Safety UI allows you to set the [failsafe action](#failsafe-actions) and [manual control loss timeout](#COM_RC_LOSS_T).
Users that want to disable this failsafe in specific modes can do so using the parameter [COM_RCL_EXCEPT](#COM_RCL_EXCEPT).
The QGCroundControl Safety UI allows you to set the [failsafe action](#failsafe-actions) and [RC Loss timeout](#COM_RC_LOSS_T).
Users that want to disable the RC loss failsafe in specific automatic modes (mission, hold, offboard) can do so using the parameter [COM_RCL_EXCEPT](#COM_RCL_EXCEPT).
Additional (and underlying) parameter settings are shown below.
| 매개변수 | 설정 | 설명 |
| -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_RC_LOSS_T"></a>[COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Manual Control Loss Timeout | Time after last setpoint received from the selected manual control source after which manual control is considered lost. This must be kept short because the vehicle will continue to fly using the last known stick position until the timeout triggers. |
| <a id="COM_RC_LOSS_T"></a>[COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Manual Control Loss Timeout | Time after last setpoint received from the selected manual control source after which manual control is considered lost. This must be kept short because the vehicle will continue to fly using the old manual control setpoint until the timeout triggers. |
| <a id="COM_FAIL_ACT_T"></a>[COM_FAIL_ACT_T](../advanced_config/parameter_reference.md#COM_FAIL_ACT_T) | Failsafe Reaction Delay | Delay in seconds between failsafe condition being triggered (`COM_RC_LOSS_T`) and failsafe action (RTL, Land, Hold). In this state the vehicle waits in hold mode for the manual control source to reconnect. This might be set longer for long-range flights so that intermittent connection loss doesn't immediately invoke the failsafe. It can be to zero so that the failsafe triggers immediately. |
| <a id="NAV_RCL_ACT"></a>[NAV_RCL_ACT](../advanced_config/parameter_reference.md#NAV_RCL_ACT) | 안전장치 동작 | Disabled, Loiter, Return, Land, Disarm, Terminate. |
| <a id="COM_RCL_EXCEPT"></a>[COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | RC 손실 예외 | Set modes in which manual control loss is ignored. |
| <a id="COM_RCL_EXCEPT"></a>[COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | RC 손실 예외 | Set the modes in which manual control loss is ignored: Mission, Hold, Offboard. |
## 데이터 연결불량 안전장치
The Data Link Loss failsafe is triggered if the connection to the last MAVLink ground station like QGroundControl is lost.
Users that want to disable this failsafe in specific modes can do so using the parameter [COM_DLL_EXCEPT](#COM_DLL_EXCEPT).
The Data Link Loss failsafe is triggered if a telemetry link (connection to ground station) is lost.
![Safety - Data Link Loss (QGC)](../../assets/qgc/setup/safety/safety_data_link_loss.png)
설정에 관련된 기본 매개변수는 다음과 같습니다.
| 설정 | 매개변수 | 설명 |
| ----------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------- |
| 데이터 연결불량 시간 초과 | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | 데이터 연결이 끊어진 후 안전 장치가 동작하기 전까지의 시간입니다. |
| 안전장치 동작 | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Disabled, Hold mode, Return mode, Land mode, Disarm, Terminate. |
| <a id="COM_DLL_EXCEPT"></a>Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes in which data link loss is ignored. |
| 설정 | 매개변수 | 설명 |
| -------------- | --------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------- |
| 데이터 연결불량 시간 초과 | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | 데이터 연결이 끊어진 후 안전 장치가 동작하기 전까지의 시간입니다. |
| 안전장치 동작 | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Disabled, Hold mode, Return mode, Land mode, Disarm, Terminate. |
다음 설정도 가능하지만 QGC UI에 표시되지 않습니다.
| 설정 | 매개변수 | 설명 |
| ----------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- |
| <a id="COM_DLL_EXCEPT"></a>Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes where DL loss will not trigger a failsafe. |
## Geofence 안전장치
-68
View File
@@ -1,68 +0,0 @@
# Asset Tracking
<Badge type="tip" text="main (planned for: PX4 v1.18)" />
PX4 can track and log detailed information about external hardware devices connected to the flight controller.
This enables unique identification of vehicle parts throughout their operational lifetime using device IDs, serial numbers, and version information.
:::info
Asset tracking is currently implemented for [DroneCAN](../dronecan/index.md) devices only.
:::
## 개요
Asset tracking allows you to determine exactly which hardware is installed on a vehicle, providing serial number, version, and other information.
This makes it easier to track and maintain specific vehicle parts across multiple vehicles, to quickly see what versions you're running when debugging, and log component information for regulatory audits.
Asset tracking automatically collects and logs the following metadata from external devices:
- **Device identification**: Vendor name, model name, device type
- **Version information**: Firmware version, hardware version
- **Unique identifiers**: Serial number, device ID
- **Device capabilities**: ESC, GPS, magnetometer, barometer, etc.
This information is published via the [`device_information`](../msg_docs/DeviceInformation.md) uORB topic and logged to flight logs.
This enables fleet management, maintenance tracking, and troubleshooting.
## Viewing Device Information
### Real-Time Monitoring
You can view device information in real-time using the [MAVLink Shell](../debug/mavlink_shell.md) or console:
```sh
listener device_information
```
Example output for a CAN GPS module:
```plain
TOPIC: device_information
device_information
timestamp: 16258961403 (0.216525 seconds ago)
device_id: 8944643 (Type: 0x88, UAVCAN:0 (0x7C))
device_type: 5
vendor_name: "cubepilot"
model_name: "here4"
firmware_version: "1.14.3006590"
hardware_version: "4.19"
serial_number: "1c00410018513331"
```
Device information is published in a round-robin fashion for each detected device, at a rate of approximately 1 Hz.
### Multi-Capability Devices
Devices with multiple sensors (e.g., a CAN GPS/magnetometer combo module like the HERE4) register separate device information entries for each capability.
Each entry shares the same serial number and base metadata but has a different `device_id` corresponding to the specific sensor capability.
## 비행 로그 분석
Device information is automatically logged to flight logs.
You can extract it using [pyulog](../log/flight_log_analysis.md#pyulog), though note that fields like vendor name, model name, and serial number are stored as `char` arrays and require additional parsing.
## See Also
- [CAN (DroneCAN & Cyphal)](../can/index.md) — CAN bus configuration and setup
- [DroneCAN](../dronecan/index.md) — DroneCAN-specific documentation
- [Flight Log Analysis](../log/flight_log_analysis.md) — Flight log analysis
-112
View File
@@ -1,112 +0,0 @@
# ARK G5 RTK GPS
:::info
This GPS module is made in the USA and NDAA compliant.
:::
[ARK G5 RTK GPS](https://arkelectron.com/product/ark-g5-rtk-gps/) is a [DroneCAN](index.md) quad-band [RTK GPS](../gps_compass/rtk_gps.md).
The module incorporates the [Septentrio mosaic-G5 P3 Ultra-compact high-precision GPS/GNSS receiver module](https://www.u-blox.com/en/product/zed-x20p-module), magnetometer, barometer, IMU, and buzzer module.
![ARK G5 RTK GPS](../../assets/hardware/gps/ark/ark_g5_rtk_gps.png)
## 구매처
Order this module from:
- [ARK Electronics](https://arkelectron.com/product/ark-g5-rtk-gps/) (US)
## Hardware Specifications
- [DroneCAN](index.md) RTK GNSS, Magnetometer, Barometer, IMU, and Buzzer Module
- [Dronecan Firmware Updating](../dronecan/index.md#firmware-update)
- 센서
- [Septentrio mosaic-G5 P3 Ultra-compact high-precision GPS/GNSS receiver module](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3)
- All-band all constellation GNSS receiver
- All-in-view satellite tracking: multi-constellation, quad-band GNSS module receiver
- Full raw data with positioning measurements and Galileo HAS positioning service compatibility
- Best-in-class RTK cm-level positioning accuracy
- Advanced GNSS+ algorithms
- 20Hz update rate
- [ST IIS2MDC Magnetometer](https://www.st.com/en/mems-and-sensors/iis2mdc.html)
- [Bosch BMP390 Barometer](https://www.bosch-sensortec.com/products/environmental-sensors/pressure-sensors/bmp390/)
- [Invensense ICM-42688-P 6-Axis IMU](https://invensense.tdk.com/products/motion-tracking/6-axis/icm-42688-p/)
- STM32F412VGH6 MCU
- Safety Button
- 부저
- Two CAN Connectors (Pixhawk Connector Standard 4-pin JST GH)
- G5 "UART 2" Connector
- 4-pin JST GH
- TX, RX, PPS, GND
- G5 USB C
- Debug Connector (Pixhawk Connector Standard 6-pin JST SH)
- LED Indicators
- GPS Fix
- RTK Status
- RGB system status
- USA Built
- NDAA Compliant
- Power Requirements
- 5V
- 270mA
- 크기
- Without Antenna
- 48.0mm x 40.0mm x 15.4mm
- 13.0g
- With Antenna
- 48.0mm x 40.0mm x 51.0mm
- 43.5g
- Includes
- CAN Cable (Pixhawk Connector Standard 4-pin)
- Full-Frequency Helical GPS Antenna
## 하드웨어 설정
### 배선
The ARK G5 RTK GPS is connected to the CAN bus using a [Pixhawk connector standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) 4-pin JST GH cable.
For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
### 장착
The recommended mounting orientation is with the connectors on the board pointing towards the **back of vehicle**.
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during [PX4 Configuration](#px4-configuration).
## Firmware Setup
The Septentrio G5 module firmware can be updated using the Septentrio [RxTools](https://www.septentrio.com/en/products/gps-gnss-receiver-software/rxtools) application.
## Flight Controller Setup
### Enabling DroneCAN
In order to use the ARK G5 RTK GPS, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)).
단계는 다음과 같습니다:
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` or `3` and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
- Connect ARK G5 RTK GPS CAN to the Pixhawk CAN.
Once enabled, the module will be detected on boot.
There is also CAN built-in bus termination via [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM)
### PX4 설정
You need to set necessary [DroneCAN](index.md) parameters and define offsets if the sensor is not centred within the vehicle:
- 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 [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK G5 RTK GPS from the vehicle's centre of gravity.
## LED 신호의 의미
The GPS status lights are located to the right of the connectors:
- Blinking green is GPS fix
- Blinking blue is received corrections and RTK Float
- Solid blue is RTK Fixed
## See Also
- [ARK G5 RTK GPS Documentation](https://docs.arkelectron.com/gps/ark-g5-rtk-gps) (ARK Docs)
-150
View File
@@ -1,150 +0,0 @@
# ARK G5 RTK HEADING GPS
:::info
This GPS module is made in the USA and NDAA compliant.
:::
[ARK G5 RTK HEADING GPS](https://arkelectron.com/product/ark-g5-rtk-gps/) is a [DroneCAN](index.md) quad-band dual antenna [RTK GPS](../gps_compass/rtk_gps.md) that additionally provides vehicle yaw information from GPS.
The module incorporates the [Septentrio mosaic-G5 P3H Ultra-compact high-precision GPS/GNSS receiver module with heading capability](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H), magnetometer, barometer, IMU, and buzzer module.
![ARK G5 RTK HEADING GPS](../../assets/hardware/gps/ark/ark_g5_rtk_gps.png)
## 구매처
Order this module from:
- [ARK Electronics](https://arkelectron.com/product/ark-g5-rtk-heading-gps/) (US)
## Hardware Specifications
- [DroneCAN](index.md) RTK GNSS, Magnetometer, Barometer, IMU, and Buzzer Module
- [Dronecan Firmware Updating](../dronecan/index.md#firmware-update)
- 센서
- [Septentrio mosaic-G5 P3H Ultra-compact high-precision GPS/GNSS receiver module with heading capability](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H)
- All-band all constellation GNSS receiver
- All-in-view satellite tracking: multi-constellation, quad-band GNSS module receiver
- Full raw data with positioning measurements and Galileo HAS positioning service compatibility
- Best-in-class RTK cm-level positioning accuracy
- Advanced GNSS+ algorithms
- 20Hz update rate
- [ST IIS2MDC Magnetometer](https://www.st.com/en/mems-and-sensors/iis2mdc.html)
- [Bosch BMP390 Barometer](https://www.bosch-sensortec.com/products/environmental-sensors/pressure-sensors/bmp390/)
- [Invensense ICM-42688-P 6-Axis IMU](https://invensense.tdk.com/products/motion-tracking/6-axis/icm-42688-p/)
- STM32F412VGH6 MCU
- Safety Button
- 부저
- Two CAN Connectors (Pixhawk Connector Standard 4-pin JST GH)
- G5 "UART 2" Connector
- 4-pin JST GH
- TX, RX, PPS, GND
- G5 USB C
- Debug Connector (Pixhawk Connector Standard 6-pin JST SH)
- LED Indicators
- GPS Fix
- RTK Status
- RGB system status
- USA Built
- NDAA Compliant
- Power Requirements
- 5V
- 270mA
- 크기
- Without Antenna
- 48.0mm x 40.0mm x 15.4mm
- 13.0g
- With Antenna
- 48.0mm x 40.0mm x 51.0mm
- 43.5g
- Includes
- CAN Cable (Pixhawk Connector Standard 4-pin)
- Full-Frequency Helical GPS Antenna
## 하드웨어 설정
### 배선
The ARK G5 RTK HEADING GPS is connected to the CAN bus using a [Pixhawk connector standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) 4-pin JST GH cable.
For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
### 장착
The recommended mounting orientation is with the connectors on the board pointing towards the **back of vehicle**.
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during [PX4 configuration](#px4-configuration).
## Firmware Setup
The Septentrio G5 module firmware can be updated using the Septentrio [RxTools](https://www.septentrio.com/en/products/gps-gnss-receiver-software/rxtools) application.
## Flight Controller Setup
### Enabling DroneCAN
In order to use the ARK G5 RTK HEADING GPS, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)).
단계는 다음과 같습니다:
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` or `3` and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
- Connect ARK G5 RTK HEADING GPS CAN to the Pixhawk CAN.
Once enabled, the module will be detected on boot.
There is also CAN built-in bus termination via [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM)
### PX4 설정
You need to set necessary [DroneCAN](index.md) parameters and define offsets if the sensor is not centred within the vehicle:
- 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).
- 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 [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK G5 RTK HEADING GPS from the vehicle's centre of gravity.
### Parameter references
This GPS is using ARK's private driver, the prameters below only exist on the firmware we ship the GPS with. You can set these params either in QGC or using the DroneCAN GUI Tool.
#### SEP_OFFS_YAW (float)
Heading offset angle for dual antenna GPS setups that support heading estimation.
Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the Rover/ANT2 antenna is in front.
The offset angle increases clockwise.
Set this to 90 if the ANT2 antenna is placed on the right side of the vehicle and the Moving Base/MAIN antenna is on the left side.
- Default: 0
- Min: -360
- Max: 360
- Unit: degree
#### SEP_OFFS_PITCH (float)
Vertical offsets can be compensated for by adjusting the Pitch offset.
Note that this can be interpreted as the "roll" angle in case the antennas are aligned along the perpendicular axis. This occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame. Since pitch is defined as the right-handed rotation about the vehicle Y axis, a situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch.
- Default: 0
- Min: -90
- Max: 90
- Unit: degree
#### SEP_OUT_RATE (enum)
Configures the output rate for GNSS data messages.
- -1: OnChange (Default)
- 50: 50 ms
- 100: 100 ms
- 200: 200 ms
- 500: 500 ms
## LED 신호의 의미
The GPS status lights are located to the right of the connectors:
- Blinking green is GPS fix
- Blinking blue is received corrections and RTK Float
- Solid blue is RTK Fixed
## See Also
- [ARK G5 RTK HEADING GPS Documentation](https://docs.arkelectron.com/gps/ark-g5-rtk-gps) (ARK Docs)
-2
View File
@@ -27,8 +27,6 @@ Connecting peripherals over DroneCAN has many benefits:
- Wiring is less complicated as you can have a single bus for connecting all your ESCs and other DroneCAN peripherals.
- Setup is easier as you configure ESC numbering by manually spinning each motor.
- It allows users to configure and update the firmware of all CAN-connected devices centrally through PX4.
- PX4 automatically tracks device information (vendor, model, versions, serial numbers) for maintenance and fleet management.
See [Asset Tracking](../debug/asset_tracking.md).
## 지원 하드웨어
+1 -1
View File
@@ -1,6 +1,6 @@
# Gain compression
<Badge type="tip" text="PX4 v1.17" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
Automatic gain compression reduces the gains of the angular-rate PID whenever oscillations are detected.
It monitors the angular-rate controller output through a band-pass filter to identify these oscillations.
+1 -1
View File
@@ -1,6 +1,6 @@
# MicoAir743-Lite
<Badge type="tip" text="PX4 v1.17" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
:::warning
PX4 does not manufacture this (or any) autopilot.
+1 -1
View File
@@ -1,6 +1,6 @@
# RadiolinkPIX6 Flight Controller
<Badge type="tip" text="PX4 v1.17" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
:::warning
PX4 does not manufacture this (or any) autopilot.
+3 -3
View File
@@ -1,6 +1,6 @@
# AP-H743-R1 Flight Controller
# AP-H743-R1
<Badge type="tip" text="PX4 v1.17" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
:::warning
PX4 does not manufacture this (or any) autopilot.
@@ -25,7 +25,7 @@ It brings you ultimate performance, stability, and reliability in every aspect.
- 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM
- 내장 센서 :
- Accel/Gyro: ICM-42688-P\*2(Version1), BMI270\*2(Version2)
- Mag: QMC5883P
- 자력계: QMC5883P
- Barometer: DPS310(Version1),SPL06(Version2)
### 인터페이스
+9 -68
View File
@@ -2,14 +2,11 @@
<img src="../../assets/site/position_fixed.svg" title="Position fix required (e.g. GPS)" width="30px" />
The _Hold_ flight mode causes the vehicle to loiter around its current GPS position and maintain its current altitude.
The mode supports a [number of distinct loiter modes](#loiter-modes), which are triggered using different QGC controls or MAVLink commands.
These allow loitering with circular and figure 8 flight paths.
The _Hold_ flight mode causes the vehicle to loiter (circle) around its current GPS position and maintain its current altitude.
:::tip
_Hold mode_ can be used to pause a mission or to help you regain control of a vehicle in an emergency.
It is usually activated with a pre-programmed RC switch.
It is usually activated with a pre-programmed switch.
:::
::: info
@@ -27,80 +24,24 @@ It is usually activated with a pre-programmed RC switch.
:::
## Loiter modes
## Technical Summary
### Default Loiter
The aircraft circles around the GPS hold position at the current altitude.
The vehicle will first ascend to [NAV_MIN_LTR_ALT](#NAV_MIN_LTR_ALT) if the mode is engaged below this altitude.
The aircraft circles around the position at which the mode was triggered and maintain its current altitude.
The loiter radius is set by the parameter [NAV_LOITER_RAD](#NAV_LOITER_RAD).
Note that if the vehicle altitude is below [NAV_MIN_LTR_ALT](#NAV_MIN_LTR_ALT), it will ascend to that minimum altitude before circling.
RC stick movement is ignored.
The default loiter mode is entered when you switch to Hold mode without explicitly specifying any loiter behaviour.
For example, if you switch to Hold mode using an RC switch, select **Hold** on the QGC flight mode selector, or activate the mode using the MAVLink [MAV_CMD_DO_SET_MODE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_MODE) command.
### Orbit Loiter Mode
<Badge type="tip" text="PX4 v1.12" />
The aircraft travels towards a _specified_ orbit center position, then circles it with a given direction and radius.
This behaviour can be accessed in QGroundControl by clicking on the map in Fly view, selecting **Orbit at Location**, and configuring the radius.
The behavior can be triggered using the MAVLink [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) command.
Note that PX4 respects the specified centre point (`param5`, `param6`, `param7`), and the radius and direction (`param1`).
PX4 ignores `param3` (Yaw behaviour) and `param4` (Orbits).
The value of `param2` (velocity) is also ignored, but the speed can be controlled using the [MAV_CMD_DO_CHANGE_SPEED](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED) command (constrained between `FW_AIRSPD_MAX` and `FW_AIRSPD_MIN`).
PX4 outputs orbit status using the [ORBIT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#ORBIT_EXECUTION_STATUS) message.
### Figure 8 Loiter Mode
<Badge type="tip" text="PX4 v1.15" /> <Badge type="warning" text="Experimental" />
The aircraft flys towards the closest point on a specified figure 8 path and then follows it.
The path is defined by the figure 8 centre position, orientation, and radius of two circles.
The feature is experimental, and is not present in PX4 firmware by default (on most flight controller boards).
It can be included by setting the `CONFIG_FIGURE_OF_EIGHT` key in the [PX4 board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) for your board and rebuilding.
For example, this is enabled on the [default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/auterion/fmu-v6s/default.px4board#L46) file for the `auterion/fmu-v6s` board.
The behavior can be triggered using the MAVLink [MAV_CMD_DO_FIGURE_EIGHT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_FIGURE_EIGHT) command (PX4 respects all the parameters).
PX4 outputs the figure 8 status using the [FIGURE_EIGHT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#FIGURE_EIGHT_EXECUTION_STATUS) message.
:::info
Figure 8 loitering is not currently supported by QGC: [QGC#12778: Need Support Figure of eight (8 figure) loitering by QGC](https://github.com/mavlink/qgroundcontrol/issues/12778).
:::
Figure 8 loitering is also available in the simulator.
You can test it in [Gazebo](../sim_gazebo_gz/index.md) using a fixed wing frame:
```sh
make px4_sitl gz_rc_cessna
```
## 매개변수
### 매개변수
Hold mode behaviour can be configured using the parameters below.
| 매개변수 | 설명 |
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------ |
| <a id="NAV_LOITER_RAD"></a>[NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The radius of the loiter circle. |
| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The radius of the loiter circle. |
| <a id="NAV_MIN_LTR_ALT"></a>[NAV_MIN_LTR_ALT](../advanced_config/parameter_reference.md#NAV_MIN_LTR_ALT) | Minimum height for loiter mode (vehicle will ascend to this altitude if mode is engaged at a lower altitude). |
## MAVLink Commands
The following commands are relevant to this mode:
- [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) - Switch to Hold mode and start the specified [Orbit loiter](#orbit-loiter-mode).
Params 2 (velocity), 3 (yaw), 4 (orbits) are ignored.
[ORBIT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#ORBIT_EXECUTION_STATUS) is emitted.
- [MAV_CMD_DO_FIGURE_EIGHT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_FIGURE_EIGHT) - Switch to Hold mode and start the specified [Figure 8 loiter](#figure-8-loiter-mode).
All params are respected.
[FIGURE_EIGHT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#FIGURE_EIGHT_EXECUTION_STATUS) is emitted.
Note, other commands may be supported.
## See Also
- [Hold Mode (MC)](../flight_modes_mc/hold.md)
[Hold Mode (MC)](../flight_modes_mc/hold.md)
<!-- this maps to AUTO_LOITER in flight mode state machine -->
+2 -2
View File
@@ -49,8 +49,8 @@ If the local position is invalid or becomes invalid while executing the takeoff,
::: info
- Takeoff towards a target position was added in <Badge type="tip" text="PX4 v1.17" />.
- Holding wings level and ascending to clearance attitude when local position is invalid during takeoff was added in <Badge type="tip" text="PX4 v1.17" />.
- Takeoff towards a target position was added in <Badge type="tip" text="main (planned for: PX4 v1.17)" />.
- Holding wings level and ascending to clearance attitude when local position is invalid during takeoff was added in <Badge type="tip" text="main (planned for: PX4 v1.17)" />.
- QGroundControl does not support `MAV_CMD_NAV_TAKEOFF` (at time of writing).
:::
+40 -48
View File
@@ -21,59 +21,52 @@ PX4 supports the [u-blox M8P](https://www.u-blox.com/en/product/neo-m8p), [u-blo
The table indicates devices that also output yaw, and that can provide yaw when two on-vehicle units are used.
It also highlights devices that connect via the CAN bus, and those which support PPK (Post-Processing Kinematic).
| 장치 | GPS | 나침반 | [DroneCAN] | [GPS Yaw] | PPK |
| :------------------------------------------------------------------------------------------------------------------- | :------------------: | :------: | :--------: | :---------------------------------: | :-: |
| [ARK G5 RTK GPS](../dronecan/ark_g5_rtk_gps.md) | [mosaic-G5 P3] | IIS2MDC | ✓ | | |
| [ARK G5 RTK HEADING GPS](../dronecan/ark_g5_rtk_heading_gps.md) | [mosaic-G5 P3H] | IIS2MDC | ✓ | [Heading Capability][mosaic-G5 P3H] | |
| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | | [Dual F9P] | |
| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | | |
| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | ✓ | [Septentrio Dual Antenna] | |
| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | IIS2MDC | | | |
| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | | | | |
| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P] | |
| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P] | |
| [CUAV C-RTK2 PPK/RTK GNSS](../gps_compass/rtk_gps_cuav_c-rtk.md) | F9P | RM3100 | | | |
| [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) | M8P | HMC5983 | | | |
| [CubePilot Here3 CAN GNSS GPS (M8N)](https://www.cubepilot.org/#/here/here3) | M8P | ICM20948 | ✓ | | |
| [Drotek SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | RM3100 | | [Dual F9P] | |
| [DATAGNSS NANO HRTK Receiver](../gps_compass/rtk_gps_datagnss_nano_hrtk.md) | [D10P] | IST8310 | | | |
| [DATAGNSS GEM1305 RTK Receiver](../gps_compass/rtk_gps_gem1305.md) | TAU951M | IST8310 | | | |
| [Femtones MINI2 Receiver](../gps_compass/rtk_gps_fem_mini2.md) | FB672, FB6A0 | ✓ | | | |
| [Freefly RTK GPS](../gps_compass/rtk_gps_freefly.md) | F9P | IST8310 | | | |
| [Holybro H-RTK ZED-F9P RTK Rover (DroneCAN variant)](../dronecan/holybro_h_rtk_zed_f9p_gps.md) | F9P | RM3100 | | [Dual F9P] | |
| [Holybro H-RTK ZED-F9P RTK Rover](https://holybro.com/collections/h-rtk-gps/products/h-rtk-zed-f9p-rover) | F9P | RM3100 | | [Dual F9P] | |
| [Holybro H-RTK F9P Ultralight](https://holybro.com/products/h-rtk-f9p-ultralight) | F9P | IST8310 | | [Dual F9P] | |
| [Holybro H-RTK F9P Helical or Base](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | [Dual F9P] | |
| [Holybro DroneCAN H-RTK F9P Helical](https://holybro.com/products/dronecan-h-rtk-f9p-helical) | F9P | BMM150 | | [Dual F9P] | |
| [Holybro H-RTK F9P Rover Lite](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | | |
| [Holybro DroneCAN H-RTK F9P Rover](https://holybro.com/products/dronecan-h-rtk-f9p-rover) | F9P | BMM150 | | [Dual F9P] | |
| [Holybro H-RTK M8P GNSS](../gps_compass/rtk_gps_holybro_h-rtk-m8p.md) | M8P | IST8310 | | | |
| [Holybro H-RTK Unicore UM982 GPS](../gps_compass/rtk_gps_holybro_unicore_um982.md) | UM982 | IST8310 | | [Unicore Dual Antenna] | |
| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | |
| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | |
| [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | ✓ | | [Dual F9P] | |
| [Navisys L1/L2 ZED-F9P RTK - Base only](https://www.navisys.com.tw/productdetail?name=GR901&class=RTK) | F9P | | | | |
| [RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | |
| [RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | |
| [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | [Septentrio Dual Antenna] | |
| [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | ✓ | | [Septentrio Dual Antenna] | |
| [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | [Dual F9P] | |
| [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | [Dual F9P] | |
| [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | ✓ | |
| 장치 | GPS | 나침반 | [DroneCAN](../dronecan/index.md) | [GPS Yaw](#configuring-gps-as-yaw-heading-source) | PPK |
| :------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------: | :------: | :------------------------------: | :-----------------------------------------------: | :-: |
| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | ✓ | [Dual F9P][DualF9P] | |
| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | | |
| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | | [Septentrio Dual Antenna][SeptDualAnt] | |
| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | BMP390 | ✓ | | |
| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | | | | |
| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P][DualF9P] | |
| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P][DualF9P] | |
| [CUAV C-RTK2 PPK/RTK GNSS](../gps_compass/rtk_gps_cuav_c-rtk.md) | F9P | RM3100 | | | |
| [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) | M8P | HMC5983 | | | |
| [CubePilot Here3 CAN GNSS GPS (M8N)](https://www.cubepilot.org/#/here/here3) | M8P | ICM20948 | ✓ | | |
| [Drotek SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | RM3100 | | [Dual F9P][DualF9P] | |
| [DATAGNSS NANO HRTK Receiver](../gps_compass/rtk_gps_datagnss_nano_hrtk.md) | [D10P](https://docs.datagnss.com/gnss/gnss_module/D10P_RTK) | IST8310 | | | |
| [DATAGNSS GEM1305 RTK Receiver](../gps_compass/rtk_gps_gem1305.md) | TAU951M | IST8310 | | | |
| [Femtones MINI2 Receiver](../gps_compass/rtk_gps_fem_mini2.md) | FB672, FB6A0 | | | | |
| [Freefly RTK GPS](../gps_compass/rtk_gps_freefly.md) | F9P | IST8310 | | | |
| [Holybro H-RTK ZED-F9P RTK Rover (DroneCAN variant)](../dronecan/holybro_h_rtk_zed_f9p_gps.md) | F9P | RM3100 | ✓ | [Dual F9P][DualF9P] | |
| [Holybro H-RTK ZED-F9P RTK Rover](https://holybro.com/collections/h-rtk-gps/products/h-rtk-zed-f9p-rover) | F9P | RM3100 | | [Dual F9P][DualF9P] | |
| [Holybro H-RTK F9P Ultralight](https://holybro.com/products/h-rtk-f9p-ultralight) | F9P | IST8310 | | [Dual F9P][DualF9P] | |
| [Holybro H-RTK F9P Helical or Base](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | [Dual F9P][DualF9P] | |
| [Holybro DroneCAN H-RTK F9P Helical](https://holybro.com/products/dronecan-h-rtk-f9p-helical) | F9P | BMM150 | ✓ | [Dual F9P][DualF9P] | |
| [Holybro H-RTK F9P Rover Lite](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | | |
| [Holybro DroneCAN H-RTK F9P Rover](https://holybro.com/products/dronecan-h-rtk-f9p-rover) | F9P | BMM150 | | [Dual F9P][DualF9P] | |
| [Holybro H-RTK M8P GNSS](../gps_compass/rtk_gps_holybro_h-rtk-m8p.md) | M8P | IST8310 | | | |
| [Holybro H-RTK Unicore UM982 GPS](../gps_compass/rtk_gps_holybro_unicore_um982.md) | UM982 | IST8310 | | [Unicore Dual Antenna][UnicoreDualAnt] | |
| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | |
| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | |
| [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | | | [Dual F9P][DualF9P] | |
| [Navisys L1/L2 ZED-F9P RTK - Base only](https://www.navisys.com.tw/productdetail?name=GR901&class=RTK) | F9P | | | | |
| [RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | |
| [RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | |
| [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | [Septentrio Dual Antenna][SeptDualAnt] | |
| [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | | | [Septentrio Dual Antenna][SeptDualAnt] | ✓ |
| [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | [Dual F9P][DualF9P] | |
| [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | [Dual F9P][DualF9P] | |
| [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | | |
<!-- links used in above table -->
[RaccnLabL1L2ZED-F9P ext_ant]: https://docs.raccoonlab.co/guide/gps_mag_baro/gnss_external_antenna_f9p_v320.html
[RaccoonLab L1/L2 ZED-F9P]: https://docs.raccoonlab.co/guide/gps_mag_baro/gps_l1_l2_zed_f9p.html
[Dual F9P]: ../gps_compass/u-blox_f9p_heading.md
[Septentrio Dual Antenna]: ../gps_compass/septentrio.md#gnss-based-heading
[Unicore Dual Antenna]: ../gps_compass/rtk_gps_holybro_unicore_um982.md#enable-gps-heading-yaw
[DualF9P]: ../gps_compass/u-blox_f9p_heading.md
[SeptDualAnt]: ../gps_compass/septentrio.md#gnss-based-heading
[UnicoreDualAnt]: ../gps_compass/rtk_gps_holybro_unicore_um982.md#enable-gps-heading-yaw
[DATAGNSS GEM1305 RTK]: ../gps_compass/rtk_gps_gem1305.md
[DroneCAN]: ../dronecan/index.md
[GPS Yaw]: #configuring-gps-as-yaw-heading-source
[mosaic-G5 P3]: https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3
[mosaic-G5 P3H]: https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H
[D10P]: https://docs.datagnss.com/gnss/gnss_module/D10P_RTK
참고:
@@ -153,7 +146,6 @@ RTK GPS 연결은 기본적으로 플러그앤플레이입니다.
![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png)
4. Survey-in이 완료되면 :
- The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle:
![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png)
+2 -4
View File
@@ -332,11 +332,9 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi
- [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT): Bridge time synchronization enable.
The uXRCE-DDS client module can synchronize the timestamp of the messages exchanged over the bridge.
This is the default configuration. In certain situations, for example during [simulations](../ros2/user_guide.md#ros-gazebo-and-px4-time-synchronization), this feature may be disabled.
- [UXRCE_DDS_NS_IDX](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) <Badge type="tip" text="PX4 v1.17" />: Index-based namespace definition.
- <Badge type="tip" text="PX4 v1.17" /> [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX): Index-based namespace definition
Setting this parameter to any value other than `-1` creates a namespace with the prefix `uav_` and the specified value, e.g. `uav_0`, `uav_1`, etc.
See [namespace](#customizing-the-namespace) for methods to define richer or arbitrary namespaces.
- [`UXRCE_DDS_FLCTRL`](../advanced_config/parameter_reference.md#UXRCE_DDS_FLCTRL) <Badge type="tip" text="PX4 main" />: Serial port hardware flow control enable.
To use hardware flow control, a custom MicroXRCE Agent needs to be adopted. Please refer to [this PR](https://github.com/eProsima/Micro-XRCE-DDS-Agent/pull/407) for the required changes, cherry-pick them on top of the [agent version](#build-run-within-ros-2-workspace) you need to use and then run the agent with the additional `--flow-control` option.
:::info
Many ports are already have a default configuration.
@@ -441,7 +439,7 @@ will generate topics under the namespaces:
:::
- A simple index-based namespace can be applied by setting the parameter [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) <Badge type="tip" text="PX4 v1.17" /> to a value between 0 and 9999.
- A simple index-based namespace can be applied by setting the parameter [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to a value between 0 and 9999.
This will generate a namespace such as `/uav_0`, `/uav_1`, and so on.
This technique is ideal if vehicles must be persistently associated with namespaces because their clients are automatically started through PX4.
-21
View File
@@ -1,21 +0,0 @@
# Neural Network Control
PX4 supports the following mechanisms for using neural networks for multirotor control:
- [MC Neural Networks Control](../neural_networks/mc_neural_network_control.md)<Badge type="warning" text="Experimental" /> — A generic neural network module that you can modify to use different underlying neural network and training models and compile into the firmware.
- [RAPTOR: A Neural Network Module for Adaptive Quadrotor Control](../neural_networks/raptor.md)<Badge type="warning" text="Experimental" /> — An adaptive RL NN module that works well with different Quad configurations without additional training.
Generally you will select the former if you wish to experiment with custom neural network architectures and train them using PyTorch or TensorFlow, and the latter if you want to use a pre-trained neural-network controller that works out-of-the-box (without training for your particular platform) or if you train your own policies using [RLtools](https://rl.tools).
Note that both modules are experimental and provided for experimentation.
The table below provides more detail on the differences.
| Use Case | [`mc_raptor`](../neural_networks/raptor.md) | [`mc_nn_control`](../neural_networks/mc_neural_network_control.md) |
| ---------------------------------------------------------------- | ------------------------------------------- | ------------------------------------------------------------------ |
| Pre-trained policy that adapts to any quadrotor without training | ✓ RAPTOR | ✘ |
| Train policy in PyTorch/TF | ✘ | ✓ TF Lite |
| Train policy in RLtools | ✓ | ✘ |
| Use manual control (remote) with NN policy | ✘ GPS/MoCap | ✓ Manual attitude commands |
| Load policy checkpoints from SD card | ✓ Upload via MAVLink FTP | ✘ Compiled into firmware |
| Offboard setpoints | ✓ MAVLink | ✘ |
| Internal Trajectory Generator | ✓ (Position, Lissajous) | ✘ |
@@ -1,119 +0,0 @@
# MC Neural Networks Control
<Badge type="tip" text="PX4 v1.17" /> <Badge type="warning" text="Experimental" />
:::warning
This is an experimental module.
Use at your own risk.
:::
The Multicopter Neural Network (NN) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) is an example module that allows you to experiment with using a pre-trained neural network on PX4.
It might be used, for example, to experiment with controllers for non-traditional drone morphologies, computer vision tasks, and so on.
The module integrates a pre-trained neural network based on the [TensorFlow Lite Micro (TFLM)](./tflm.md) module.
The module is trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md) multicopter frame.
While the controller is fairly robust, and might work on other platforms, we recommend [Training your own Network](#training-your-own-network) if you use a different vehicle.
Note that after training the network you will need to update and rebuild PX4.
TLFM is a mature inference library intended for use on embedded devices.
It has support for several architectures, so there is a high likelihood that you can build it for the board you want to use.
If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview).
This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works.
The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether.
If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/).
## Neural Network PX4 Firmware
:::warning
This module requires Ubuntu 24.04 or newer (it is not supported in Ubuntu 22.04).
:::
The module has been tested on a number of configurations, which can be build locally using the commands:
```sh
make px4_sitl_neural
```
```sh
make px4_fmu-v6c_neural
```
```sh
make mro_pixracerpro_neural
```
You can add the module to other board configurations by modifying their `default.px4board file` configuration to include these lines:
```sh
CONFIG_LIB_TFLM=y
CONFIG_MODULES_MC_NN_CONTROL=y
```
:::tip
The `mc_nn_control` module takes up roughly 50KB, and many of the `default.px4board file` are already close to filling all the flash on their boards. To make room for the neural control module you can remove the include statements for other modules, such as FW, rover, VTOL and UUV.
:::
## Example Module Overview
The example module replaces the entire controller structure as well as the control allocator, as shown in the diagram below:
![neural_control](../../assets/advanced/neural_control.png)
In the [controller diagram](../flight_stack/controller_diagrams.md) you can see the [uORB message](../middleware/uorb.md) flow.
We hook into this flow by subscribing to messages at particular points, using our neural network to calculate outputs, and then publishing them into the next point in the flow.
We also need to stop the module publishing the topic to be replaced, which is covered in [Neural Network Module: System Integration](nn_module_utilities.md)
### Input
The input can be changed to whatever you want.
Set up the input you want to use during training and then provide the same input in PX4.
In the Neural Control module the input is an array of 15 numbers, and consists of these values in this order:
- [3] Local position error. (goal position - current position)
- [6] The first 2 rows of a 3 dimensional rotation matrix.
- [3] Linear velocity
- [3] Angular velocity
All the input values are collected from uORB topics and transformed into the correct representation in the `PopulateInputTensor()` function.
PX4 uses the NED frame representation, while the Aerial Gym Simulator, in which the NN was trained, uses the ENU representation.
Therefore two rotation matrices are created in the function and all the inputs are transformed from the NED representation to the ENU one.
![ENU-NED](../../assets/advanced/ENU-NED.png)
ENU and NED are just rotation representations, the translational difference is only there so both can be seen in the same figure.
### 출력
The output consists of 4 values, the motor forces, one for each motor.
These are transformed in the `RescaleActions()` function.
This is done because PX4 expects normalized motor commands while the Aerial Gym Simulator uses physical values.
So the output from the network needs to be normalized before they can be sent to the motors in PX4.
The commands are published to the [ActuatorMotors](../msg_docs/ActuatorMotors.md) topic.
The publishing is handled in `PublishOutput(float* command_actions)` function.
:::tip
If the neural control mode is too aggressive or unresponsive the [MC_NN_THRST_COEF](../advanced_config/parameter_reference.md#MC_NN_THRST_COEF) parameter can be tuned.
Decrease it for more thrust.
:::
## Training your own Network
The network is currently trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md).
But the controller is somewhat robust, so it could work directly on other platforms, but performing system identification and training a new network is recommended.
Since the Aerial Gym Simulator is open-source you can download it and train your own networks as long as you have access to an NVIDIA GPU.
If you want to train a control network optimized for your platform you can follow the instructions in the [Aerial Gym Documentation](https://ntnu-arl.github.io/aerial_gym_simulator/9_sim2real/).
You should do one system identification flight for this and get an approximate inertia matrix for your platform.
On the `sys-id` flight you need ESC telemetry, you can read more about that in [DSHOT](../peripherals/dshot.md).
Then do the following steps:
- Do a hover flight
- Read of the logs what RPM is required for the drone to hover.
- Use the weight of each motor, length of the motor arms, total weight of the platform with battery to calculate an approximate inertia matrix for the platform.
- Insert these values into the Aerial Gym configuration and train your network.
- Convert the network as explained in [TFLM](tflm.md).
@@ -1,86 +0,0 @@
# 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)](./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) message's 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
```
-221
View File
@@ -1,221 +0,0 @@
# RAPTOR: A Neural Network Module for Adaptive Quadrotor Control
<Badge type="tip" text="main (planned for PX4 v1.18)" /> <Badge type="info" text="Multicopter" /> <Badge type="warning" text="Experimental" />
:::warning
This is an experimental module.
Use at your own risk.
:::
RAPTOR is a tiny reinforcement-learning based neural network module for quadrotor control that can be used to control a wide variety of quadrotors without retuning.
This topic provides an overview of the fundamental concepts, and explains how you can use the module in simulation and real hardware.
## 개요
![Visual Abstract](../../assets/advanced/neural_networks/raptor/visual_abstract.jpg)
RAPTOR is an adaptive policy for end-to-end quadrotor control.
It is motivated by the human ability to adapt learned behaviours to similar situations.
For example, while humans may initially require many hours of driving experience to be able to smoothly control the car and blend into traffic, when faced with a new vehicle they do not need to re-learn how to drive — they only need to experience a few rough braking/acceleration/steering responses to adjust their previously learned behavior.
Reinforcement Learning (RL) is a machine learning technique that uses trial and error to learn decision making/control behaviors, which is similar to the way that humans learn to drive.
RL is interesting for controlling robots (and particularly UAVs) because it overcomes some fundamental limitations of classic, modular control architectures (information loss at module boundaries, requirement for expert tuning, etc).
RL has been very successful in [high-performance quadrotor flight](https://doi.org/10.1038/s41586-023-06419-4), but previous designs have not been particularly adaptable to new frames and vehicle types.
RAPTOR fills this gap and demonstrates a single, tiny neural-network control policy that can control a wide variety of quadrotors (tested on real quadrotors from 32 g to 2.4 kg).
For more details please refer to this video:
<lite-youtube videoid="hVzdWRFTX3k" title="RAPTOR: A Foundation Policy for Quadrotor Control"/>
The method we developed for training the RAPTOR policy is called Meta-Imitation Learning:
![Diagram showing the Method Overview](../../assets/advanced/neural_networks/raptor/method.jpg)
You can torture test the RAPTOR policy in your browser at [https://raptor.rl.tools](https://raptor.rl.tools) or in the embedded app here:
<iframe src="https://rl-tools.github.io/raptor.rl.tools?raptor=false" width="100%" height="1000" style="border: none;"></iframe>
For more information please refer to the paper at [https://arxiv.org/abs/2509.11481](https://arxiv.org/abs/2509.11481).
## 구조
The RAPTOR control policy is an end-to-end policy that takes position, orientation, linear velocity and angular velocity as inputs and outputs motor commands (`actuator_motors`).
To integrate it into PX4 we use the external mode registration facilities in PX4 (which also works well for internal modes as demonstrated in `mc_nn_control`).
Because of this architecture the `mc_raptor` module is completely decoupled from all other PX4 logic.
By default, the RAPTOR module expects setpoints via `trajectory_setpoint` messages.
If no `trajectory_setpoint` messages are received or if no `trajectory_setpoint` is received within 200 ms, the current position and orientation (with zero velocity) is used as the setpoint.
Since feeding setpoints reliably via telemetry is still a challenge, we also implement a simple option to generate internal reference trajectories (controlled through the `MC_RAPTOR_INTREF` parameter) for demonstration and benchmarking purposes.
## 특징
- Tiny neural network (just 2084 parameters) => minimal CPU usage
- Easily maintainable
- Simple CMake setup
- Self-contained (no interference with other modules)
- Single, simple and well-maintained dependency (RLtools)
- Loading neural network parameters from SD card
- Minimal flash usage (for possible inclusion into default build configurations)
- Easy development: Train new neural network and just upload it via MAVLink FTP without requiring to re-flash the firmware
- Tested on 10+ different real platforms (including flexible frames, brushed motors)
- Actively developed and maintained
## 사용법
### SITL
Build PX4 SITL with Raptor, disable QGC requirement, and adjust the `IMU_GYRO_RATEMAX` to match the simulation IMU rate
```sh
make px4_sitl_raptor gz_x500
param set NAV_DLL_ACT 0
param set COM_DISARM_LAND -1 # When taking off in offboard the landing detector can cause mid-air disarms
param set IMU_GYRO_RATEMAX 250 # Just for SITL. Tested with IMU_GYRO_RATEMAX=400 on real FCUs
param set MC_RAPTOR_ENABLE 1 # Enable the mc_raptor module
param save
```
Upload the RAPTOR checkpoint to the "SD card": Separate terminal
```bash
mavproxy.py --master udp:127.0.0.1:14540
ftp mkdir /raptor # for the real FMU use: /fs/microsd/raptor
ftp put src/modules/mc_raptor/blob/policy.tar /raptor/policy.tar
```
Restart (<kbd>Ctrl+C</kbd>)
```sh
make px4_sitl_raptor gz_x500
commander takeoff
commander status
```
Note the external mode ID of `RAPTOR` in the status report
```sh
commander mode ext{RAPTOR_MODE_ID}
```
#### Internal Reference Trajectory Generation
In our experience, feeding the `trajectory_setpoint` via MAVLink (even via WiFi telemetry) is unreliable.
But we do not want to constrain this module to only platforms that have a companion board.
For this reason we have integrated a simple internal reference trajectory generator for testing and benchmarking purposes.
It supports position (constant position and yaw setpoint) as well as configurable [Lissajous trajectories](https://en.wikipedia.org/wiki/Lissajous_curve).
The Lissajous generator can, for example, generate smooth figure-eight trajectories that contain interesting accelerations for benchmarking and testing purposes.
Please refer to the embedded configurator later in this section to explore the Lissajous parameters and view the resulting trajectories.
To use the internal reference generator, select the mode: `0`: Off/activation position tracking, `1`: Lissajous
```sh
param set MC_RAPTOR_INTREF 1
```
Restart (ctrl+c)
```sh
commander takeoff
commander mode ext{RAPTOR_MODE_ID}
mc_raptor intref lissajous 0.5 1 0 2 1 1 10 3
```
The trajectory is relative to the position and yaw of the vehicle at the point where the RAPTOR mode is activated (or the position and yaw where the parameters are changed if it is already activated).
You can adjust the parameters of the trajectory with the following tool.
Make sure to copy the generated CLI string at the end:
<iframe src="https://rl-tools.github.io/mc-raptor-trajectory-tool" width="100%" height="1700" style="border: none;"></iframe>
### Real-World
#### 설정
The `mc_raptor` module has been mostly tested with the Holybro X500 V2 but it should also work out-of-the-box with other platforms (see the [Other Platforms](#other-platforms) section).
```sh
make px4_fmu-v6c_raptor upload
```
We recommend initially testing the RAPTOR mode using a dead man's switch.
For this we configure the mode selection to be connected to a push button or a switch with a spring that automatically switches back.
In the default position we configure e.g. `Stabilized Mode` and in the pressed configuration we select `External Mode 1` (since the name of the external mode is only transmitted at runtime).
This allows to take off manually and then just trigger the RAPTOR mode for a split-second to see how it behaves.
In our experiments it has been exceptionally stable (zero crashes) but we still think progressively activating it for longer is the safest way to build confidence.
:::warning
Make sure that your platform uses the standard PX4 quadrotor motor layout:
1: front-right, 2: back-left, 3: front-left, 4: back-right
:::
##### Other Platforms
To enable the `mc_raptor` module in other platforms, just add `CONFIG_MODULES_MC_RAPTOR=y` and `CONFIG_LIB_RL_TOOLS=y`
```diff
+++ b/boards/px4/fmu-v6c/raptor.px4board
@@ -35,2 +35,3 @@
CONFIG_DRIVERS_UAVCAN=y
+CONFIG_LIB_RL_TOOLS=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
@@ -64,2 +65,3 @@
CONFIG_MODULES_MC_POS_CONTROL=y
+CONFIG_MODULES_MC_RAPTOR=y
CONFIG_MODULES_MC_RATE_CONTROL=y
```
#### Results
Even though there were moderate winds (~ 5 m/s) during the test, we found good figure-eight tracking performance at velocities up to 12 m/s:
![Lissajous](../../assets/advanced/neural_networks/raptor/results_figure_eight.svg)
We also tested the linear velocity in a straight line and found that the RAPTOR policy can reliably fly at > 17 m/s (the wind direction was orthogonal to the line):
![Linear Oscillation](../../assets/advanced/neural_networks/raptor/results_line.svg)
### 문제 해결
#### 로깅
Use this logging configuration to log all relevant topics at maximum rate:
```sh
cat > logger_topics.txt << EOF
raptor_status 0
raptor_input 0
trajectory_setpoint 0
vehicle_local_position 0
vehicle_angular_velocity 0
vehicle_attitude 0
vehicle_status 0
actuator_motors 0
EOF
```
Use mavproxy FTP to upload it:
```sh
mavproxy.py
```
##### Real
```sh
ftp mkdir /fs/microsd/etc
ftp mkdir /fs/microsd/etc/logging
ftp put logger_topics.txt /fs/microsd/etc/logging/logger_topics.txt
```
##### SITL
```sh
ftp mkdir etc
ftp mkdir logging
ftp put logger_topics.txt etc/logging/logger_topics.txt
```
-77
View File
@@ -1,77 +0,0 @@
# TensorFlow Lite Micro (TFLM)
The PX4 [MC Neural Networks Control](../neural_networks/mc_neural_network_control.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 [MC Neural Networks Control](../neural_networks/mc_neural_network_control.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
View File
@@ -151,7 +151,6 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### uXRCE-DDS / ROS2
- [PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113): <Badge type="warning" text="Experimental"/> [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically
- <Badge type="warning" text="Experimental"/>[PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md).
- dds_topics: add vtol_vehicle_status ([PX4-Autopilot#24582](https://github.com/PX4/PX4-Autopilot/pull/24582))
- dds_topics: add home_position ([PX4-Autopilot#24583](https://github.com/PX4/PX4-Autopilot/pull/24583))
-134
View File
@@ -1,134 +0,0 @@
# PX4-Autopilot v1.17.0 Release Notes
<Badge type="danger" text="Alpha/Beta" />
<script setup>
import { useData } from 'vitepress'
const { site } = useData();
</script>
<div v-if="site.title !== 'PX4 Guide (main)'">
<div class="custom-block danger">
<p class="custom-block-title">This page is on a release branch, and hence probably out of date. <a href="https://docs.px4.io/main/en/releases/main.html">See the latest version</a>.</p>
</div>
</div>
This contains changes to PX4 planned for PX4 v1.17 (since the last major release [PX v1.16](../releases/1.16.md)).
:::warning
PX4 v1.17 is in alpha/beta testing.
Update these notes with features that are going to be in PX4 v1.17 release.
New features that are not expected to go into the v1.17 release are in [PX4-Autopilot `main` Release Notes](../releases/main.md).
:::
## Read Before Upgrading
TBD …
Please continue reading for [upgrade instructions](#upgrade-guide).
## Major Changes
- TBD
## Upgrade Guide
## Other changes
### Hardware Support
- **[New Hardware]** boards: [MicoAir743-Lite FC](../flight_controller/micoair743-lite.md) <!-- CHECK is this version and add PR link (or fix up doc version tag and move this) -->
- **[New Hardware]** boards: [RadiolinkPIX6 FC](../flight_controller/radiolink_pix6.md) <!-- CHECK is this version and add PR! -->
- **[New Hardware]** boards: [AP-H743-R1 FC](../flight_controller/x-mav_ap-h743r1.md) <!-- CHECK is this version and add PR! -->
<!--
### Common
- [QGroundControl Bootloader Update](../advanced_config/bootloader_update.md#qgc-bootloader-update-sys-bl-update) via the [SYS_BL_UPDATE](../advanced_config/parameter_reference.md#SYS_BL_UPDATE) parameter has been re-enabled after being broken for a number of releases. ([PX4-Autopilot#25032: build: romf: fix generation of rc.board_bootloader_upgrade](https://github.com/PX4/PX4-Autopilot/pull/25032)).
-->
### 제어
<!--
- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW).
For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
-->
- <Badge type="warning" text="Experimental" /> [MC Neural Network Module](../advanced/neural_networkss.md)
### Estimation
- TBD
<!--
### Sensors
- Add [sbgECom INS driver](../sensor/sbgecom.md) ([PX4-Autopilot#24137](https://github.com/PX4/PX4-Autopilot/pull/24137))
- Quick magnetometer calibration now supports specifying an arbitrary initial heading ([PX4-Autopilot#24637](https://github.com/PX4/PX4-Autopilot/pull/24637))
-->
### 시뮬레이션
- Overhaul rover simulation:
- Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107)
- Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113)
- Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117)
- [Simulation-in-Hardware (SIH)](../sim_sih/index.md#compatibility) <!-- Listed in https://docs.px4.io/main/en/sim_sih/#compatibility : Check the PRs -->
- New simulation: MC Hexacopter X
- New simulation: Ackermann Rover
### Debug & Logging
- TBD
### Ethernet
- TBD
### uXRCE-DDS / Zenoh / ROS2
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)).
- [UXRCE_DDS: Simple index based namespace (UXRCE_DDS_NS_IDX)](../middleware/uxrce_dds.md#customizing-the-namespace)
- [Zenoh (PX4 ROS 2 rmw_zenoh)](../middleware/zenoh.md)
### MAVLink
- TBD
<!--
### RC
- Parse ELRS Status and Link Statistics TX messages in the CRSF parser.
### Multi-Rotor
- Removed parameters `MPC_{XY/Z/YAW}_MAN_EXPO` and use default value instead, as they were not deemed necessary anymore. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
- Renamed `MPC_HOLD_DZ` to `MAN_DEADZONE` to have it globally available in modes that allow for a dead zone. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
-->
### 수직이착륙기(VTOL)
- TBD
### Fixed-wing
- [Fixed Wing Takeoff mode](../flight_modes_fw/takeoff.md) will now keep climbing with level wings on position loss.
A target takeoff waypoint can be set to control takeoff course and loiter altitude. ([PX4-Autopilot#25083](https://github.com/PX4/PX4-Autopilot/pull/25083)).
- Automatically suppress angular rate oscillations using [Gain compression](../features_fw/gain_compression.md). ([PX4-Autopilot#25840: FW rate control: add gain compression algorithm](https://github.com/PX4/PX4-Autopilot/pull/25840))
### 탐사선
- Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)).
- Add support for [Apps & API](../flight_modes_rover/api.md) including [Rover Setpoints](../ros2/px4_ros2_control_interface.md#rover-setpoints) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)).
- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details).
### ROS 2
- TBD
+1 -2
View File
@@ -2,8 +2,7 @@
PX4 릴리스 노트는 각 릴리스의 변경 사항들을 설명합니다.
- [main](../releases/main.md) (changes planned for v1.18 or later)
- [v1.17](../releases/1.17.md) (changes planned for v1.17, since v1.16)
- [main](../releases/main.md) (changes since v1.16)
- [v1.16](../releases/1.16.md)
- [v1.15](../releases/1.15.md)
- [v1.14](../releases/1.14.md)
+6 -30
View File
@@ -16,13 +16,13 @@ const { site } = useData();
This contains changes to PX4 `main` branch since the last major release ([PX v1.16](../releases/1.16.md)).
:::warning
PX4 v1.17 is in alpha/beta testing.
Update these notes with features that are going to be in `main` (PX4 v1.18 or later) but not the PX4 v1.17 release.
PX4 v1.16 is in candidate-release testing, pending release.
Update these notes with features that are going to be in `main` but not the PX4 v1.16 release.
:::
## Read Before Upgrading
- TBD …
TBD …
Please continue reading for [upgrade instructions](#upgrade-guide).
@@ -45,7 +45,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### 제어
- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW).
For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. (PX4-Autopilot#25435: Add new flight mode: Altitude Cruise
).
### Estimation
@@ -58,34 +59,19 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### 시뮬레이션
- TBD
<!-- MOVED THIS TO v1.17
- Overhaul rover simulation:
- Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107)
- Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113)
- Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117)
-->
### Debug & Logging
- [Asset Tracking](../debug/asset_tracking.md): Automatic tracking and logging of external device information including vendor name, firmware and hardware version, serial numbers. Currently supports DroneCAN devices. ([PX4-Autopilot#25617](https://github.com/PX4/PX4-Autopilot/pull/25617))
### Ethernet
- TBD
### uXRCE-DDS / Zenoh / ROS2
- TBD
<!-- MOVED THIS TO v1.17
### uXRCE-DDS / ROS2
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)).
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md).
-->
### MAVLink
@@ -106,26 +92,16 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Fixed-wing
- TBD
<!-- MOVED THIS TO v1.17
- [Fixed Wing Takeoff mode](../flight_modes_fw/takeoff.md) will now keep climbing with level wings on position loss.
A target takeoff waypoint can be set to control takeoff course and loiter altitude. ([PX4-Autopilot#25083](https://github.com/PX4/PX4-Autopilot/pull/25083)).
- Automatically suppress angular rate oscillations using [Gain compression](../features_fw/gain_compression.md). ([PX4-Autopilot#25840: FW rate control: add gain compression algorithm](https://github.com/PX4/PX4-Autopilot/pull/25840))
-->
### 탐사선
- TBD
<!-- MOVED THIS TO v1.17
- Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)).
- Add support for [Apps & API](../flight_modes_rover/api.md) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)).
- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details).
-->
### ROS 2
- TBD
+5 -5
View File
@@ -345,9 +345,9 @@ The used types also define the compatibility with different vehicle types.
The following sections provide a list of supported setpoint types:
- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): <Badge type="warning" text="MC only" /> Smooth position and (optionally) heading control
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="warning" text="FW only" /> <Badge type="tip" text="PX4 v1.17" /> Direct control of lateral and longitudinal fixed wing dynamics
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="warning" text="FW only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct control of lateral and longitudinal fixed wing dynamics
- [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints
- [Rover Setpoints](#rover-setpoints): <Badge type="tip" text="PX4 v1.17" /> Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering).
- [Rover Setpoints](#rover-setpoints): <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering).
:::tip
The other setpoint types are currently experimental, and can be found in: [px4_ros2/control/setpoint_types/experimental](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental).
@@ -414,7 +414,7 @@ _goto_setpoint->update(
#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType)
<Badge type="warning" text="Fixed wing only" /> <Badge type="tip" text="PX4 v1.17" />
<Badge type="warning" text="Fixed wing only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" />
:::info
This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode.
@@ -556,7 +556,7 @@ If you want to control an actuator that does not control the vehicle's motion, b
#### Rover Setpoints
<Badge type="tip" text="PX4 v1.17" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
The rover modules use a hierarchical structure to propagate setpoints:
@@ -590,7 +590,7 @@ An example for a rover specific drive mode using the `RoverSpeedAttitudeSetpoint
### Controlling a VTOL
<Badge type="tip" text="PX4 v1.17" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration:
+2 -2
View File
@@ -27,8 +27,8 @@ The Desktop computer is only used to display the virtual vehicle.
- SIH for FW (airplane) and VTOL tailsitter are supported from PX4 v1.13.
- SIH as SITL (without hardware) from PX4 v1.14.
- SIH for Standard VTOL from PX4 v1.16.
- SIH for MC Hexacopter X from PX4 v1.17.
- SIH for Ackermann Rover from PX4 v1.17.
- SIH for MC Hexacopter X from `main` (expected to be PX4 v1.17).
- SIH for Ackermann Rover from `main`.
### Benefits
+3 -12
View File
@@ -93,7 +93,6 @@
- [Настройка Зворотнього Переходу](config_vtol/vtol_back_transition_tuning.md)
- [ВЗІП Датчик польоту](config_vtol/vtol_without_airspeed_sensor.md)
- [VTOL Weather Vane](config_vtol/vtol_weathervane.md)
- [VTOL Ice Shedding](config_vtol/vtol_ice_shedding.md)
- [Режим польоту](flight_modes_vtol/index.md)
- [Mission Mode (VTOL)](flight_modes_vtol/mission.md)
- [Return Mode (VTOL)](flight_modes_vtol/return.md)
@@ -129,7 +128,6 @@
- [Значення світлодіодів](getting_started/led_meanings.md)
- [Значення звуків та мелодій](getting_started/tunes.md)
- [QGroundControl Flight-Readiness Status](flying/pre_flight_checks.md)
- [Asset Tracking](debug/asset_tracking.md)
- [Вибір обладнання & Налаштування](hardware/drone_parts.md)
- [Flight Controllers (Autopilots)](flight_controller/index.md)
@@ -275,8 +273,6 @@
- [Holybro M8N & M9N GPS](gps_compass/gps_holybro_m8n_m9n.md)
- [Sky-Drones SmartAP GPS](gps_compass/gps_smartap.md)
- [RTK GNSS](gps_compass/rtk_gps.md)
- [ARK G5 RTK GPS](dronecan/ark_g5_rtk_gps.md)
- [ARK G5 RTK HEADING GPS](dronecan/ark_g5_rtk_heading_gps.md)
- [ARK RTK GPS (CAN)](dronecan/ark_rtk_gps.md)
- [ARK RTK GPS L1 L5 (CAN)](dronecan/ark_rtk_gps_l1_l2.md)
- [ARK X20 RTK GPS (CAN)](dronecan/ark_x20_rtk_gps.md)
@@ -362,8 +358,6 @@
- [Супутниковий зв'язок (Iridium/RockBlock)](advanced_features/satcom_roadblock.md)
- [Analog Video Transmitters](vtx/index.md)
- [Енергетичні системи](power_systems/index.md)
- [Налаштування оцінки батареї](config/battery.md)
- [Battery Chemistry Overview](power_systems/battery_chemistry.md)
@@ -846,11 +840,9 @@
- [Інтеграція камери/Архітектура](camera/camera_architecture.md)
- [Комп'ютерний зір](advanced/computer_vision.md)
- [Захоплення руху (VICON, Optitrack, NOKOV)](tutorials/motion-capture.md)
- [Neural Networks](neural_networks/index.md)
- [MC NN Control Module (Generic)](neural_networks/mc_neural_network_control.md)
- [Neural Network Module Utilities](neural_networks/nn_module_utilities.md)
- [TensorFlow Lite Micro (TFLM)](neural_networks/tflm.md)
- [RAPTOR Adaptive RL NN Module](neural_networks/raptor.md)
- [Neural Networks](advanced/neural_networks.md)
- [Neural Network Module Utilities](advanced/nn_module_utilities.md)
- [TensorFlow Lite Micro (TFLM)](advanced/tflm.md)
- [Встановлюється драйвер для Intel RealSense R200](advanced/realsense_intel_driver.md)
- [Перемикання оцінювачів стану](advanced/switching_state_estimators.md)
- [Out-of-Tree модулі](advanced/out_of_tree_modules.md)
@@ -933,7 +925,6 @@
- [Релізи](releases/index.md)
- [main (alpha)](releases/main.md)
- [1.17 (alpha)](releases/1.17.md)
- [1.16 (stable)](releases/1.16.md)
- [1.15](releases/1.15.md)
- [1.14](releases/1.14.md)
+1 -1
View File
@@ -74,7 +74,7 @@ Gimbal також можна контролювати шляхом підклю
![Gimbal Actuator config](../../assets/config/actuators/qgc_actuators_gimbal.png)
The PWM values to use for the disarmed, maximum, center and minimum values can be determined in the same way as other servo, using the [Actuator Test sliders](../config/actuators.md#actuator-testing) to confirm that each slider moves the appropriate axis, and changing the values so that the gimbal is in the appropriate position at the disarmed, low, center and high position in the slider.
PWM значення для використання при відблокованому, максимальному та мінімальному значеннях можна визначити так само, як і для інших сервоприводів, використовуючи [повзунки тесту приводу](../config/actuators.md#actuator-testing), щоб підтвердити, що кожний повзунок переміщує відповідну вісь, і змінюючи значення так, щоб гімбал знаходився у відповідному положенні при відблокованому стані, низькому і високому положенні повзунка.
Значення також можуть бути наведені у документації гімбала.
## Gimbal Control in Missions
+119 -1
View File
@@ -1 +1,119 @@
<Redirect to="../neural_networks/mc_neural_network_control" />
# Neural Networks
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
:::warning
This is an experimental module.
Use at your own risk.
:::
The Multicopter Neural Network (NN) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) is an example module that allows you to experiment with using a pre-trained neural network on PX4.
It might be used, for example, to experiment with controllers for non-traditional drone morphologies, computer vision tasks, and so on.
The module integrates a pre-trained neural network based on the [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md) module.
The module is trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md) multicopter frame.
While the controller is fairly robust, and might work on other platforms, we recommend [Training your own Network](#training-your-own-network) if you use a different vehicle.
Note that after training the network you will need to update and rebuild PX4.
TLFM is a mature inference library intended for use on embedded devices.
It has support for several architectures, so there is a high likelihood that you can build it for the board you want to use.
If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview).
This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works.
The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether.
If you are looking for more resources to learn about the module, a website has been created with links to a youtube video and a workshop paper. A full master's thesis will be added later. [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/).
## Neural Network PX4 Firmware
:::warning
This module requires Ubuntu 24.04 or newer (it is not supported in Ubuntu 22.04).
:::
The module has been tested on a number of configurations, which can be build locally using the commands:
```sh
make px4_sitl_neural
```
```sh
make px4_fmu-v6c_neural
```
```sh
make mro_pixracerpro_neural
```
You can add the module to other board configurations by modifying their `default.px4board file` configuration to include these lines:
```sh
CONFIG_LIB_TFLM=y
CONFIG_MODULES_MC_NN_CONTROL=y
```
:::tip
The `mc_nn_control` module takes up roughly 50KB, and many of the `default.px4board file` are already close to filling all the flash on their boards. To make room for the neural control module you can remove the include statements for other modules, such as FW, rover, VTOL and UUV.
:::
## Example Module Overview
The example module replaces the entire controller structure as well as the control allocator, as shown in the diagram below:
![neural_control](../../assets/advanced/neural_control.png)
In the [controller diagram](../flight_stack/controller_diagrams.md) you can see the [uORB message](../middleware/uorb.md) flow.
We hook into this flow by subscribing to messages at particular points, using our neural network to calculate outputs, and then publishing them into the next point in the flow.
We also need to stop the module publishing the topic to be replaced, which is covered in [Neural Network Module: System Integration](nn_module_utilities.md)
### Вхід
The input can be changed to whatever you want.
Set up the input you want to use during training and then provide the same input in PX4.
In the Neural Control module the input is an array of 15 numbers, and consists of these values in this order:
- [3] Local position error. (goal position - current position)
- [6] The first 2 rows of a 3 dimensional rotation matrix.
- [3] Linear velocity
- [3] Angular velocity
All the input values are collected from uORB topics and transformed into the correct representation in the `PopulateInputTensor()` function.
PX4 uses the NED frame representation, while the Aerial Gym Simulator, in which the NN was trained, uses the ENU representation.
Therefore two rotation matrices are created in the function and all the inputs are transformed from the NED representation to the ENU one.
![ENU-NED](../../assets/advanced/ENU-NED.png)
ENU and NED are just rotation representations, the translational difference is only there so both can be seen in the same figure.
### Output
The output consists of 4 values, the motor forces, one for each motor.
These are transformed in the `RescaleActions()` function.
This is done because PX4 expects normalized motor commands while the Aerial Gym Simulator uses physical values.
So the output from the network needs to be normalized before they can be sent to the motors in PX4.
The commands are published to the [ActuatorMotors](../msg_docs/ActuatorMotors.md) topic.
The publishing is handled in `PublishOutput(float* command_actions)` function.
:::tip
If the neural control mode is too aggressive or unresponsive the [MC_NN_THRST_COEF](../advanced_config/parameter_reference.md#MC_NN_THRST_COEF) parameter can be tuned.
Decrease it for more thrust.
:::
## Training your own Network
The network is currently trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md).
But the controller is somewhat robust, so it could work directly on other platforms, but performing system identification and training a new network is recommended.
Since the Aerial Gym Simulator is open-source you can download it and train your own networks as long as you have access to an NVIDIA GPU.
If you want to train a control network optimized for your platform you can follow the instructions in the [Aerial Gym Documentation](https://ntnu-arl.github.io/aerial_gym_simulator/9_sim2real/).
You should do one system identification flight for this and get an approximate inertia matrix for your platform.
On the `sys-id` flight you need ESC telemetry, you can read more about that in [DSHOT](../peripherals/dshot.md).
Then do the following steps:
- Do a hover flight
- Read of the logs what RPM is required for the drone to hover.
- Use the weight of each motor, length of the motor arms, total weight of the platform with battery to calculate an approximate inertia matrix for the platform.
- Insert these values into the Aerial Gym configuration and train your network.
- Convert the network as explained in [TFLM](tflm.md).
-4
View File
@@ -10,10 +10,6 @@ CAN it is designed to be democratic and uses differential signaling.
For this reason it is very robust even over longer cable lengths (on large vehicles), and avoids a single point of failure.
CAN також дозволяє отримання зворотного зв'язку від периферійних пристроїв та зручне оновлення прошивки через шину.
PX4 has the ability to track and log detailed information from CAN devices, including firmware versions, hardware versions, and serial numbers.
This enables unique identification and lifecycle tracking of hardware connected to the flight controller.
See [Asset Tracking](../debug/asset_tracking.md) for more information.
PX4 підтримує два програмні протоколи для взаємодії з пристроями CAN:
- [DroneCAN](../dronecan/README.md): PX4 рекомендує це для більшості типових налаштувань.
+16 -12
View File
@@ -104,7 +104,7 @@ There are several other "battery related" failsafe mechanisms that may be config
| Налаштування | Параметр | Опис |
| -------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None (default), `1`: Warning, `3`: Return mode. |
| <a id="COM_FLTT_LOW_ACT"></a> Low flight time for safe return action | [COM_FLTT_LOW_ACT](../advanced_config/parameter_reference.md#COM_FLTT_LOW_ACT) | Action when return mode can only just reach safety with remaining battery. `0`: None, `1`: Warning, `3`: Return mode (default). |
| <a id="COM_FLT_TIME_MAX"></a> Maximum flight time failsafe level | [COM_FLT_TIME_MAX](../advanced_config/parameter_reference.md#COM_FLT_TIME_MAX) | Maximum allowed flight time before Return mode will be engaged, in seconds. `-1`: Disabled (default). |
## Manual Control Loss Failsafe
@@ -119,32 +119,36 @@ PX4 and the receiver may also need to be configured in order to _detect RC loss_
![Safety - RC Loss (QGC)](../../assets/qgc/setup/safety/safety_rc_loss.png)
The QGCroundControl Safety UI allows you to set the [failsafe action](#failsafe-actions) and [manual control loss timeout](#COM_RC_LOSS_T).
Users that want to disable this failsafe in specific modes can do so using the parameter [COM_RCL_EXCEPT](#COM_RCL_EXCEPT).
The QGCroundControl Safety UI allows you to set the [failsafe action](#failsafe-actions) and [RC Loss timeout](#COM_RC_LOSS_T).
Users that want to disable the RC loss failsafe in specific automatic modes (mission, hold, offboard) can do so using the parameter [COM_RCL_EXCEPT](#COM_RCL_EXCEPT).
Нижче наведено додаткові (і базові) налаштування параметрів.
| Параметр | Налаштування | Опис |
| -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="COM_RC_LOSS_T"></a>[COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Аварійний режим втрати ручного керування Timeout | Час після отримання останньої встановленої точки від вибраного джерела керування вручну, після якого керування вважається втраченим. This must be kept short because the vehicle will continue to fly using the last known stick position until the timeout triggers. |
| <a id="COM_RC_LOSS_T"></a>[COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Аварійний режим втрати ручного керування Timeout | Час після отримання останньої встановленої точки від вибраного джерела керування вручну, після якого керування вважається втраченим. Це повинно бути коротким, оскільки транспортний засіб продовжуватиме літати за старими налаштуваннями керування вручну, поки не спрацює таймаут. |
| <a id="COM_FAIL_ACT_T"></a>[COM_FAIL_ACT_T](../advanced_config/parameter_reference.md#COM_FAIL_ACT_T) | Затримка відмови від дії | Delay in seconds between failsafe condition being triggered (`COM_RC_LOSS_T`) and failsafe action (RTL, Land, Hold). У цьому стані транспортний засіб очікує в режимі утримання на повторне підключення джерела керування вручну. Це може бути встановлено довше для довгих польотів, щоб втрата інтермітентного з'єднання не викликала негайного виклику аварійного режиму. Це може бути рівним нулю, щоб аварійний запобіжник спрацював негайно. |
| <a id="NAV_RCL_ACT"></a>[NAV_RCL_ACT](../advanced_config/parameter_reference.md#NAV_RCL_ACT) | Моделювання відмовостійкості | Вимкнути, Блукати, Повернутися, Приземлитися, Роззброїти, Завершити. |
| <a id="COM_RCL_EXCEPT"></a>[COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | Виключення втрат RC | Set modes in which manual control loss is ignored. |
| <a id="COM_RCL_EXCEPT"></a>[COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | Виключення втрат RC | Встановіть режими, в яких втрата керування вручну ігнорується: Місія, Утримання, Offboard. |
## Втрата каналу зв'язку Failsafe
The Data Link Loss failsafe is triggered if the connection to the last MAVLink ground station like QGroundControl is lost.
Users that want to disable this failsafe in specific modes can do so using the parameter [COM_DLL_EXCEPT](#COM_DLL_EXCEPT).
Збій втрати втрати даних посилання (при переході через телеметрію (підключення до наземної станції) втрачено.
![Safety - Data Link Loss (QGC)](../../assets/qgc/setup/safety/safety_data_link_loss.png)
Налаштування та вибрані параметри показані нижче.
| Налаштування | Параметр | Опис |
| ----------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------- |
| Тайм-аут втрати каналу зв'язку | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | Час після втрати з'єднання з даними перед тим, як спрацює запобіжник. |
| Моделювання відмовостійкості | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Вимкнути, Hold mode, Return mode, Land mode, Роззброїти, Завершити. |
| <a id="COM_DLL_EXCEPT"></a>Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes in which data link loss is ignored. |
| Налаштування | Параметр | Опис |
| ------------------------------ | --------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------- |
| Тайм-аут втрати каналу зв'язку | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | Час після втрати з'єднання з даними перед тим, як спрацює запобіжник. |
| Моделювання відмовостійкості | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Вимкнути, Hold mode, Return mode, Land mode, Роззброїти, Завершити. |
Також застосовуються наступні налаштування, але вони не відображаються в інтерфейсі QGC.
| Налаштування | Параметр | Опис |
| ----------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- |
| <a id="COM_DLL_EXCEPT"></a>Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes where DL loss will not trigger a failsafe. |
## Аварійний режим "обмеження зони політів"
-1
View File
@@ -9,4 +9,3 @@ As part of this you should calibrate the [Airspeed sensor](../config/airspeed.md
- [Back-transition Tuning](../config_vtol/vtol_back_transition_tuning.md)
- [VTOL w/o Airspeed Sensor](../config_vtol/vtol_without_airspeed_sensor.md)
- [VTOL Weather Vane](../config_vtol/vtol_weathervane.md)
- [Ice Shedding](../config_vtol/vtol_ice_shedding.md)
-22
View File
@@ -1,22 +0,0 @@
# VTOL Ice Shedding feature
## Загальний огляд
Ice shedding is a feature that periodically spins unused motors in fixed-wing
flight, to break off any ice that is starting to build up in the motors while it
is still feasible to do so.
It is configured by the paramter `CA_ICE_PERIOD`. When it is 0, the feature is
disabled, when it is above 0, it sets the duration of the ice shedding cycle in
seconds. In each cycle, the rotors are spun for two seconds at a motor output of
0.01.
:::warning
When enabling the feature on a new airframe, there is the risk of producing
torques that disturb the fixed-wing rate controller. To mitigate this risk:
- Set your `PWM_MIN` values correctly, so that the motor output 0.01 actually
produces 1% thrust
- Be prepared to take control and switch back to multicopter
:::
+1 -1
View File
@@ -34,7 +34,7 @@ Not all PX4 source code matches the style guide, but any _new code_ that you wri
### Довжина рядка
- Maximum line length is 140 characters.
- Максимальна довжина рядка становить 120 символів.
### Розширення файлів
-68
View File
@@ -1,68 +0,0 @@
# Asset Tracking
<Badge type="tip" text="main (planned for: PX4 v1.18)" />
PX4 can track and log detailed information about external hardware devices connected to the flight controller.
This enables unique identification of vehicle parts throughout their operational lifetime using device IDs, serial numbers, and version information.
:::info
Asset tracking is currently implemented for [DroneCAN](../dronecan/index.md) devices only.
:::
## Загальний огляд
Asset tracking allows you to determine exactly which hardware is installed on a vehicle, providing serial number, version, and other information.
This makes it easier to track and maintain specific vehicle parts across multiple vehicles, to quickly see what versions you're running when debugging, and log component information for regulatory audits.
Asset tracking automatically collects and logs the following metadata from external devices:
- **Device identification**: Vendor name, model name, device type
- **Version information**: Firmware version, hardware version
- **Unique identifiers**: Serial number, device ID
- **Device capabilities**: ESC, GPS, magnetometer, barometer, etc.
This information is published via the [`device_information`](../msg_docs/DeviceInformation.md) uORB topic and logged to flight logs.
This enables fleet management, maintenance tracking, and troubleshooting.
## Viewing Device Information
### Real-Time Monitoring
You can view device information in real-time using the [MAVLink Shell](../debug/mavlink_shell.md) or console:
```sh
listener device_information
```
Example output for a CAN GPS module:
```plain
TOPIC: device_information
device_information
timestamp: 16258961403 (0.216525 seconds ago)
device_id: 8944643 (Type: 0x88, UAVCAN:0 (0x7C))
device_type: 5
vendor_name: "cubepilot"
model_name: "here4"
firmware_version: "1.14.3006590"
hardware_version: "4.19"
serial_number: "1c00410018513331"
```
Device information is published in a round-robin fashion for each detected device, at a rate of approximately 1 Hz.
### Multi-Capability Devices
Devices with multiple sensors (e.g., a CAN GPS/magnetometer combo module like the HERE4) register separate device information entries for each capability.
Each entry shares the same serial number and base metadata but has a different `device_id` corresponding to the specific sensor capability.
## Аналіз журналу польотів
Device information is automatically logged to flight logs.
You can extract it using [pyulog](../log/flight_log_analysis.md#pyulog), though note that fields like vendor name, model name, and serial number are stored as `char` arrays and require additional parsing.
## Дивіться також
- [CAN (DroneCAN & Cyphal)](../can/index.md) — CAN bus configuration and setup
- [DroneCAN](../dronecan/index.md) — DroneCAN-specific documentation
- [Flight Log Analysis](../log/flight_log_analysis.md) — Flight log analysis
-112
View File
@@ -1,112 +0,0 @@
# ARK G5 RTK GPS
:::info
This GPS module is made in the USA and NDAA compliant.
:::
[ARK G5 RTK GPS](https://arkelectron.com/product/ark-g5-rtk-gps/) is a [DroneCAN](index.md) quad-band [RTK GPS](../gps_compass/rtk_gps.md).
The module incorporates the [Septentrio mosaic-G5 P3 Ultra-compact high-precision GPS/GNSS receiver module](https://www.u-blox.com/en/product/zed-x20p-module), magnetometer, barometer, IMU, and buzzer module.
![ARK G5 RTK GPS](../../assets/hardware/gps/ark/ark_g5_rtk_gps.png)
## Де купити
Замовте цей модуль з:
- [ARK Electronics](https://arkelectron.com/product/ark-g5-rtk-gps/) (US)
## Характеристики обладнання
- [DroneCAN](index.md) RTK GNSS, Magnetometer, Barometer, IMU, and Buzzer Module
- [Dronecan Firmware Updating](../dronecan/index.md#firmware-update)
- Датчики
- [Septentrio mosaic-G5 P3 Ultra-compact high-precision GPS/GNSS receiver module](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3)
- All-band all constellation GNSS receiver
- All-in-view satellite tracking: multi-constellation, quad-band GNSS module receiver
- Full raw data with positioning measurements and Galileo HAS positioning service compatibility
- Best-in-class RTK cm-level positioning accuracy
- Advanced GNSS+ algorithms
- 20Hz update rate
- [ST IIS2MDC Magnetometer](https://www.st.com/en/mems-and-sensors/iis2mdc.html)
- [Bosch BMP390 Barometer](https://www.bosch-sensortec.com/products/environmental-sensors/pressure-sensors/bmp390/)
- [Invensense ICM-42688-P 6-Axis IMU](https://invensense.tdk.com/products/motion-tracking/6-axis/icm-42688-p/)
- STM32F412VGH6 MCU
- Кнопка безпеки
- Зумер
- Two CAN Connectors (Pixhawk Connector Standard 4-pin JST GH)
- G5 "UART 2" Connector
- 4-pin JST GH
- TX, RX, PPS, GND
- G5 USB C
- Debug Connector (Pixhawk Connector Standard 6-pin JST SH)
- LED індикатори
- GPS Fix
- Статус RTK
- RGB Статус системи
- USA Built
- NDAA Compliant
- Вимоги до живлення
- 5V
- 270mA
- Розміри
- Without Antenna
- 48.0mm x 40.0mm x 15.4mm
- 13.0g
- With Antenna
- 48.0mm x 40.0mm x 51.0mm
- 43.5g
- Includes
- CAN Cable (Pixhawk Connector Standard 4-pin)
- Full-Frequency Helical GPS Antenna
## Налаштування програмного забезпечення
### Підключення
The ARK G5 RTK GPS is connected to the CAN bus using a [Pixhawk connector standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) 4-pin JST GH cable.
For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
### Встановлення
The recommended mounting orientation is with the connectors on the board pointing towards the **back of vehicle**.
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during [PX4 Configuration](#px4-configuration).
## Налаштування прошивки
The Septentrio G5 module firmware can be updated using the Septentrio [RxTools](https://www.septentrio.com/en/products/gps-gnss-receiver-software/rxtools) application.
## Налаштування польотного контролера
### Увімкнення DroneCAN
In order to use the ARK G5 RTK GPS, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)).
Кроки наступні:
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` or `3` and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
- Connect ARK G5 RTK GPS CAN to the Pixhawk CAN.
Після активації модуль буде виявлено при завантаженні.
There is also CAN built-in bus termination via [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM)
### Конфігурація PX4
You need to set necessary [DroneCAN](index.md) parameters and define offsets if the sensor is not centred within the vehicle:
- 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 [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK G5 RTK GPS from the vehicle's centre of gravity.
## Значення LED індикаторів
The GPS status lights are located to the right of the connectors:
- Миготіння зеленого - це фіксація GPS
- Миготіння синього - це отримані корекції та RTK Float
- Сталий синій - це RTK зафіксовано
## Дивіться також
- [ARK G5 RTK GPS Documentation](https://docs.arkelectron.com/gps/ark-g5-rtk-gps) (ARK Docs)
-150
View File
@@ -1,150 +0,0 @@
# ARK G5 RTK HEADING GPS
:::info
This GPS module is made in the USA and NDAA compliant.
:::
[ARK G5 RTK HEADING GPS](https://arkelectron.com/product/ark-g5-rtk-gps/) is a [DroneCAN](index.md) quad-band dual antenna [RTK GPS](../gps_compass/rtk_gps.md) that additionally provides vehicle yaw information from GPS.
The module incorporates the [Septentrio mosaic-G5 P3H Ultra-compact high-precision GPS/GNSS receiver module with heading capability](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H), magnetometer, barometer, IMU, and buzzer module.
![ARK G5 RTK HEADING GPS](../../assets/hardware/gps/ark/ark_g5_rtk_gps.png)
## Де купити
Замовте цей модуль з:
- [ARK Electronics](https://arkelectron.com/product/ark-g5-rtk-heading-gps/) (US)
## Характеристики обладнання
- [DroneCAN](index.md) RTK GNSS, Magnetometer, Barometer, IMU, and Buzzer Module
- [Dronecan Firmware Updating](../dronecan/index.md#firmware-update)
- Датчики
- [Septentrio mosaic-G5 P3H Ultra-compact high-precision GPS/GNSS receiver module with heading capability](https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H)
- All-band all constellation GNSS receiver
- All-in-view satellite tracking: multi-constellation, quad-band GNSS module receiver
- Full raw data with positioning measurements and Galileo HAS positioning service compatibility
- Best-in-class RTK cm-level positioning accuracy
- Advanced GNSS+ algorithms
- 20Hz update rate
- [ST IIS2MDC Magnetometer](https://www.st.com/en/mems-and-sensors/iis2mdc.html)
- [Bosch BMP390 Barometer](https://www.bosch-sensortec.com/products/environmental-sensors/pressure-sensors/bmp390/)
- [Invensense ICM-42688-P 6-Axis IMU](https://invensense.tdk.com/products/motion-tracking/6-axis/icm-42688-p/)
- STM32F412VGH6 MCU
- Кнопка безпеки
- Зумер
- Two CAN Connectors (Pixhawk Connector Standard 4-pin JST GH)
- G5 "UART 2" Connector
- 4-pin JST GH
- TX, RX, PPS, GND
- G5 USB C
- Debug Connector (Pixhawk Connector Standard 6-pin JST SH)
- LED індикатори
- GPS Fix
- Статус RTK
- RGB Статус системи
- USA Built
- NDAA Compliant
- Вимоги до живлення
- 5V
- 270mA
- Розміри
- Without Antenna
- 48.0mm x 40.0mm x 15.4mm
- 13.0g
- With Antenna
- 48.0mm x 40.0mm x 51.0mm
- 43.5g
- Includes
- CAN Cable (Pixhawk Connector Standard 4-pin)
- Full-Frequency Helical GPS Antenna
## Налаштування програмного забезпечення
### Підключення
The ARK G5 RTK HEADING GPS is connected to the CAN bus using a [Pixhawk connector standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf) 4-pin JST GH cable.
For more information, refer to the [CAN Wiring](../can/index.md#wiring) instructions.
### Встановлення
The recommended mounting orientation is with the connectors on the board pointing towards the **back of vehicle**.
The sensor can be mounted anywhere on the frame, but you will need to specify its position, relative to vehicle centre of gravity, during [PX4 configuration](#px4-configuration).
## Налаштування прошивки
The Septentrio G5 module firmware can be updated using the Septentrio [RxTools](https://www.septentrio.com/en/products/gps-gnss-receiver-software/rxtools) application.
## Налаштування польотного контролера
### Увімкнення DroneCAN
In order to use the ARK G5 RTK HEADING GPS, connect it to the Pixhawk CAN bus and enable the DroneCAN driver by setting parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)).
Кроки наступні:
- In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` or `3` and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)).
- Connect ARK G5 RTK HEADING GPS CAN to the Pixhawk CAN.
Після активації модуль буде виявлено при завантаженні.
There is also CAN built-in bus termination via [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM)
### Конфігурація PX4
You need to set necessary [DroneCAN](index.md) parameters and define offsets if the sensor is not centred within the vehicle:
- 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).
- 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 [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK G5 RTK HEADING GPS from the vehicle's centre of gravity.
### Parameter references
This GPS is using ARK's private driver, the prameters below only exist on the firmware we ship the GPS with. You can set these params either in QGC or using the DroneCAN GUI Tool.
#### SEP_OFFS_YAW (float)
Heading offset angle for dual antenna GPS setups that support heading estimation.
Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the Rover/ANT2 antenna is in front.
The offset angle increases clockwise.
Set this to 90 if the ANT2 antenna is placed on the right side of the vehicle and the Moving Base/MAIN antenna is on the left side.
- Default: 0
- Min: -360
- Max: 360
- Unit: degree
#### SEP_OFFS_PITCH (float)
Vertical offsets can be compensated for by adjusting the Pitch offset.
Note that this can be interpreted as the "roll" angle in case the antennas are aligned along the perpendicular axis. This occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame. Since pitch is defined as the right-handed rotation about the vehicle Y axis, a situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch.
- Default: 0
- Min: -90
- Max: 90
- Unit: degree
#### SEP_OUT_RATE (enum)
Configures the output rate for GNSS data messages.
- -1: OnChange (Default)
- 50: 50 ms
- 100: 100 ms
- 200: 200 ms
- 500: 500 ms
## Значення LED індикаторів
The GPS status lights are located to the right of the connectors:
- Миготіння зеленого - це фіксація GPS
- Миготіння синього - це отримані корекції та RTK Float
- Сталий синій - це RTK зафіксовано
## Дивіться також
- [ARK G5 RTK HEADING GPS Documentation](https://docs.arkelectron.com/gps/ark-g5-rtk-gps) (ARK Docs)
-2
View File
@@ -27,8 +27,6 @@ DroneCAN was previously known as UAVCAN v0 (or just UAVCAN).
- Проводка менше складна, оскільки ви можете мати один шину для підключення всіх ваших ESC і інших периферійних пристроїв DroneCAN.
- Налаштування стає простіше, оскільки ви налаштовуєте нумерацію ESC, обертаючи кожен двигун вручну.
- Це дозволяє користувачам налаштовувати та оновлювати прошивку всіх пристроїв, підключених через CAN, централізовано через PX4.
- PX4 automatically tracks device information (vendor, model, versions, serial numbers) for maintenance and fleet management.
See [Asset Tracking](../debug/asset_tracking.md).
## Підтримуване обладнання
+1 -1
View File
@@ -1,6 +1,6 @@
# Gain compression
<Badge type="tip" text="PX4 v1.17" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
Automatic gain compression reduces the gains of the angular-rate PID whenever oscillations are detected.
It monitors the angular-rate controller output through a band-pass filter to identify these oscillations.
+1 -1
View File
@@ -1,6 +1,6 @@
# MicoAir743-Lite
<Badge type="tip" text="PX4 v1.17" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
:::warning
PX4 не розробляє цей (або будь-який інший) автопілот.
+1 -1
View File
@@ -1,6 +1,6 @@
# RadiolinkPIX6 Flight Controller
<Badge type="tip" text="PX4 v1.17" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
:::warning
PX4 не розробляє цей (або будь-який інший) автопілот.
+2 -2
View File
@@ -1,6 +1,6 @@
# AP-H743-R1 Flight Controller
# AP-H743-R1
<Badge type="tip" text="PX4 v1.17" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
:::warning
PX4 не розробляє цей (або будь-який інший) автопілот.
+9 -68
View File
@@ -2,14 +2,11 @@
<img src="../../assets/site/position_fixed.svg" title="Position fix required (e.g. GPS)" width="30px" />
The _Hold_ flight mode causes the vehicle to loiter around its current GPS position and maintain its current altitude.
The mode supports a [number of distinct loiter modes](#loiter-modes), which are triggered using different QGC controls or MAVLink commands.
These allow loitering with circular and figure 8 flight paths.
The _Hold_ flight mode causes the vehicle to loiter (circle) around its current GPS position and maintain its current altitude.
:::tip
_Hold mode_ can be used to pause a mission or to help you regain control of a vehicle in an emergency.
It is usually activated with a pre-programmed RC switch.
Зазвичай він активується за допомогою наперед заданого перемикача.
:::
::: info
@@ -27,80 +24,24 @@ It is usually activated with a pre-programmed RC switch.
:::
## Loiter modes
## Технічний підсумок
### Default Loiter
Літак кружляє навколо позиції утримання GPS на поточній висоті.
The vehicle will first ascend to [NAV_MIN_LTR_ALT](#NAV_MIN_LTR_ALT) if the mode is engaged below this altitude.
The aircraft circles around the position at which the mode was triggered and maintain its current altitude.
The loiter radius is set by the parameter [NAV_LOITER_RAD](#NAV_LOITER_RAD).
Note that if the vehicle altitude is below [NAV_MIN_LTR_ALT](#NAV_MIN_LTR_ALT), it will ascend to that minimum altitude before circling.
Рух стіків радіокерування ігнорується.
The default loiter mode is entered when you switch to Hold mode without explicitly specifying any loiter behaviour.
For example, if you switch to Hold mode using an RC switch, select **Hold** on the QGC flight mode selector, or activate the mode using the MAVLink [MAV_CMD_DO_SET_MODE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_MODE) command.
### Orbit Loiter Mode
<Badge type="tip" text="PX4 v1.12" />
The aircraft travels towards a _specified_ orbit center position, then circles it with a given direction and radius.
This behaviour can be accessed in QGroundControl by clicking on the map in Fly view, selecting **Orbit at Location**, and configuring the radius.
The behavior can be triggered using the MAVLink [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) command.
Note that PX4 respects the specified centre point (`param5`, `param6`, `param7`), and the radius and direction (`param1`).
PX4 ignores `param3` (Yaw behaviour) and `param4` (Orbits).
The value of `param2` (velocity) is also ignored, but the speed can be controlled using the [MAV_CMD_DO_CHANGE_SPEED](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_CHANGE_SPEED) command (constrained between `FW_AIRSPD_MAX` and `FW_AIRSPD_MIN`).
PX4 outputs orbit status using the [ORBIT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#ORBIT_EXECUTION_STATUS) message.
### Figure 8 Loiter Mode
<Badge type="tip" text="PX4 v1.15" /> <Badge type="warning" text="Experimental" />
The aircraft flys towards the closest point on a specified figure 8 path and then follows it.
The path is defined by the figure 8 centre position, orientation, and radius of two circles.
The feature is experimental, and is not present in PX4 firmware by default (on most flight controller boards).
It can be included by setting the `CONFIG_FIGURE_OF_EIGHT` key in the [PX4 board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) for your board and rebuilding.
For example, this is enabled on the [default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/auterion/fmu-v6s/default.px4board#L46) file for the `auterion/fmu-v6s` board.
The behavior can be triggered using the MAVLink [MAV_CMD_DO_FIGURE_EIGHT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_FIGURE_EIGHT) command (PX4 respects all the parameters).
PX4 outputs the figure 8 status using the [FIGURE_EIGHT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#FIGURE_EIGHT_EXECUTION_STATUS) message.
:::info
Figure 8 loitering is not currently supported by QGC: [QGC#12778: Need Support Figure of eight (8 figure) loitering by QGC](https://github.com/mavlink/qgroundcontrol/issues/12778).
:::
Figure 8 loitering is also available in the simulator.
You can test it in [Gazebo](../sim_gazebo_gz/index.md) using a fixed wing frame:
```sh
make px4_sitl gz_rc_cessna
```
## Параметри
### Параметри
Поведінку режиму утримання можна налаштувати за допомогою наведених нижче параметрів.
| Параметр | Опис |
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="NAV_LOITER_RAD"></a>[NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | Радіус кола обертання. |
| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | Радіус кола обертання. |
| <a id="NAV_MIN_LTR_ALT"></a>[NAV_MIN_LTR_ALT](../advanced_config/parameter_reference.md#NAV_MIN_LTR_ALT) | Мінімальна висота для режиму очікування (транспортний засіб підніметься на цю висоту, якщо режим увімкнуто на меншій висоті). |
## MAVLink Commands
The following commands are relevant to this mode:
- [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) - Switch to Hold mode and start the specified [Orbit loiter](#orbit-loiter-mode).
Params 2 (velocity), 3 (yaw), 4 (orbits) are ignored.
[ORBIT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#ORBIT_EXECUTION_STATUS) is emitted.
- [MAV_CMD_DO_FIGURE_EIGHT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_FIGURE_EIGHT) - Switch to Hold mode and start the specified [Figure 8 loiter](#figure-8-loiter-mode).
All params are respected.
[FIGURE_EIGHT_EXECUTION_STATUS](https://mavlink.io/en/messages/common.html#FIGURE_EIGHT_EXECUTION_STATUS) is emitted.
Note, other commands may be supported.
## Дивіться також
- [Hold Mode (MC)](../flight_modes_mc/hold.md)
[Hold Mode (MC)](../flight_modes_mc/hold.md)
<!-- this maps to AUTO_LOITER in flight mode state machine -->
+2 -2
View File
@@ -49,8 +49,8 @@ If the local position is invalid or becomes invalid while executing the takeoff,
::: info
- Takeoff towards a target position was added in <Badge type="tip" text="PX4 v1.17" />.
- Holding wings level and ascending to clearance attitude when local position is invalid during takeoff was added in <Badge type="tip" text="PX4 v1.17" />.
- Takeoff towards a target position was added in <Badge type="tip" text="main (planned for: PX4 v1.17)" />.
- Holding wings level and ascending to clearance attitude when local position is invalid during takeoff was added in <Badge type="tip" text="main (planned for: PX4 v1.17)" />.
- QGroundControl does not support `MAV_CMD_NAV_TAKEOFF` (at time of writing).
:::
+40 -48
View File
@@ -20,59 +20,52 @@ PX4 supports the [u-blox M8P](https://www.u-blox.com/en/product/neo-m8p), [u-blo
Таблиця вказує пристрої, які також виводять курсову відмітку, а також можуть надавати курсову відмітку, коли використовуються дві одиниці на транспортному засобі.
Він також відзначає пристрої, які підключаються через CAN шину, та ті, які підтримують PPK (пост-процесуальну кінематику).
| Пристрій | GPS | Компас | [DroneCAN] | [GPS Yaw] | PPK |
| :------------------------------------------------------------------------------------------------------------------- | :------------------: | :------: | :--------: | :---------------------------------: | :-: |
| [ARK G5 RTK GPS](../dronecan/ark_g5_rtk_gps.md) | [mosaic-G5 P3] | IIS2MDC | ✓ | | |
| [ARK G5 RTK HEADING GPS](../dronecan/ark_g5_rtk_heading_gps.md) | [mosaic-G5 P3H] | IIS2MDC | ✓ | [Heading Capability][mosaic-G5 P3H] | |
| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | | [Dual F9P] | |
| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | | |
| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | ✓ | [Septentrio Dual Antenna] | |
| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | IIS2MDC | | | |
| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | | | | |
| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P] | |
| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P] | |
| [CUAV C-RTK2 PPK/RTK GNSS](../gps_compass/rtk_gps_cuav_c-rtk.md) | F9P | RM3100 | | | |
| [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) | M8P | HMC5983 | | | |
| [CubePilot Here3 CAN GNSS GPS (M8N)](https://www.cubepilot.org/#/here/here3) | M8P | ICM20948 | ✓ | | |
| [Drotek SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | RM3100 | | [Dual F9P] | |
| [DATAGNSS NANO HRTK Receiver](../gps_compass/rtk_gps_datagnss_nano_hrtk.md) | [D10P] | IST8310 | | | |
| [DATAGNSS GEM1305 RTK Receiver](../gps_compass/rtk_gps_gem1305.md) | TAU951M | IST8310 | | | |
| [Femtones MINI2 Receiver](../gps_compass/rtk_gps_fem_mini2.md) | FB672, FB6A0 | ✓ | | | |
| [Freefly RTK GPS](../gps_compass/rtk_gps_freefly.md) | F9P | IST8310 | | | |
| [Holybro H-RTK ZED-F9P RTK Rover (DroneCAN variant)](../dronecan/holybro_h_rtk_zed_f9p_gps.md) | F9P | RM3100 | | [Dual F9P] | |
| [Holybro H-RTK ZED-F9P RTK Rover](https://holybro.com/collections/h-rtk-gps/products/h-rtk-zed-f9p-rover) | F9P | RM3100 | | [Dual F9P] | |
| [Holybro H-RTK F9P Ultralight](https://holybro.com/products/h-rtk-f9p-ultralight) | F9P | IST8310 | | [Dual F9P] | |
| [Holybro H-RTK F9P Helical or Base](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | [Dual F9P] | |
| [Holybro DroneCAN H-RTK F9P Helical](https://holybro.com/products/dronecan-h-rtk-f9p-helical) | F9P | BMM150 | | [Dual F9P] | |
| [Holybro H-RTK F9P Rover Lite](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | | |
| [Holybro DroneCAN H-RTK F9P Rover](https://holybro.com/products/dronecan-h-rtk-f9p-rover) | F9P | BMM150 | | [Dual F9P] | |
| [Holybro H-RTK M8P GNSS](../gps_compass/rtk_gps_holybro_h-rtk-m8p.md) | M8P | IST8310 | | | |
| [Holybro H-RTK Unicore UM982 GPS](../gps_compass/rtk_gps_holybro_unicore_um982.md) | UM982 | IST8310 | | [Unicore Dual Antenna] | |
| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | |
| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | |
| [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | ✓ | | [Dual F9P] | |
| [Navisys L1/L2 ZED-F9P RTK - Base only](https://www.navisys.com.tw/productdetail?name=GR901&class=RTK) | F9P | | | | |
| [RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | |
| [RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | |
| [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | [Septentrio Dual Antenna] | |
| [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | ✓ | | [Septentrio Dual Antenna] | |
| [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | [Dual F9P] | |
| [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | [Dual F9P] | |
| [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | ✓ | |
| Пристрій | GPS | Компас | [DroneCAN](../dronecan/index.md) | [GPS Yaw](#configuring-gps-as-yaw-heading-source) | PPK |
| :------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------: | :------: | :------------------------------: | :-----------------------------------------------: | :-: |
| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | ✓ | [Dual F9P][DualF9P] | |
| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | | |
| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | | [Septentrio Dual Antenna][SeptDualAnt] | |
| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | BMP390 | ✓ | | |
| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | | | | |
| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P][DualF9P] | |
| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P][DualF9P] | |
| [CUAV C-RTK2 PPK/RTK GNSS](../gps_compass/rtk_gps_cuav_c-rtk.md) | F9P | RM3100 | | | |
| [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) | M8P | HMC5983 | | | |
| [CubePilot Here3 CAN GNSS GPS (M8N)](https://www.cubepilot.org/#/here/here3) | M8P | ICM20948 | ✓ | | |
| [Drotek SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | RM3100 | | [Dual F9P][DualF9P] | |
| [DATAGNSS NANO HRTK Receiver](../gps_compass/rtk_gps_datagnss_nano_hrtk.md) | [D10P](https://docs.datagnss.com/gnss/gnss_module/D10P_RTK) | IST8310 | | | |
| [DATAGNSS GEM1305 RTK Receiver](../gps_compass/rtk_gps_gem1305.md) | TAU951M | IST8310 | | | |
| [Femtones MINI2 Receiver](../gps_compass/rtk_gps_fem_mini2.md) | FB672, FB6A0 | | | | |
| [Freefly RTK GPS](../gps_compass/rtk_gps_freefly.md) | F9P | IST8310 | | | |
| [Holybro H-RTK ZED-F9P RTK Rover (DroneCAN variant)](../dronecan/holybro_h_rtk_zed_f9p_gps.md) | F9P | RM3100 | ✓ | [Dual F9P][DualF9P] | |
| [Holybro H-RTK ZED-F9P RTK Rover](https://holybro.com/collections/h-rtk-gps/products/h-rtk-zed-f9p-rover) | F9P | RM3100 | | [Dual F9P][DualF9P] | |
| [Holybro H-RTK F9P Ultralight](https://holybro.com/products/h-rtk-f9p-ultralight) | F9P | IST8310 | | [Dual F9P][DualF9P] | |
| [Holybro H-RTK F9P Helical or Base](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | [Dual F9P][DualF9P] | |
| [Holybro DroneCAN H-RTK F9P Helical](https://holybro.com/products/dronecan-h-rtk-f9p-helical) | F9P | BMM150 | ✓ | [Dual F9P][DualF9P] | |
| [Holybro H-RTK F9P Rover Lite](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | | |
| [Holybro DroneCAN H-RTK F9P Rover](https://holybro.com/products/dronecan-h-rtk-f9p-rover) | F9P | BMM150 | | [Dual F9P][DualF9P] | |
| [Holybro H-RTK M8P GNSS](../gps_compass/rtk_gps_holybro_h-rtk-m8p.md) | M8P | IST8310 | | | |
| [Holybro H-RTK Unicore UM982 GPS](../gps_compass/rtk_gps_holybro_unicore_um982.md) | UM982 | IST8310 | | [Unicore Dual Antenna][UnicoreDualAnt] | |
| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | |
| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | |
| [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | | | [Dual F9P][DualF9P] | |
| [Navisys L1/L2 ZED-F9P RTK - Base only](https://www.navisys.com.tw/productdetail?name=GR901&class=RTK) | F9P | | | | |
| [RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | |
| [RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | |
| [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | [Septentrio Dual Antenna][SeptDualAnt] | |
| [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | | | [Septentrio Dual Antenna][SeptDualAnt] | ✓ |
| [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | [Dual F9P][DualF9P] | |
| [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | [Dual F9P][DualF9P] | |
| [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | | |
<!-- links used in above table -->
[RaccnLabL1L2ZED-F9P ext_ant]: https://docs.raccoonlab.co/guide/gps_mag_baro/gnss_external_antenna_f9p_v320.html
[RaccoonLab L1/L2 ZED-F9P]: https://docs.raccoonlab.co/guide/gps_mag_baro/gps_l1_l2_zed_f9p.html
[Dual F9P]: ../gps_compass/u-blox_f9p_heading.md
[Septentrio Dual Antenna]: ../gps_compass/septentrio.md#gnss-based-heading
[Unicore Dual Antenna]: ../gps_compass/rtk_gps_holybro_unicore_um982.md#enable-gps-heading-yaw
[DualF9P]: ../gps_compass/u-blox_f9p_heading.md
[SeptDualAnt]: ../gps_compass/septentrio.md#gnss-based-heading
[UnicoreDualAnt]: ../gps_compass/rtk_gps_holybro_unicore_um982.md#enable-gps-heading-yaw
[DATAGNSS GEM1305 RTK]: ../gps_compass/rtk_gps_gem1305.md
[DroneCAN]: ../dronecan/index.md
[GPS Yaw]: #configuring-gps-as-yaw-heading-source
[mosaic-G5 P3]: https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3
[mosaic-G5 P3H]: https://www.septentrio.com/en/products/gnss-receivers/gnss-receiver-modules/mosaic-G5-P3H
[D10P]: https://docs.datagnss.com/gnss/gnss_module/D10P_RTK
Примітки:
@@ -152,7 +145,6 @@ This should be set by default, but if not, follow the [MAVLink2 configuration in
![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png)
4. Після завершення опитування:
- The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle:
![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png)
+2 -4
View File
@@ -332,11 +332,9 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi
- [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT): Bridge time synchronization enable.
Клієнтський модуль uXRCE-DDS може синхронізувати мітку часу повідомлень, якими обмінюються через міст.
Це стандартна конфігурація. In certain situations, for example during [simulations](../ros2/user_guide.md#ros-gazebo-and-px4-time-synchronization), this feature may be disabled.
- [UXRCE_DDS_NS_IDX](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) <Badge type="tip" text="PX4 v1.17" />: Index-based namespace definition.
- <Badge type="tip" text="PX4 v1.17" /> [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX): Index-based namespace definition
Setting this parameter to any value other than `-1` creates a namespace with the prefix `uav_` and the specified value, e.g. `uav_0`, `uav_1`, etc.
See [namespace](#customizing-the-namespace) for methods to define richer or arbitrary namespaces.
- [`UXRCE_DDS_FLCTRL`](../advanced_config/parameter_reference.md#UXRCE_DDS_FLCTRL) <Badge type="tip" text="PX4 main" />: Serial port hardware flow control enable.
To use hardware flow control, a custom MicroXRCE Agent needs to be adopted. Please refer to [this PR](https://github.com/eProsima/Micro-XRCE-DDS-Agent/pull/407) for the required changes, cherry-pick them on top of the [agent version](#build-run-within-ros-2-workspace) you need to use and then run the agent with the additional `--flow-control` option.
:::info
Many ports are already have a default configuration.
@@ -441,7 +439,7 @@ PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500
:::
- A simple index-based namespace can be applied by setting the parameter [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) <Badge type="tip" text="PX4 v1.17" /> to a value between 0 and 9999.
- A simple index-based namespace can be applied by setting the parameter [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to a value between 0 and 9999.
This will generate a namespace such as `/uav_0`, `/uav_1`, and so on.
This technique is ideal if vehicles must be persistently associated with namespaces because their clients are automatically started through PX4.
+1 -5
View File
@@ -89,19 +89,15 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too
```
:::tip
The main function must be named `<module_name>_main` and exported from the module as shown.
:::
:::tip
`PX4_INFO` is the equivalent of `printf` for the PX4 shell (included from **px4_platform_common/log.h**).
There are different log levels: `PX4_INFO`, `PX4_WARN`, `PX4_ERR`, `PX4_DEBUG`.
Warnings and errors are additionally added to the [ULog](../dev_log/ulog_file_format.md) and shown on [Flight Review](https://logs.px4.io/).
:::
3. Create and open a new _cmake_ definition file named **CMakeLists.txt**.
@@ -170,7 +166,7 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too
4. Create and open a new _Kconfig_ definition file named **Kconfig** and define your symbol for naming (see [Kconfig naming convention](../hardware/porting_guide_config.md#px4-kconfig-symbol-naming-convention)).
Скопіюйте текст нижче:
```text
```
menuconfig EXAMPLES_PX4_SIMPLE_APP
bool "px4_simple_app"
default n
-21
View File
@@ -1,21 +0,0 @@
# Neural Network Control
PX4 supports the following mechanisms for using neural networks for multirotor control:
- [MC Neural Networks Control](../neural_networks/mc_neural_network_control.md)<Badge type="warning" text="Experimental" /> — A generic neural network module that you can modify to use different underlying neural network and training models and compile into the firmware.
- [RAPTOR: A Neural Network Module for Adaptive Quadrotor Control](../neural_networks/raptor.md)<Badge type="warning" text="Experimental" /> — An adaptive RL NN module that works well with different Quad configurations without additional training.
Generally you will select the former if you wish to experiment with custom neural network architectures and train them using PyTorch or TensorFlow, and the latter if you want to use a pre-trained neural-network controller that works out-of-the-box (without training for your particular platform) or if you train your own policies using [RLtools](https://rl.tools).
Note that both modules are experimental and provided for experimentation.
The table below provides more detail on the differences.
| Use Case | [`mc_raptor`](../neural_networks/raptor.md) | [`mc_nn_control`](../neural_networks/mc_neural_network_control.md) |
| ---------------------------------------------------------------- | ------------------------------------------- | ------------------------------------------------------------------ |
| Pre-trained policy that adapts to any quadrotor without training | ✓ RAPTOR | ✘ |
| Train policy in PyTorch/TF | ✘ | ✓ TF Lite |
| Train policy in RLtools | ✓ | ✘ |
| Use manual control (remote) with NN policy | ✘ GPS/MoCap | ✓ Manual attitude commands |
| Load policy checkpoints from SD card | ✓ Upload via MAVLink FTP | ✘ Compiled into firmware |
| Offboard setpoints | ✓ MAVLink | ✘ |
| Internal Trajectory Generator | ✓ (Position, Lissajous) | ✘ |
@@ -1,123 +0,0 @@
# MC Neural Networks Control
<Badge type="tip" text="PX4 v1.17" /> <Badge type="warning" text="Experimental" />
:::warning
This is an experimental module.
Use at your own risk.
:::
The Multicopter Neural Network (NN) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) is an example module that allows you to experiment with using a pre-trained neural network on PX4.
It might be used, for example, to experiment with controllers for non-traditional drone morphologies, computer vision tasks, and so on.
The module integrates a pre-trained neural network based on the [TensorFlow Lite Micro (TFLM)](./tflm.md) module.
The module is trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md) multicopter frame.
While the controller is fairly robust, and might work on other platforms, we recommend [Training your own Network](#training-your-own-network) if you use a different vehicle.
Note that after training the network you will need to update and rebuild PX4.
TLFM is a mature inference library intended for use on embedded devices.
It has support for several architectures, so there is a high likelihood that you can build it for the board you want to use.
If not, there are other possible NN frameworks, such as [Eigen](https://eigen.tuxfamily.org/index.php?title=Main_Page) and [Executorch](https://pytorch.org/executorch-overview).
This document explains how you can include the module in your PX4 build, and provides a broad overview of how it works.
The other documents in the section provide more information about the integration, allowing you to replace the NN with a version trained on different data, or even to replace the TLFM library altogether.
:::tip
For more information, see the Masters thesis from which this module was created: [Deep Reinforcement Learning for Embedded Control Policies for Aerial Vehicles](https://nva.sikt.no/registration/019b26689144-efeebae8-84d6-4413-ad7f-9aceb4ff7374).
In addition, the (Norwegian) website [A Neural Network Mode for PX4 on Embedded Flight Controllers](https://ntnu-arl.github.io/px4-nns/) has a youtube video and a workshop paper .
:::
## Neural Network PX4 Firmware
:::warning
This module requires Ubuntu 24.04 or newer (it is not supported in Ubuntu 22.04).
:::
The module has been tested on a number of configurations, which can be build locally using the commands:
```sh
make px4_sitl_neural
```
```sh
make px4_fmu-v6c_neural
```
```sh
make mro_pixracerpro_neural
```
You can add the module to other board configurations by modifying their `default.px4board file` configuration to include these lines:
```sh
CONFIG_LIB_TFLM=y
CONFIG_MODULES_MC_NN_CONTROL=y
```
:::tip
The `mc_nn_control` module takes up roughly 50KB, and many of the `default.px4board file` are already close to filling all the flash on their boards. To make room for the neural control module you can remove the include statements for other modules, such as FW, rover, VTOL and UUV.
:::
## Example Module Overview
The example module replaces the entire controller structure as well as the control allocator, as shown in the diagram below:
![neural_control](../../assets/advanced/neural_control.png)
In the [controller diagram](../flight_stack/controller_diagrams.md) you can see the [uORB message](../middleware/uorb.md) flow.
We hook into this flow by subscribing to messages at particular points, using our neural network to calculate outputs, and then publishing them into the next point in the flow.
We also need to stop the module publishing the topic to be replaced, which is covered in [Neural Network Module: System Integration](nn_module_utilities.md)
### Вхід
The input can be changed to whatever you want.
Set up the input you want to use during training and then provide the same input in PX4.
In the Neural Control module the input is an array of 15 numbers, and consists of these values in this order:
- [3] Local position error. (goal position - current position)
- [6] The first 2 rows of a 3 dimensional rotation matrix.
- [3] Linear velocity
- [3] Angular velocity
All the input values are collected from uORB topics and transformed into the correct representation in the `PopulateInputTensor()` function.
PX4 uses the NED frame representation, while the Aerial Gym Simulator, in which the NN was trained, uses the ENU representation.
Therefore two rotation matrices are created in the function and all the inputs are transformed from the NED representation to the ENU one.
![ENU-NED](../../assets/advanced/ENU-NED.png)
ENU and NED are just rotation representations, the translational difference is only there so both can be seen in the same figure.
### Output
The output consists of 4 values, the motor forces, one for each motor.
These are transformed in the `RescaleActions()` function.
This is done because PX4 expects normalized motor commands while the Aerial Gym Simulator uses physical values.
So the output from the network needs to be normalized before they can be sent to the motors in PX4.
The commands are published to the [ActuatorMotors](../msg_docs/ActuatorMotors.md) topic.
The publishing is handled in `PublishOutput(float* command_actions)` function.
:::tip
If the neural control mode is too aggressive or unresponsive the [MC_NN_THRST_COEF](../advanced_config/parameter_reference.md#MC_NN_THRST_COEF) parameter can be tuned.
Decrease it for more thrust.
:::
## Training your own Network
The network is currently trained for the [X500 V2](../frames_multicopter/holybro_x500v2_pixhawk6c.md).
But the controller is somewhat robust, so it could work directly on other platforms, but performing system identification and training a new network is recommended.
Since the Aerial Gym Simulator is open-source you can download it and train your own networks as long as you have access to an NVIDIA GPU.
If you want to train a control network optimized for your platform you can follow the instructions in the [Aerial Gym Documentation](https://ntnu-arl.github.io/aerial_gym_simulator/9_sim2real/).
You should do one system identification flight for this and get an approximate inertia matrix for your platform.
On the `sys-id` flight you need ESC telemetry, you can read more about that in [DSHOT](../peripherals/dshot.md).
Then do the following steps:
- Do a hover flight
- Read of the logs what RPM is required for the drone to hover.
- Use the weight of each motor, length of the motor arms, total weight of the platform with battery to calculate an approximate inertia matrix for the platform.
- Insert these values into the Aerial Gym configuration and train your network.
- Convert the network as explained in [TFLM](tflm.md).
@@ -1,86 +0,0 @@
# 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)](./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) message's 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
```
-221
View File
@@ -1,221 +0,0 @@
# RAPTOR: A Neural Network Module for Adaptive Quadrotor Control
<Badge type="tip" text="main (planned for PX4 v1.18)" /> <Badge type="info" text="Multicopter" /> <Badge type="warning" text="Experimental" />
:::warning
This is an experimental module.
Use at your own risk.
:::
RAPTOR is a tiny reinforcement-learning based neural network module for quadrotor control that can be used to control a wide variety of quadrotors without retuning.
This topic provides an overview of the fundamental concepts, and explains how you can use the module in simulation and real hardware.
## Загальний огляд
![Visual Abstract](../../assets/advanced/neural_networks/raptor/visual_abstract.jpg)
RAPTOR is an adaptive policy for end-to-end quadrotor control.
It is motivated by the human ability to adapt learned behaviours to similar situations.
For example, while humans may initially require many hours of driving experience to be able to smoothly control the car and blend into traffic, when faced with a new vehicle they do not need to re-learn how to drive — they only need to experience a few rough braking/acceleration/steering responses to adjust their previously learned behavior.
Reinforcement Learning (RL) is a machine learning technique that uses trial and error to learn decision making/control behaviors, which is similar to the way that humans learn to drive.
RL is interesting for controlling robots (and particularly UAVs) because it overcomes some fundamental limitations of classic, modular control architectures (information loss at module boundaries, requirement for expert tuning, etc).
RL has been very successful in [high-performance quadrotor flight](https://doi.org/10.1038/s41586-023-06419-4), but previous designs have not been particularly adaptable to new frames and vehicle types.
RAPTOR fills this gap and demonstrates a single, tiny neural-network control policy that can control a wide variety of quadrotors (tested on real quadrotors from 32 g to 2.4 kg).
For more details please refer to this video:
<lite-youtube videoid="hVzdWRFTX3k" title="RAPTOR: A Foundation Policy for Quadrotor Control"/>
The method we developed for training the RAPTOR policy is called Meta-Imitation Learning:
![Diagram showing the Method Overview](../../assets/advanced/neural_networks/raptor/method.jpg)
You can torture test the RAPTOR policy in your browser at [https://raptor.rl.tools](https://raptor.rl.tools) or in the embedded app here:
<iframe src="https://raptor.rl.tools?raptor=false" width="100%" height="1000" style="border: none;"></iframe>
For more information please refer to the paper at [https://arxiv.org/abs/2509.11481](https://arxiv.org/abs/2509.11481).
## Структура
The RAPTOR control policy is an end-to-end policy that takes position, orientation, linear velocity and angular velocity as inputs and outputs motor commands (`actuator_motors`).
To integrate it into PX4 we use the external mode registration facilities in PX4 (which also works well for internal modes as demonstrated in `mc_nn_control`).
Because of this architecture the `mc_raptor` module is completely decoupled from all other PX4 logic.
By default, the RAPTOR module expects setpoints via `trajectory_setpoint` messages.
If no `trajectory_setpoint` messages are received or if no `trajectory_setpoint` is received within 200 ms, the current position and orientation (with zero velocity) is used as the setpoint.
Since feeding setpoints reliably via telemetry is still a challenge, we also implement a simple option to generate internal reference trajectories (controlled through the `MC_RAPTOR_INTREF` parameter) for demonstration and benchmarking purposes.
## Функції
- Tiny neural network (just 2084 parameters) => minimal CPU usage
- Easily maintainable
- Simple CMake setup
- Self-contained (no interference with other modules)
- Single, simple and well-maintained dependency (RLtools)
- Loading neural network parameters from SD card
- Minimal flash usage (for possible inclusion into default build configurations)
- Easy development: Train new neural network and just upload it via MAVLink FTP without requiring to re-flash the firmware
- Tested on 10+ different real platforms (including flexible frames, brushed motors)
- Actively developed and maintained
## Використання
### SITL
Build PX4 SITL with Raptor, disable QGC requirement, and adjust the `IMU_GYRO_RATEMAX` to match the simulation IMU rate
```sh
make px4_sitl_raptor gz_x500
param set NAV_DLL_ACT 0
param set COM_DISARM_LAND -1 # When taking off in offboard the landing detector can cause mid-air disarms
param set IMU_GYRO_RATEMAX 250 # Just for SITL. Tested with IMU_GYRO_RATEMAX=400 on real FCUs
param set MC_RAPTOR_ENABLE 1 # Enable the mc_raptor module
param save
```
Upload the RAPTOR checkpoint to the "SD card": Separate terminal
```bash
mavproxy.py --master udp:127.0.0.1:14540
ftp mkdir /raptor # for the real FMU use: /fs/microsd/raptor
ftp put src/modules/mc_raptor/blob/policy.tar /raptor/policy.tar
```
Restart (<kbd>Ctrl+C</kbd>)
```sh
make px4_sitl_raptor gz_x500
commander takeoff
commander status
```
Note the external mode ID of `RAPTOR` in the status report
```sh
commander mode ext{RAPTOR_MODE_ID}
```
#### Internal Reference Trajectory Generation
In our experience, feeding the `trajectory_setpoint` via MAVLink (even via WiFi telemetry) is unreliable.
But we do not want to constrain this module to only platforms that have a companion board.
For this reason we have integrated a simple internal reference trajectory generator for testing and benchmarking purposes.
It supports position (constant position and yaw setpoint) as well as configurable [Lissajous trajectories](https://en.wikipedia.org/wiki/Lissajous_curve).
The Lissajous generator can, for example, generate smooth figure-eight trajectories that contain interesting accelerations for benchmarking and testing purposes.
Please refer to the embedded configurator later in this section to explore the Lissajous parameters and view the resulting trajectories.
To use the internal reference generator, select the mode: `0`: Off/activation position tracking, `1`: Lissajous
```sh
param set MC_RAPTOR_INTREF 1
```
Restart (ctrl+c)
```sh
commander takeoff
commander mode ext{RAPTOR_MODE_ID}
mc_raptor intref lissajous 0.5 1 0 2 1 1 10 3
```
The trajectory is relative to the position and yaw of the vehicle at the point where the RAPTOR mode is activated (or the position and yaw where the parameters are changed if it is already activated).
You can adjust the parameters of the trajectory with the following tool.
Make sure to copy the generated CLI string at the end:
<iframe src="https://rl-tools.github.io/mc-raptor-trajectory-tool" width="100%" height="1700" style="border: none;"></iframe>
### Real-World
#### Установка
The `mc_raptor` module has been mostly tested with the Holybro X500 V2 but it should also work out-of-the-box with other platforms (see the [Other Platforms](#other-platforms) section).
```sh
make px4_fmu-v6c_raptor upload
```
We recommend initially testing the RAPTOR mode using a dead man's switch.
For this we configure the mode selection to be connected to a push button or a switch with a spring that automatically switches back.
In the default position we configure e.g. `Stabilized Mode` and in the pressed configuration we select `External Mode 1` (since the name of the external mode is only transmitted at runtime).
This allows to take off manually and then just trigger the RAPTOR mode for a split-second to see how it behaves.
In our experiments it has been exceptionally stable (zero crashes) but we still think progressively activating it for longer is the safest way to build confidence.
:::warning
Make sure that your platform uses the standard PX4 quadrotor motor layout:
1: front-right, 2: back-left, 3: front-left, 4: back-right
:::
##### Other Platforms
To enable the `mc_raptor` module in other platforms, just add `CONFIG_MODULES_MC_RAPTOR=y` and `CONFIG_LIB_RL_TOOLS=y`
```diff
+++ b/boards/px4/fmu-v6c/raptor.px4board
@@ -35,2 +35,3 @@
CONFIG_DRIVERS_UAVCAN=y
+CONFIG_LIB_RL_TOOLS=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
@@ -64,2 +65,3 @@
CONFIG_MODULES_MC_POS_CONTROL=y
+CONFIG_MODULES_MC_RAPTOR=y
CONFIG_MODULES_MC_RATE_CONTROL=y
```
#### Results
Even though there were moderate winds (~ 5 m/s) during the test, we found good figure-eight tracking performance at velocities up to 12 m/s:
![Lissajous](../../assets/advanced/neural_networks/raptor/results_figure_eight.svg)
We also tested the linear velocity in a straight line and found that the RAPTOR policy can reliably fly at > 17 m/s (the wind direction was orthogonal to the line):
![Linear Oscillation](../../assets/advanced/neural_networks/raptor/results_line.svg)
### Усунення проблем
#### Логування
Use this logging configuration to log all relevant topics at maximum rate:
```sh
cat > logger_topics.txt << EOF
raptor_status 0
raptor_input 0
trajectory_setpoint 0
vehicle_local_position 0
vehicle_angular_velocity 0
vehicle_attitude 0
vehicle_status 0
actuator_motors 0
EOF
```
Use mavproxy FTP to upload it:
```sh
mavproxy.py
```
##### Real
```sh
ftp mkdir /fs/microsd/etc
ftp mkdir /fs/microsd/etc/logging
ftp put logger_topics.txt /fs/microsd/etc/logging/logger_topics.txt
```
##### SITL
```sh
ftp mkdir etc
ftp mkdir logging
ftp put logger_topics.txt etc/logging/logger_topics.txt
```
-77
View File
@@ -1,77 +0,0 @@
# TensorFlow Lite Micro (TFLM)
The PX4 [MC Neural Networks Control](../neural_networks/mc_neural_network_control.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 [MC Neural Networks Control](../neural_networks/mc_neural_network_control.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
@@ -11,7 +11,7 @@ PX4 traffic avoidance works with ADS-B or FLARM products that supply transponder
Було протестовано з наступними пристроями:
- [PingRX ADS-B Receiver](https://uavionix.com/product/pingrx-pro/) (uAvionix)
- [FLARM](https://www.flarm.com/en/drones/)
- [FLARM](https://flarm.com/products/uav/atom-uav-flarm-for-drones/) <!-- I think originally https://flarm.com/products/powerflarm/uav/ -->
## Налаштування програмного забезпечення
-1
View File
@@ -151,7 +151,6 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### uXRCE-DDS / ROS2
- [PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113): <Badge type="warning" text="Experimental"/> [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically
- <Badge type="warning" text="Experimental"/>[PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md).
- dds_topics: add vtol_vehicle_status ([PX4-Autopilot#24582](https://github.com/PX4/PX4-Autopilot/pull/24582))
- dds_topics: add home_position ([PX4-Autopilot#24583](https://github.com/PX4/PX4-Autopilot/pull/24583))
-134
View File
@@ -1,134 +0,0 @@
# PX4-Autopilot v1.17.0 Release Notes
<Badge type="danger" text="Alpha/Beta" />
<script setup>
import { useData } from 'vitepress'
const { site } = useData();
</script>
<div v-if="site.title !== 'PX4 Guide (main)'">
<div class="custom-block danger">
<p class="custom-block-title">This page is on a release branch, and hence probably out of date. <a href="https://docs.px4.io/main/en/releases/main.html">See the latest version</a>.</p>
</div>
</div>
This contains changes to PX4 planned for PX4 v1.17 (since the last major release [PX v1.16](../releases/1.16.md)).
:::warning
PX4 v1.17 is in alpha/beta testing.
Update these notes with features that are going to be in PX4 v1.17 release.
New features that are not expected to go into the v1.17 release are in [PX4-Autopilot `main` Release Notes](../releases/main.md).
:::
## Прочитайте перед оновленням
TBD …
Please continue reading for [upgrade instructions](#upgrade-guide).
## Основні зміни
- Уточнюється
## Інструкції для оновлення
## Інші зміни
### Підтримка обладнання
- **[New Hardware]** boards: [MicoAir743-Lite FC](../flight_controller/micoair743-lite.md) <!-- CHECK is this version and add PR link (or fix up doc version tag and move this) -->
- **[New Hardware]** boards: [RadiolinkPIX6 FC](../flight_controller/radiolink_pix6.md) <!-- CHECK is this version and add PR! -->
- **[New Hardware]** boards: [AP-H743-R1 FC](../flight_controller/x-mav_ap-h743r1.md) <!-- CHECK is this version and add PR! -->
<!--
### Common
- [QGroundControl Bootloader Update](../advanced_config/bootloader_update.md#qgc-bootloader-update-sys-bl-update) via the [SYS_BL_UPDATE](../advanced_config/parameter_reference.md#SYS_BL_UPDATE) parameter has been re-enabled after being broken for a number of releases. ([PX4-Autopilot#25032: build: romf: fix generation of rc.board_bootloader_upgrade](https://github.com/PX4/PX4-Autopilot/pull/25032)).
-->
### Управління
<!--
- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW).
For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
-->
- <Badge type="warning" text="Experimental" /> [MC Neural Network Module](../advanced/neural_networkss.md)
### Оцінки
- Уточнюється
<!--
### Sensors
- Add [sbgECom INS driver](../sensor/sbgecom.md) ([PX4-Autopilot#24137](https://github.com/PX4/PX4-Autopilot/pull/24137))
- Quick magnetometer calibration now supports specifying an arbitrary initial heading ([PX4-Autopilot#24637](https://github.com/PX4/PX4-Autopilot/pull/24637))
-->
### Симуляція
- Overhaul rover simulation:
- Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107)
- Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113)
- Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117)
- [Simulation-in-Hardware (SIH)](../sim_sih/index.md#compatibility) <!-- Listed in https://docs.px4.io/main/en/sim_sih/#compatibility : Check the PRs -->
- New simulation: MC Hexacopter X
- New simulation: Ackermann Rover
### Debug & Logging
- Уточнюється
### Ethernet
- Уточнюється
### uXRCE-DDS / Zenoh / ROS2
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)).
- [UXRCE_DDS: Simple index based namespace (UXRCE_DDS_NS_IDX)](../middleware/uxrce_dds.md#customizing-the-namespace)
- [Zenoh (PX4 ROS 2 rmw_zenoh)](../middleware/zenoh.md)
### MAVLink
- Уточнюється
<!--
### RC
- Parse ELRS Status and Link Statistics TX messages in the CRSF parser.
### Multi-Rotor
- Removed parameters `MPC_{XY/Z/YAW}_MAN_EXPO` and use default value instead, as they were not deemed necessary anymore. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
- Renamed `MPC_HOLD_DZ` to `MAN_DEADZONE` to have it globally available in modes that allow for a dead zone. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
-->
### VTOL
- Уточнюється
### Літак з фіксованим крилом
- [Fixed Wing Takeoff mode](../flight_modes_fw/takeoff.md) will now keep climbing with level wings on position loss.
A target takeoff waypoint can be set to control takeoff course and loiter altitude. ([PX4-Autopilot#25083](https://github.com/PX4/PX4-Autopilot/pull/25083)).
- Automatically suppress angular rate oscillations using [Gain compression](../features_fw/gain_compression.md). ([PX4-Autopilot#25840: FW rate control: add gain compression algorithm](https://github.com/PX4/PX4-Autopilot/pull/25840))
### Ровер
- Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)).
- Add support for [Apps & API](../flight_modes_rover/api.md) including [Rover Setpoints](../ros2/px4_ros2_control_interface.md#rover-setpoints) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)).
- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details).
### ROS 2
- Уточнюється
+1 -2
View File
@@ -2,8 +2,7 @@
Перелік PX4 реліз, вони містять список змін, що відбулися в кожному релізі, пояснення включених функцій, виправлень, застарілих та оновлень.
- [main](../releases/main.md) (changes planned for v1.18 or later)
- [v1.17](../releases/1.17.md) (changes planned for v1.17, since v1.16)
- [main](../releases/main.md) (changes since v1.16)
- [v1.16](../releases/1.16.md)
- [v1.15](../releases/1.15.md)
- [v1.14](../releases/1.14.md)
+6 -30
View File
@@ -16,13 +16,13 @@ const { site } = useData();
This contains changes to PX4 `main` branch since the last major release ([PX v1.16](../releases/1.16.md)).
:::warning
PX4 v1.17 is in alpha/beta testing.
Update these notes with features that are going to be in `main` (PX4 v1.18 or later) but not the PX4 v1.17 release.
PX4 v1.16 is in candidate-release testing, pending release.
Update these notes with features that are going to be in `main` but not the PX4 v1.16 release.
:::
## Прочитайте перед оновленням
- TBD …
TBD …
Please continue reading for [upgrade instructions](#upgrade-guide).
@@ -45,7 +45,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Управління
- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW).
For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)).
For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. (PX4-Autopilot#25435: Add new flight mode: Altitude Cruise
).
### Оцінки
@@ -58,34 +59,19 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Симуляція
- Уточнюється
<!-- MOVED THIS TO v1.17
- Overhaul rover simulation:
- Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107)
- Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113)
- Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117)
-->
### Debug & Logging
- [Asset Tracking](../debug/asset_tracking.md): Automatic tracking and logging of external device information including vendor name, firmware and hardware version, serial numbers. Currently supports DroneCAN devices. ([PX4-Autopilot#25617](https://github.com/PX4/PX4-Autopilot/pull/25617))
### Ethernet
- Уточнюється
### uXRCE-DDS / Zenoh / ROS2
- Уточнюється
<!-- MOVED THIS TO v1.17
### uXRCE-DDS / ROS2
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)).
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md).
-->
### MAVLink
@@ -106,26 +92,16 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Літак з фіксованим крилом
- Уточнюється
<!-- MOVED THIS TO v1.17
- [Fixed Wing Takeoff mode](../flight_modes_fw/takeoff.md) will now keep climbing with level wings on position loss.
A target takeoff waypoint can be set to control takeoff course and loiter altitude. ([PX4-Autopilot#25083](https://github.com/PX4/PX4-Autopilot/pull/25083)).
- Automatically suppress angular rate oscillations using [Gain compression](../features_fw/gain_compression.md). ([PX4-Autopilot#25840: FW rate control: add gain compression algorithm](https://github.com/PX4/PX4-Autopilot/pull/25840))
-->
### Ровер
- Уточнюється
<!-- MOVED THIS TO v1.17
- Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)).
- Add support for [Apps & API](../flight_modes_rover/api.md) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)).
- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details).
-->
### ROS 2
- Уточнюється
+6 -12
View File
@@ -14,7 +14,7 @@ At the time of writing, parts of the PX4 ROS 2 Control Interface are experimenta
:::
The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) is a C++ library (with Python bindings) that simplifies controlling PX4 from ROS 2.
[PX4 ROS 2 Interface бібліотека](../ros2/px4_ros2_interface_lib.md) - це бібліотека C++++, яка спрощує контроль PX4 з ROS 2.
Розробники використовують бібліотеку для створення і динамічної реєстрації режимів, написаних за допомогою ROS 2.
Ці режими динамічно реєструються в PX4 і здаються частиною PX4 для наземної станції або іншої зовнішньої системи.
@@ -26,12 +26,6 @@ The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) is a C++ li
PX4 ROS 2 modes are easier to implement and maintain than PX4 internal modes, and provide more resources for developers in terms of processing power and pre-existing libraries.
Unless the mode is safety-critical, requires strict timing or very high update rates, or your vehicle doesn't have a companion computer, you should [consider using PX4 ROS 2 modes in preference to PX4 internal modes](../concept/flight_modes.md#internal-vs-external-modes).
:::tip
If you want to use Python, check out the [examples in the repository](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/python).
Not all classes have Python bindings yet — the [supported bindings are here](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_py/src/px4_ros2).
You are welcome to add and contribute missing classes.
:::
## Загальний огляд
Ця діаграма надає концептуального уявлення про те, як режими інтерфейсу і режими керування будуть взаємодіяти з PX4.
@@ -352,9 +346,9 @@ private:
Наступні розділи надають список підтримуваних типів установок:
- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): <Badge type="warning" text="MC only" /> Smooth position and (optionally) heading control
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="warning" text="FW only" /> <Badge type="tip" text="PX4 v1.17" /> Direct control of lateral and longitudinal fixed wing dynamics
- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): <Badge type="warning" text="FW only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct control of lateral and longitudinal fixed wing dynamics
- DirectActuatorsSetpointType: Пряме керування моторами та установками сервоприводів польотних поверхонь
- [Rover Setpoints](#rover-setpoints): <Badge type="tip" text="PX4 v1.17" /> Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering).
- [Rover Setpoints](#rover-setpoints): <Badge type="tip" text="main (planned for: PX4 v1.17)" /> Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering).
:::tip
The other setpoint types are currently experimental, and can be found in: [px4_ros2/control/setpoint_types/experimental](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental).
@@ -421,7 +415,7 @@ _goto_setpoint->update(
#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType)
<Badge type="warning" text="Fixed wing only" /> <Badge type="tip" text="PX4 v1.17" />
<Badge type="warning" text="Fixed wing only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" />
:::info
This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode.
@@ -563,7 +557,7 @@ and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX).
#### Rover Setpoints
<Badge type="tip" text="PX4 v1.17" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
The rover modules use a hierarchical structure to propagate setpoints:
@@ -597,7 +591,7 @@ An example for a rover specific drive mode using the `RoverSpeedAttitudeSetpoint
### Controlling a VTOL
<Badge type="tip" text="PX4 v1.17" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration:
+1 -1
View File
@@ -7,7 +7,7 @@
На момент написання цієї статті, деякі частини бібліотеки інтерфейсу PX4 ROS 2 є експериментальними і, отже, можуть бути змінені.
:::
The [PX4 ROS 2 Interface Library](https://github.com/Auterion/px4-ros2-interface-lib) is a C++ library (with Python bindings) that simplifies controlling and interacting with PX4 from ROS 2.
[PX4 ROS 2 Інтерфейс бібліотеки](https://github.com/Auterion/px4-ros2-interface-lib) є бібліотекою C+++, яка спрощує контроль і взаємодіє з PX4 з ROS 2.
The library provides three high-level interfaces for developers:

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